Make NuttX drivers cross platform (VDev -> CDev)

This commit is contained in:
Daniel Agar 2017-08-24 01:21:48 -04:00 committed by Lorenz Meier
parent 6562dd496b
commit 07619cf723
29 changed files with 216 additions and 306 deletions

View File

@ -17,6 +17,9 @@ set(config_module_list
# Board support modules
#
drivers/device
drivers/airspeed
drivers/ms4525_airspeed
modules/sensors
platforms/posix/drivers/df_mpu9250_wrapper
platforms/posix/drivers/df_lsm9ds1_wrapper

View File

@ -10,6 +10,9 @@ set(config_module_list
drivers/pwm_out_sim
drivers/vmount
drivers/linux_gpio
drivers/airspeed
drivers/ms4525_airspeed
modules/sensors
platforms/posix/drivers/accelsim
platforms/posix/drivers/adcsim

View File

@ -1,34 +1,40 @@
# navio config for FW
uorb start
param load
param set MAV_BROADCAST 1
#param set SYS_AUTOSTART 2104
param set SYS_AUTOSTART 2100
param set MAV_TYPE 1
param set SYS_MC_EST_GROUP 2
param set BAT_CNT_V_VOLT 0.001
param set BAT_V_DIV 10.9176300578
param set BAT_CNT_V_CURR 0.001
param set BAT_A_PER_V 15.391030303
dataman start
df_lsm9ds1_wrapper start -R 4
df_ms5611_wrapper start
navio_rgbled start
navio_adc start
gps start -d /dev/spidev0.0 -i spi -p ubx
ms4525_airspeed start
sensors start
commander start
navigator start
ekf2 start
fw_att_control start
fw_pos_control_l1 start
mavlink start -u 14556 -r 1000000
sleep 1
mavlink stream -u 14556 -s HIGHRES_IMU -r 20
mavlink stream -u 14556 -s ATTITUDE -r 20
mavlink stream -u 14556 -s MANUAL_CONTROL -r 10
navio_sysfs_rc_in start
linux_pwm_out start -m ROMFS/px4fmu_common/mixers/AERT.main.mix
linux_pwm_out start -m ROMFS/px4fmu_common/mixers/AETRFG.main.mix
logger start -t -b 200
mavlink boot_complete

View File

@ -39,28 +39,10 @@
*/
#include <px4_config.h>
#include <drivers/device/device.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <arch/board/board.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
@ -173,7 +155,7 @@ Airspeed::probe()
}
int
Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
Airspeed::ioctl(device::file_t *filp, int cmd, unsigned long arg)
{
switch (cmd) {
@ -249,14 +231,14 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
return -EINVAL;
}
irqstate_t flags = px4_enter_critical_section();
ATOMIC_ENTER;
if (!_reports->resize(arg)) {
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return -ENOMEM;
}
px4_leave_critical_section(flags);
ATOMIC_LEAVE;
return OK;
}
@ -288,7 +270,7 @@ Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
Airspeed::read(struct file *filp, char *buffer, size_t buflen)
Airspeed::read(device::file_t *filp, char *buffer, size_t buflen)
{
unsigned count = buflen / sizeof(differential_pressure_s);
differential_pressure_s *abuf = reinterpret_cast<differential_pressure_s *>(buffer);

View File

@ -38,47 +38,20 @@
* Generic driver for airspeed sensors connected via I2C.
*/
#include <drivers/device/i2c.h>
#include <drivers/device/ringbuffer.h>
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <px4_config.h>
#include <px4_defines.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#ifdef __PX4_NUTTX
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#
#else
#include <px4_workqueue.h>
#endif
#include <arch/board/board.h>
#include <systemlib/airspeed.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
#include <systemlib/perf_counter.h>
#include <drivers/drv_airspeed.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/subsystem_info.h>
#include <uORB/uORB.h>
/* Default I2C bus */
static constexpr uint8_t PX4_I2C_BUS_DEFAULT = PX4_I2C_BUS_EXPANSION;

View File

@ -50,5 +50,11 @@
#define BOARD_MAX_LEDS 1 // Number external of LED's this board has
/*
* I2C busses
*/
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_NUMBER_I2C_BUSES 1
#include <system_config.h>
#include "../common/board_common.h"

View File

@ -2,7 +2,6 @@
* I2C busses
*/
#define PX4_I2C_BUS_ESC 1
#define PX4_SIM_BUS_TEST 2
#define PX4_I2C_BUS_EXPANSION 3
#define PX4_I2C_BUS_LED 3

View File

@ -50,5 +50,8 @@
#define CONFIG_ARCH_BOARD_SITL 1
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_NUMBER_I2C_BUSES 1
#include <system_config.h>
#include "../common/board_common.h"

View File

@ -35,7 +35,16 @@
#ifdef __PX4_NUTTX
#include "device_nuttx.h"
#include <nuttx/arch.h>
#define ATOMIC_ENTER irqstate_t flags = px4_enter_critical_section()
#define ATOMIC_LEAVE px4_leave_critical_section(flags)
#elif defined (__PX4_POSIX)
#include "vdev.h"
#define ATOMIC_ENTER lock()
#define ATOMIC_LEAVE unlock()
#endif

View File

@ -64,9 +64,10 @@ namespace device
I2C::I2C(const char *name,
const char *devname,
int bus,
uint16_t address) :
uint16_t address,
uint32_t frequency) :
// base class
VDev(name, devname),
CDev(name, devname),
// public
// protected
_retries(0),
@ -75,7 +76,7 @@ I2C::I2C(const char *name,
_address(address),
_fd(-1)
{
//warnx("I2C::I2C name = %s devname = %s", name, devname);
DEVICE_DEBUG("I2C::I2C name = %s devname = %s", name, devname);
// fill in _device_id fields for a I2C device
_device_id.devid_s.bus_type = DeviceBusType_I2C;
_device_id.devid_s.bus = bus;
@ -103,10 +104,10 @@ I2C::init()
// way to set it from user space.
// do base class init, which will create device node, etc
ret = VDev::init();
ret = CDev::init();
if (ret != PX4_OK) {
DEVICE_DEBUG("VDev::init failed");
DEVICE_DEBUG("CDev::init failed");
return ret;
}
@ -146,12 +147,12 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
unsigned retry_count = 0;
if (_fd < 0) {
warnx("I2C device not opened");
PX4_ERR("I2C device not opened");
return 1;
}
do {
// DEVICE_DEBUG("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
DEVICE_DEBUG("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
msgs = 0;
if (send_len > 0) {
@ -178,15 +179,18 @@ I2C::transfer(const uint8_t *send, unsigned send_len, uint8_t *recv, unsigned re
packets.nmsgs = msgs;
if (simulate) {
//warnx("I2C SIM: transfer_4 on %s", get_devname());
DEVICE_DEBUG("I2C SIM: transfer_4 on %s", get_devname());
ret = PX4_OK;
} else {
ret = ::ioctl(_fd, I2C_RDWR, (unsigned long)&packets);
if (ret < 0) {
warnx("I2C transfer failed");
return 1;
if (ret == -1) {
DEVICE_DEBUG("I2C transfer failed");
ret = PX4_ERROR;
} else {
ret = PX4_OK;
}
}
@ -221,7 +225,7 @@ I2C::transfer(struct i2c_msg *msgv, unsigned msgs)
packets.nmsgs = msgs;
if (simulate) {
warnx("I2C SIM: transfer_2 on %s", get_devname());
DEVICE_DEBUG("I2C SIM: transfer_2 on %s", get_devname());
ret = PX4_OK;
} else {
@ -229,7 +233,7 @@ I2C::transfer(struct i2c_msg *msgv, unsigned msgs)
}
if (ret < 0) {
warnx("I2C transfer failed");
DEVICE_DEBUG("I2C transfer failed");
return 1;
}
@ -251,13 +255,13 @@ int I2C::ioctl(device::file_t *filp, int cmd, unsigned long arg)
#ifdef __PX4_LINUX
case I2C_RDWR:
warnx("Use I2C::transfer, not ioctl");
DEVICE_DEBUG("Use I2C::transfer, not ioctl");
return 0;
#endif
default:
/* give it to the superclass */
return VDev::ioctl(filp, cmd, arg);
return CDev::ioctl(filp, cmd, arg);
}
}
@ -265,7 +269,7 @@ ssize_t I2C::read(file_t *filp, char *buffer, size_t buflen)
{
if (simulate) {
// FIXME no idea what this should be
warnx("2C SIM I2C::read");
DEVICE_DEBUG("2C SIM I2C::read");
return 0;
}
@ -279,7 +283,7 @@ ssize_t I2C::read(file_t *filp, char *buffer, size_t buflen)
ssize_t I2C::write(file_t *filp, const char *buffer, size_t buflen)
{
if (simulate) {
warnx("2C SIM I2C::write");
DEVICE_DEBUG("2C SIM I2C::write");
return buflen;
}

View File

@ -55,7 +55,7 @@ namespace device __EXPORT
/**
* Abstract class for character device on I2C
*/
class __EXPORT I2C : public VDev
class __EXPORT I2C : public CDev
{
public:
@ -88,7 +88,8 @@ protected:
I2C(const char *name,
const char *devname,
int bus,
uint16_t address);
uint16_t address,
uint32_t frequency = 0);
virtual ~I2C();
virtual int init();
@ -122,6 +123,20 @@ protected:
*/
int transfer(struct i2c_msg *msgv, unsigned msgs);
/**
* Change the bus address.
*
* Most often useful during probe() when the driver is testing
* several possible bus addresses.
*
* @param address The new bus address to set.
*/
void set_address(uint16_t address)
{
_address = address;
_device_id.devid_s.address = _address;
}
private:
uint16_t _address;
int _fd;

View File

@ -88,7 +88,7 @@ SIM::init()
ret = Device::init();
if (ret != PX4_OK) {
PX4_ERR("VDev::init failed");
PX4_ERR("CDev::init failed");
return ret;
}

View File

@ -50,11 +50,7 @@ namespace device __EXPORT
/**
* Abstract class for character device on SPI
*/
#ifdef __PX4_NUTTX
class __EXPORT SPI : public CDev
#else
class __EXPORT SPI : public VDev
#endif
{
protected:
/**

View File

@ -61,7 +61,7 @@ static map<string, void *> devmap;
pthread_mutex_t devmutex = PTHREAD_MUTEX_INITIALIZER;
VDev::VDev(const char *name,
CDev::CDev(const char *name,
const char *devname) :
// base class
Device(name),
@ -75,12 +75,12 @@ VDev::VDev(const char *name,
_open_count(0),
_pollset(nullptr)
{
PX4_DEBUG("VDev::VDev");
DEVICE_DEBUG("CDev::CDev");
}
VDev::~VDev()
CDev::~CDev()
{
PX4_DEBUG("VDev::~VDev");
DEVICE_DEBUG("CDev::~CDev");
if (_registered) {
unregister_driver(_devname);
@ -92,9 +92,9 @@ VDev::~VDev()
}
int
VDev::register_class_devname(const char *class_devname)
CDev::register_class_devname(const char *class_devname)
{
PX4_DEBUG("VDev::register_class_devname %s", class_devname);
DEVICE_DEBUG("CDev::register_class_devname %s", class_devname);
if (class_devname == nullptr) {
return -EINVAL;
@ -121,9 +121,9 @@ VDev::register_class_devname(const char *class_devname)
}
int
VDev::register_driver(const char *name, void *data)
CDev::register_driver(const char *name, void *data)
{
PX4_DEBUG("VDev::register_driver %s", name);
DEVICE_DEBUG("CDev::register_driver %s", name);
int ret = 0;
if (name == nullptr || data == nullptr) {
@ -141,7 +141,7 @@ VDev::register_driver(const char *name, void *data)
}
devmap[name] = (void *)data;
PX4_DEBUG("Registered DEV %s", name);
DEVICE_DEBUG("Registered DEV %s", name);
pthread_mutex_unlock(&devmutex);
@ -149,9 +149,9 @@ VDev::register_driver(const char *name, void *data)
}
int
VDev::unregister_driver(const char *name)
CDev::unregister_driver(const char *name)
{
PX4_DEBUG("VDev::unregister_driver %s", name);
DEVICE_DEBUG("CDev::unregister_driver %s", name);
int ret = -EINVAL;
if (name == nullptr) {
@ -161,7 +161,7 @@ VDev::unregister_driver(const char *name)
pthread_mutex_lock(&devmutex);
if (devmap.erase(name) > 0) {
PX4_DEBUG("Unregistered DEV %s", name);
DEVICE_DEBUG("Unregistered DEV %s", name);
ret = 0;
}
@ -171,9 +171,9 @@ VDev::unregister_driver(const char *name)
}
int
VDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
CDev::unregister_class_devname(const char *class_devname, unsigned class_instance)
{
PX4_DEBUG("VDev::unregister_class_devname");
DEVICE_DEBUG("CDev::unregister_class_devname");
char name[32];
snprintf(name, sizeof(name), "%s%u", class_devname, class_instance);
int ret = -EINVAL;
@ -182,7 +182,7 @@ VDev::unregister_class_devname(const char *class_devname, unsigned class_instanc
pthread_mutex_lock(&devmutex);
if (devmap.erase(name) > 0) {
PX4_DEBUG("Unregistered class DEV %s", name);
DEVICE_DEBUG("Unregistered class DEV %s", name);
ret = 0;
}
@ -192,9 +192,9 @@ VDev::unregister_class_devname(const char *class_devname, unsigned class_instanc
}
int
VDev::init()
CDev::init()
{
PX4_DEBUG("VDev::init");
DEVICE_DEBUG("CDev::init");
// base class init first
int ret = Device::init();
@ -222,9 +222,9 @@ out:
* Default implementations of the character device interface
*/
int
VDev::open(file_t *filep)
CDev::open(file_t *filep)
{
PX4_DEBUG("VDev::open");
DEVICE_DEBUG("CDev::open");
int ret = PX4_OK;
lock();
@ -247,16 +247,16 @@ VDev::open(file_t *filep)
}
int
VDev::open_first(file_t *filep)
CDev::open_first(file_t *filep)
{
PX4_DEBUG("VDev::open_first");
DEVICE_DEBUG("CDev::open_first");
return PX4_OK;
}
int
VDev::close(file_t *filep)
CDev::close(file_t *filep)
{
PX4_DEBUG("VDev::close");
DEVICE_DEBUG("CDev::close");
int ret = PX4_OK;
lock();
@ -280,37 +280,37 @@ VDev::close(file_t *filep)
}
int
VDev::close_last(file_t *filep)
CDev::close_last(file_t *filep)
{
PX4_DEBUG("VDev::close_last");
DEVICE_DEBUG("CDev::close_last");
return PX4_OK;
}
ssize_t
VDev::read(file_t *filep, char *buffer, size_t buflen)
CDev::read(file_t *filep, char *buffer, size_t buflen)
{
PX4_DEBUG("VDev::read");
DEVICE_DEBUG("CDev::read");
return -ENOSYS;
}
ssize_t
VDev::write(file_t *filep, const char *buffer, size_t buflen)
CDev::write(file_t *filep, const char *buffer, size_t buflen)
{
PX4_DEBUG("VDev::write");
DEVICE_DEBUG("CDev::write");
return -ENOSYS;
}
off_t
VDev::seek(file_t *filep, off_t offset, int whence)
CDev::seek(file_t *filep, off_t offset, int whence)
{
PX4_DEBUG("VDev::seek");
DEVICE_DEBUG("CDev::seek");
return -ENOSYS;
}
int
VDev::ioctl(file_t *filep, int cmd, unsigned long arg)
CDev::ioctl(file_t *filep, int cmd, unsigned long arg)
{
PX4_DEBUG("VDev::ioctl");
DEVICE_DEBUG("CDev::ioctl");
int ret = -ENOTTY;
switch (cmd) {
@ -342,9 +342,9 @@ VDev::ioctl(file_t *filep, int cmd, unsigned long arg)
}
int
VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
CDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
{
PX4_DEBUG("VDev::Poll %s", setup ? "setup" : "teardown");
DEVICE_DEBUG("CDev::Poll %s", setup ? "setup" : "teardown");
int ret = PX4_OK;
/*
@ -358,7 +358,7 @@ VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
* benefit.
*/
fds->priv = (void *)filep;
PX4_DEBUG("VDev::poll: fds->priv = %p", filep);
DEVICE_DEBUG("CDev::poll: fds->priv = %p", filep);
/*
* Handle setup requests.
@ -395,9 +395,9 @@ VDev::poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
}
void
VDev::poll_notify(pollevent_t events)
CDev::poll_notify(pollevent_t events)
{
PX4_DEBUG("VDev::poll_notify events = %0x", events);
DEVICE_DEBUG("CDev::poll_notify events = %0x", events);
/* lock against poll() as well as other wakeups */
lock();
@ -412,16 +412,16 @@ VDev::poll_notify(pollevent_t events)
}
void
VDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
CDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
{
PX4_DEBUG("VDev::poll_notify_one");
DEVICE_DEBUG("CDev::poll_notify_one");
int value;
px4_sem_getvalue(fds->sem, &value);
/* update the reported event set */
fds->revents |= fds->events & events;
PX4_DEBUG(" Events fds=%p %0x %0x %0x %d", fds, fds->revents, fds->events, events, value);
DEVICE_DEBUG(" Events fds=%p %0x %0x %0x %d", fds, fds->revents, fds->events, events, value);
/* if the state is now interesting, wake the waiter if it's still asleep */
/* XXX semcount check here is a vile hack; counting semphores should not be abused as cvars */
@ -431,20 +431,20 @@ VDev::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
}
pollevent_t
VDev::poll_state(file_t *filep)
CDev::poll_state(file_t *filep)
{
PX4_DEBUG("VDev::poll_notify");
DEVICE_DEBUG("CDev::poll_notify");
/* by default, no poll events to report */
return 0;
}
int
VDev::store_poll_waiter(px4_pollfd_struct_t *fds)
CDev::store_poll_waiter(px4_pollfd_struct_t *fds)
{
/*
* Look for a free slot.
*/
PX4_DEBUG("VDev::store_poll_waiter");
DEVICE_DEBUG("CDev::store_poll_waiter");
for (unsigned i = 0; i < _max_pollwaiters; i++) {
if (nullptr == _pollset[i]) {
@ -482,9 +482,9 @@ VDev::store_poll_waiter(px4_pollfd_struct_t *fds)
}
int
VDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
CDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
{
PX4_DEBUG("VDev::remove_poll_waiter");
DEVICE_DEBUG("CDev::remove_poll_waiter");
for (unsigned i = 0; i < _max_pollwaiters; i++) {
if (fds == _pollset[i]) {
@ -499,9 +499,9 @@ VDev::remove_poll_waiter(px4_pollfd_struct_t *fds)
return -EINVAL;
}
VDev *VDev::getDev(const char *path)
CDev *CDev::getDev(const char *path)
{
PX4_DEBUG("VDev::getDev");
PX4_DEBUG("CDev::getDev");
pthread_mutex_lock(&devmutex);
@ -509,7 +509,7 @@ VDev *VDev::getDev(const char *path)
if (item != devmap.end()) {
pthread_mutex_unlock(&devmutex);
return (VDev *)item->second;
return (CDev *)item->second;
}
pthread_mutex_unlock(&devmutex);
@ -517,7 +517,7 @@ VDev *VDev::getDev(const char *path)
return nullptr;
}
void VDev::showDevices()
void CDev::showDevices()
{
int i = 0;
PX4_INFO("PX4 Devices:");
@ -547,7 +547,7 @@ void VDev::showDevices()
} while (i == 0);
}
void VDev::showTopics()
void CDev::showTopics()
{
PX4_INFO("Devices:");
@ -562,7 +562,7 @@ void VDev::showTopics()
pthread_mutex_unlock(&devmutex);
}
void VDev::showFiles()
void CDev::showFiles()
{
PX4_INFO("Files:");

View File

@ -209,7 +209,7 @@ private:
/**
* Abstract class for any virtual character device
*/
class __EXPORT VDev : public Device
class __EXPORT CDev : public Device
{
public:
/**
@ -218,12 +218,12 @@ public:
* @param name Driver name
* @param devname Device node name
*/
VDev(const char *name, const char *devname);
CDev(const char *name, const char *devname);
/**
* Destructor
*/
virtual ~VDev();
virtual ~CDev();
virtual int init();
@ -322,7 +322,7 @@ public:
*/
virtual int ioctl(file_t *filep, int cmd, unsigned long arg);
static VDev *getDev(const char *path);
static CDev *getDev(const char *path);
static void showFiles(void);
static void showDevices(void);
static void showTopics(void);
@ -447,8 +447,8 @@ private:
int remove_poll_waiter(px4_pollfd_struct_t *fds);
/* do not allow copying this class */
VDev(const VDev &);
//VDev operator=(const VDev&);
CDev(const CDev &);
//CDev operator=(const CDev&);
};
#if 0

View File

@ -72,14 +72,14 @@ extern "C" {
return ret;
}
inline VDev *get_vdev(int fd)
inline CDev *get_vdev(int fd)
{
pthread_mutex_lock(&filemutex);
bool valid = (fd < PX4_MAX_FD && fd >= 0 && filemap[fd] != nullptr);
VDev *dev;
CDev *dev;
if (valid) {
dev = (VDev *)(filemap[fd]->vdev);
dev = (CDev *)(filemap[fd]->vdev);
} else {
dev = nullptr;
@ -92,7 +92,7 @@ extern "C" {
int px4_open(const char *path, int flags, ...)
{
PX4_DEBUG("px4_open");
VDev *dev = VDev::getDev(path);
CDev *dev = CDev::getDev(path);
int ret = 0;
int i;
mode_t mode;
@ -163,7 +163,7 @@ extern "C" {
{
int ret;
VDev *dev = get_vdev(fd);
CDev *dev = get_vdev(fd);
if (dev) {
pthread_mutex_lock(&filemutex);
@ -193,7 +193,7 @@ extern "C" {
{
int ret;
VDev *dev = get_vdev(fd);
CDev *dev = get_vdev(fd);
if (dev) {
PX4_DEBUG("px4_read fd = %d", fd);
@ -215,7 +215,7 @@ extern "C" {
{
int ret;
VDev *dev = get_vdev(fd);
CDev *dev = get_vdev(fd);
if (dev) {
PX4_DEBUG("px4_write fd = %d", fd);
@ -238,7 +238,7 @@ extern "C" {
PX4_DEBUG("px4_ioctl fd = %d", fd);
int ret = 0;
VDev *dev = get_vdev(fd);
CDev *dev = get_vdev(fd);
if (dev) {
ret = dev->ioctl(filemap[fd], cmd, arg);
@ -297,11 +297,11 @@ extern "C" {
fds[i].revents = 0;
fds[i].priv = nullptr;
VDev *dev = get_vdev(fds[i].fd);
CDev *dev = get_vdev(fds[i].fd);
// If fd is valid
if (dev) {
PX4_DEBUG("%s: px4_poll: VDev->poll(setup) %d", thread_name, fds[i].fd);
PX4_DEBUG("%s: px4_poll: CDev->poll(setup) %d", thread_name, fds[i].fd);
ret = dev->poll(filemap[fds[i].fd], &fds[i], true);
if (ret < 0) {
@ -358,11 +358,11 @@ extern "C" {
// go through all fds and count how many have data
for (i = 0; i < nfds; ++i) {
VDev *dev = get_vdev(fds[i].fd);
CDev *dev = get_vdev(fds[i].fd);
// If fd is valid
if (dev) {
PX4_DEBUG("%s: px4_poll: VDev->poll(teardown) %d", thread_name, fds[i].fd);
PX4_DEBUG("%s: px4_poll: CDev->poll(teardown) %d", thread_name, fds[i].fd);
ret = dev->poll(filemap[fds[i].fd], &fds[i], false);
if (ret < 0) {
@ -396,23 +396,23 @@ extern "C" {
return -1;
}
VDev *dev = VDev::getDev(pathname);
CDev *dev = CDev::getDev(pathname);
return (dev != nullptr) ? 0 : -1;
}
void px4_show_devices()
{
VDev::showDevices();
CDev::showDevices();
}
void px4_show_topics()
{
VDev::showTopics();
CDev::showTopics();
}
void px4_show_files()
{
VDev::showFiles();
CDev::showFiles();
}
void px4_enable_sim_lockstep()

View File

@ -44,7 +44,7 @@
using namespace device;
VFile::VFile(const char *fname, mode_t mode) :
VDev("vfile", fname)
CDev("vfile", fname)
{
}

View File

@ -44,7 +44,7 @@
#include <unistd.h>
#include <stdio.h>
class VFile : public device::VDev
class VFile : public device::CDev
{
public:

View File

@ -514,11 +514,7 @@ int IridiumSBD::ioctl(struct file *filp, int cmd, unsigned long arg)
default: {
/* see if the parent class can make any use of it */
#ifdef __PX4_NUTTX
return CDev::ioctl(filp, cmd, arg);
#else
return VDev::ioctl(filp, cmd, arg);
#endif
}
}
}

View File

@ -56,11 +56,7 @@ extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
#ifdef __PX4_NUTTX
class LED : device::CDev
#else
class LED : device::VDev
#endif
{
public:
LED();
@ -70,12 +66,7 @@ public:
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
};
LED::LED() :
#ifdef __PX4_NUTTX
CDev("led", LED0_DEVICE_PATH)
#else
VDev("led", LED0_DEVICE_PATH)
#endif
LED::LED() : CDev("led", LED0_DEVICE_PATH)
{
// force immediate init/device registration
init();
@ -89,11 +80,7 @@ int
LED::init()
{
DEVICE_DEBUG("LED::init");
#ifdef __PX4_NUTTX
CDev::init();
#else
VDev::init();
#endif
led_init();
return 0;
@ -117,13 +104,8 @@ LED::ioctl(device::file_t *filp, int cmd, unsigned long arg)
led_toggle(arg);
break;
default:
#ifdef __PX4_NUTTX
result = CDev::ioctl(filp, cmd, arg);
#else
result = VDev::ioctl(filp, cmd, arg);
#endif
}
return result;

View File

@ -54,23 +54,6 @@
#include <drivers/device/i2c.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdlib.h>
#include <stdbool.h>
#include <semaphore.h>
#include <string.h>
#include <fcntl.h>
#include <poll.h>
#include <errno.h>
#include <stdio.h>
#include <math.h>
#include <unistd.h>
#include <nuttx/arch.h>
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <board_config.h>
#include <systemlib/airspeed.h>
@ -417,7 +400,7 @@ start(int i2c_bus)
int fd;
if (g_dev != nullptr) {
errx(1, "already started");
PX4_ERR("already started");
}
/* create the driver, try the MS4525DO first */
@ -430,22 +413,22 @@ start(int i2c_bus)
/* both versions failed if the init for the MS5525DSO fails, give up */
if (OK != g_dev->Airspeed::init()) {
PX4_WARN("init fail");
PX4_ERR("init fail");
goto fail;
}
/* set the poll rate to default, starts automatic data collection */
fd = open(PATH_MS4525, O_RDONLY);
fd = px4_open(PATH_MS4525, O_RDONLY);
if (fd < 0) {
goto fail;
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
goto fail;
}
exit(0);
return;
fail:
@ -455,7 +438,6 @@ fail:
}
PX4_WARN("no MS4525 airspeed sensor connected");
exit(1);
}
/**
@ -469,10 +451,8 @@ stop()
g_dev = nullptr;
} else {
errx(1, "driver not running");
PX4_ERR("driver not running");
}
exit(0);
}
/**
@ -487,25 +467,25 @@ test()
ssize_t sz;
int ret;
int fd = open(PATH_MS4525, O_RDONLY);
int fd = px4_open(PATH_MS4525, O_RDONLY);
if (fd < 0) {
err(1, "%s open failed (try 'meas_airspeed start' if the driver is not running", PATH_MS4525);
PX4_ERR("%s open failed (try 'meas_airspeed start' if the driver is not running", PATH_MS4525);
}
/* do a simple demand read */
sz = read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
err(1, "immediate read failed");
PX4_ERR("immediate read failed");
}
warnx("single read");
warnx("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
PX4_INFO("single read");
PX4_INFO("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
errx(1, "failed to set 2Hz poll rate");
if (OK != px4_ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
PX4_ERR("failed to set 2Hz poll rate");
}
/* read the sensor 5x and report each value */
@ -518,27 +498,25 @@ test()
ret = poll(&fds, 1, 2000);
if (ret != 1) {
errx(1, "timed out");
PX4_ERR("timed out");
}
/* now go get it */
sz = read(fd, &report, sizeof(report));
if (sz != sizeof(report)) {
err(1, "periodic read failed");
PX4_ERR("periodic read failed");
}
warnx("periodic read %u", i);
warnx("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
PX4_INFO("periodic read %u", i);
PX4_INFO("diff pressure: %d pa", (int)report.differential_pressure_filtered_pa);
PX4_INFO("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}
/* reset the sensor polling to its default rate */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
errx(1, "failed to set default rate");
if (OK != px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
PX4_ERR("failed to set default rate");
}
errx(0, "PASS");
}
/**
@ -547,21 +525,19 @@ test()
void
reset()
{
int fd = open(PATH_MS4525, O_RDONLY);
int fd = px4_open(PATH_MS4525, O_RDONLY);
if (fd < 0) {
err(1, "failed ");
PX4_ERR("failed ");
}
if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
err(1, "driver reset failed");
if (px4_ioctl(fd, SENSORIOCRESET, 0) < 0) {
PX4_ERR("driver reset failed");
}
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
err(1, "driver poll restart failed");
if (px4_ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
PX4_ERR("driver poll restart failed");
}
exit(0);
}
/**
@ -571,13 +547,11 @@ void
info()
{
if (g_dev == nullptr) {
errx(1, "driver not running");
PX4_ERR("driver not running");
}
printf("state @ %p\n", g_dev);
PX4_INFO("state @ %p", g_dev);
g_dev->print_info();
exit(0);
}
} // namespace
@ -586,11 +560,11 @@ info()
static void
meas_airspeed_usage()
{
warnx("usage: meas_airspeed command [options]");
warnx("options:");
warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT);
warnx("command:");
warnx("\tstart|stop|reset|test|info");
PX4_INFO("usage: meas_airspeed command [options]");
PX4_INFO("options:");
PX4_INFO("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT);
PX4_INFO("command:");
PX4_INFO("\tstart|stop|reset|test|info");
}
int
@ -644,5 +618,6 @@ ms4525_airspeed_main(int argc, char *argv[])
}
meas_airspeed_usage();
exit(0);
return 0;
}

View File

@ -82,11 +82,7 @@
#include <systemlib/err.h>
#ifdef __PX4_NUTTX
class PWMSim : public device::CDev
#else
class PWMSim : public device::VDev
#endif
{
const uint32_t PWM_SIM_DISARMED_MAGIC = 900;
const uint32_t PWM_SIM_FAILSAFE_MAGIC = 600;
@ -178,12 +174,7 @@ bool PWMSim::_lockdown = false;
bool PWMSim::_failsafe = false;
PWMSim::PWMSim() :
#ifdef __PX4_NUTTX
CDev
#else
VDev
#endif
("pwm_out_sim", PWM_OUTPUT0_DEVICE_PATH),
CDev("pwm_out_sim", PWM_OUTPUT0_DEVICE_PATH),
_task(-1),
_mode(MODE_NONE),
_update_rate(50),
@ -244,11 +235,7 @@ PWMSim::init()
ASSERT(_task == -1);
/* do regular cdev init */
#ifdef __PX4_NUTTX
ret = CDev::init();
#else
ret = VDev::init();
#endif
if (ret != OK) {
return ret;
@ -609,11 +596,7 @@ PWMSim::ioctl(device::file_t *filp, int cmd, unsigned long arg)
/* if nobody wants it, let CDev have it */
if (ret == -ENOTTY) {
#ifdef __PX4_NUTTX
ret = CDev::ioctl(filp, cmd, arg);
#else
ret = VDev::ioctl(filp, cmd, arg);
#endif
}
return ret;

View File

@ -39,9 +39,6 @@
#include <systemlib/px4_macros.h>
#ifdef __PX4_NUTTX
#include <nuttx/arch.h>
#define ATOMIC_ENTER irqstate_t flags = px4_enter_critical_section()
#define ATOMIC_LEAVE px4_leave_critical_section(flags)
#define FILE_FLAGS(filp) filp->f_oflags
#define FILE_PRIV(filp) filp->f_priv
#define ITERATE_NODE_MAP() \
@ -55,8 +52,6 @@
#include <algorithm>
#define FILE_FLAGS(filp) filp->flags
#define FILE_PRIV(filp) filp->priv
#define ATOMIC_ENTER lock()
#define ATOMIC_LEAVE unlock()
#define ITERATE_NODE_MAP() \
for (const auto &node_iter : _node_map)
#define INIT_NODE_MAP_VARS(node_obj, node_name_str) \
@ -88,7 +83,7 @@ uORB::DeviceNode::SubscriberData *uORB::DeviceNode::filp_to_sd(device::file_t *f
uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const char *name, const char *path,
int priority, unsigned int queue_size) :
VDev(name, path),
CDev(name, path),
_meta(meta),
_data(nullptr),
_last_update(0),
@ -134,7 +129,7 @@ uORB::DeviceNode::open(device::file_t *filp)
/* now complete the open */
if (ret == PX4_OK) {
ret = VDev::open(filp);
ret = CDev::open(filp);
/* open failed - not the publisher anymore */
if (ret != PX4_OK) {
@ -165,12 +160,12 @@ uORB::DeviceNode::open(device::file_t *filp)
FILE_PRIV(filp) = (void *)sd;
ret = VDev::open(filp);
ret = CDev::open(filp);
add_internal_subscriber();
if (ret != PX4_OK) {
PX4_ERR("VDev::open failed");
PX4_ERR("CDev::open failed");
delete sd;
}
@ -202,7 +197,7 @@ uORB::DeviceNode::close(device::file_t *filp)
}
}
return VDev::close(filp);
return CDev::close(filp);
}
ssize_t
@ -414,7 +409,7 @@ uORB::DeviceNode::ioctl(device::file_t *filp, int cmd, unsigned long arg)
default:
/* give it to the superclass */
return VDev::ioctl(filp, cmd, arg);
return CDev::ioctl(filp, cmd, arg);
}
}
@ -535,7 +530,7 @@ uORB::DeviceNode::poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events)
* If the topic looks updated to the subscriber, go ahead and notify them.
*/
if (appears_updated(sd)) {
VDev::poll_notify_one(fds, events);
CDev::poll_notify_one(fds, events);
}
}
@ -834,7 +829,7 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data
}
uORB::DeviceMaster::DeviceMaster(Flavor f) :
VDev((f == PUBSUB) ? "obj_master" : "param_master",
CDev((f == PUBSUB) ? "obj_master" : "param_master",
(f == PUBSUB) ? TOPIC_MASTER_DEVICE_PATH : PARAM_MASTER_DEVICE_PATH),
_flavor(f)
{
@ -959,7 +954,7 @@ uORB::DeviceMaster::ioctl(device::file_t *filp, int cmd, unsigned long arg)
default:
/* give it to the superclass */
return VDev::ioctl(filp, cmd, arg);
return CDev::ioctl(filp, cmd, arg);
}
}

View File

@ -42,13 +42,6 @@
#include <stdlib.h>
#include "ORBMap.hpp"
namespace device
{
//type mappings to NuttX
typedef ::file file_t;
typedef CDev VDev;
}
#else
#include <string>
@ -56,8 +49,6 @@ typedef CDev VDev;
#endif /* __PX4_NUTTX */
namespace uORB
{
class DeviceNode;
@ -68,7 +59,7 @@ class Manager;
/**
* Per-object device instance.
*/
class uORB::DeviceNode : public device::VDev
class uORB::DeviceNode : public device::CDev
{
public:
DeviceNode(const struct orb_metadata *meta, const char *name, const char *path,
@ -277,7 +268,7 @@ private:
* Used primarily to create new objects via the ORBIOCCREATE
* ioctl.
*/
class uORB::DeviceMaster : public device::VDev
class uORB::DeviceMaster : public device::CDev
{
public:
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);

View File

@ -72,7 +72,7 @@
#include "airspeedsim.h"
AirspeedSim::AirspeedSim(int bus, int address, unsigned conversion_interval, const char *path) :
VDev("AIRSPEEDSIM", path),
CDev("AIRSPEEDSIM", path),
_reports(nullptr),
_retries(0),
_sensor_ok(false),
@ -119,8 +119,8 @@ AirspeedSim::init()
int ret = ERROR;
/* init base class */
if (VDev::init() != OK) {
DEVICE_DEBUG("VDev init failed");
if (CDev::init() != OK) {
DEVICE_DEBUG("CDev init failed");
goto out;
}

View File

@ -78,7 +78,7 @@
# error This requires CONFIG_SCHED_WORKQUEUE.
#endif
class __EXPORT AirspeedSim : public device::VDev
class __EXPORT AirspeedSim : public device::CDev
{
public:
AirspeedSim(int bus, int address, unsigned conversion_interval, const char *path);

View File

@ -44,16 +44,6 @@
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#define ADCSIM0_DEVICE_PATH "/dev/adc0"
/*
* I2C busses
*/
#define PX4_I2C_BUS_ESC 1
#define PX4_SIM_BUS_TEST 2
#define PX4_I2C_BUS_EXPANSION 3
#define PX4_I2C_BUS_LED 3
#define PX4_NUMBER_I2C_BUSES 3
#define PX4_I2C_OBDEV_LED 0x55
#define SIM_FORMATED_UUID "000000010000000200000003"
#define PX4_CPU_UUID_BYTE_LENGTH 12
#define PX4_CPU_UUID_WORD32_LENGTH 3

View File

@ -99,11 +99,11 @@ public:
size_t _read_offset;
};
class VCDevNode : public VDev
class VCDevNode : public CDev
{
public:
VCDevNode() :
VDev("vcdevtest", TESTDEV),
CDev("vcdevtest", TESTDEV),
_is_open_for_write(false),
_write_offset(0) {};
@ -127,7 +127,7 @@ int VCDevNode::open(device::file_t *handlep)
return -1;
}
int ret = VDev::open(handlep);
int ret = CDev::open(handlep);
if (ret != 0) {
return ret;
@ -146,7 +146,7 @@ int VCDevNode::close(device::file_t *handlep)
{
delete (PrivData *)handlep->priv;
handlep->priv = nullptr;
VDev::close(handlep);
CDev::close(handlep);
// Enable a new writer of the device is re-opened for write
if ((handlep->flags & PX4_F_WRONLY) && _is_open_for_write) {

View File

@ -4,7 +4,6 @@
* I2C busses
*/
#define PX4_I2C_BUS_ESC 1
#define PX4_SIM_BUS_TEST 2
#define PX4_I2C_BUS_EXPANSION 3
#define PX4_I2C_BUS_LED 3