drivers device naming consistency

This commit is contained in:
Daniel Agar 2017-11-18 12:45:16 -05:00 committed by Lorenz Meier
parent 53595bac0e
commit 8738fe8daf
10 changed files with 232 additions and 160 deletions

View File

@ -31,42 +31,33 @@
#
############################################################################
set(SRCS)
list(APPEND SRCS
CDev.cpp
ringbuffer.cpp
integrator.cpp
)
include_directories(${CMAKE_CURRENT_SOURCE_DIR})
if(${OS} STREQUAL "nuttx")
include_directories(nuttx)
list(APPEND SRCS
set(SRCS_PLATFORM)
if (${OS} STREQUAL "nuttx")
list(APPEND SRCS_PLATFORM
nuttx/cdev_platform.cpp
)
if ("${CONFIG_I2C}" STREQUAL "y")
list(APPEND SRCS nuttx/i2c_nuttx.cpp)
list(APPEND SRCS_PLATFORM nuttx/I2C.cpp)
endif()
if ("${CONFIG_SPI}" STREQUAL "y")
list(APPEND SRCS nuttx/spi.cpp)
list(APPEND SRCS_PLATFORM nuttx/SPI.cpp)
endif()
else()
include_directories(posix)
list(APPEND SRCS
list(APPEND SRCS_PLATFORM
posix/I2C.cpp
posix/cdev_platform.cpp
posix/vfile.cpp
posix/i2c_posix.cpp
)
endif()
px4_add_module(
MODULE drivers__device
SRCS ${SRCS}
SRCS
CDev.cpp
ringbuffer.cpp
integrator.cpp
${SRCS_PLATFORM}
DEPENDS
platforms__common
)

View File

@ -33,7 +33,7 @@
#pragma once
#ifdef __PX4_NUTTX
#include "nuttx/i2c_nuttx.h"
#include "nuttx/I2C.hpp"
#else
#include "posix/i2c_posix.h"
#include "posix/I2C.hpp"
#endif

View File

@ -40,7 +40,7 @@
* that is supplied. Should we just depend on the bus knowing?
*/
#include "i2c.h"
#include "I2C.hpp"
namespace device
{

View File

@ -45,9 +45,10 @@
* non-interrupt-mode client.
*/
#include "SPI.hpp"
#include <px4_config.h>
#include <nuttx/arch.h>
#include "spi.h"
#ifndef CONFIG_SPI_EXCHANGE
# error This driver requires CONFIG_SPI_EXCHANGE
@ -128,13 +129,6 @@ out:
return ret;
}
int
SPI::probe()
{
// assume the device is too stupid to be discoverable
return OK;
}
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
@ -170,12 +164,6 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
return result;
}
void
SPI::set_frequency(uint32_t frequency)
{
_frequency = frequency;
}
int
SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
{

View File

@ -0,0 +1,153 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file spi.h
*
* Base class for devices connected via SPI.
*/
#ifndef _DEVICE_SPI_H
#define _DEVICE_SPI_H
#include "../CDev.hpp"
#include <px4_spi.h>
namespace device __EXPORT
{
/**
* Abstract class for character device on SPI
*/
class __EXPORT SPI : public CDev
{
protected:
/**
* Constructor
*
* @param name Driver name
* @param devname Device node name
* @param bus SPI bus on which the device lives
* @param device Device handle (used by SPI_SELECT)
* @param mode SPI clock/data mode
* @param frequency SPI clock frequency
*/
SPI(const char *name,
const char *devname,
int bus,
uint32_t device,
enum spi_mode_e mode,
uint32_t frequency);
virtual ~SPI();
/**
* Locking modes supported by the driver.
*/
enum LockMode {
LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
};
virtual int init();
/**
* Check for the presence of the device on the bus.
*/
virtual int probe() { return PX4_OK; }
/**
* Perform a SPI transfer.
*
* If called from interrupt context, this interface does not lock
* the bus and may interfere with non-interrupt-context callers.
*
* Clients in a mixed interrupt/non-interrupt configuration must
* ensure appropriate interlocking.
*
* At least one of send or recv must be non-null.
*
* @param send Bytes to send to the device, or nullptr if
* no data is to be sent.
* @param recv Buffer for receiving bytes from the device,
* or nullptr if no bytes are to be received.
* @param len Number of bytes to transfer.
* @return OK if the exchange was successful, -errno
* otherwise.
*/
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
/**
* Set the SPI bus frequency
* This is used to change frequency on the fly. Some sensors
* (such as the MPU6000) need a lower frequency for setup
* registers and can handle higher frequency for sensor
* value registers
*
* @param frequency Frequency to set (Hz)
*/
void set_frequency(uint32_t frequency) { _frequency = frequency; }
/**
* Set the SPI bus locking mode
*
* This set the SPI locking mode. For devices competing with NuttX SPI
* drivers on a bus the right lock mode is LOCK_THREADS.
*
* @param mode Locking mode
*/
void set_lockmode(enum LockMode mode) { locking_mode = mode; }
LockMode locking_mode; /**< selected locking mode */
private:
uint32_t _device;
enum spi_mode_e _mode;
uint32_t _frequency;
struct spi_dev_s *_dev;
/* this class does not allow copying */
SPI(const SPI &);
SPI operator=(const SPI &);
protected:
int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
bool external() { return px4_spi_bus_external(get_device_bus()); }
};
} // namespace device
#endif /* _DEVICE_SPI_H */

View File

@ -40,7 +40,7 @@
* that is supplied. Should we just depend on the bus knowing?
*/
#include "i2c_posix.h"
#include "I2C.hpp"
#ifdef __PX4_LINUX
#include <linux/i2c.h>

View File

@ -0,0 +1,54 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file spi.h
*
* Base class for devices connected via SPI.
*/
#ifndef _DEVICE_SPI_H
#define _DEVICE_SPI_H
#include "CDev.hpp"
#include <px4_spi.h>
namespace device __EXPORT
{
// TODO: implement posix spi
} // namespace device
#endif /* _DEVICE_SPI_H */

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -30,124 +30,10 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/**
* @file spi.h
*
* Base class for devices connected via SPI.
*/
#ifndef _DEVICE_SPI_H
#define _DEVICE_SPI_H
#include "device.h"
#include <px4_spi.h>
namespace device __EXPORT
{
/**
* Abstract class for character device on SPI
*/
class __EXPORT SPI : public CDev
{
protected:
/**
* Constructor
*
* @param name Driver name
* @param devname Device node name
* @param bus SPI bus on which the device lives
* @param device Device handle (used by SPI_SELECT)
* @param mode SPI clock/data mode
* @param frequency SPI clock frequency
*/
SPI(const char *name,
const char *devname,
int bus,
uint32_t device,
enum spi_mode_e mode,
uint32_t frequency);
virtual ~SPI();
/**
* Locking modes supported by the driver.
*/
enum LockMode {
LOCK_PREEMPTION, /**< the default; lock against all forms of preemption. */
LOCK_THREADS, /**< lock only against other threads, using SPI_LOCK */
LOCK_NONE /**< perform no locking, only safe if the bus is entirely private */
};
virtual int init();
/**
* Check for the presence of the device on the bus.
*/
virtual int probe();
/**
* Perform a SPI transfer.
*
* If called from interrupt context, this interface does not lock
* the bus and may interfere with non-interrupt-context callers.
*
* Clients in a mixed interrupt/non-interrupt configuration must
* ensure appropriate interlocking.
*
* At least one of send or recv must be non-null.
*
* @param send Bytes to send to the device, or nullptr if
* no data is to be sent.
* @param recv Buffer for receiving bytes from the device,
* or nullptr if no bytes are to be received.
* @param len Number of bytes to transfer.
* @return OK if the exchange was successful, -errno
* otherwise.
*/
int transfer(uint8_t *send, uint8_t *recv, unsigned len);
/**
* Set the SPI bus frequency
* This is used to change frequency on the fly. Some sensors
* (such as the MPU6000) need a lower frequency for setup
* registers and can handle higher frequency for sensor
* value registers
*
* @param frequency Frequency to set (Hz)
*/
void set_frequency(uint32_t frequency);
/**
* Set the SPI bus locking mode
*
* This set the SPI locking mode. For devices competing with NuttX SPI
* drivers on a bus the right lock mode is LOCK_THREADS.
*
* @param mode Locking mode
*/
void set_lockmode(enum LockMode mode) { locking_mode = mode; }
LockMode locking_mode; /**< selected locking mode */
private:
uint32_t _device;
enum spi_mode_e _mode;
uint32_t _frequency;
struct spi_dev_s *_dev;
/* this class does not allow copying */
SPI(const SPI &);
SPI operator=(const SPI &);
protected:
int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
bool external() { return px4_spi_bus_external(get_device_bus()); }
};
} // namespace device
#endif /* _DEVICE_SPI_H */
#ifdef __PX4_NUTTX
#include "nuttx/SPI.hpp"
#else
#include "posix/SPI.hpp"
#endif