uorb: remove syntax differences between posix & nuttx src file

This commit is contained in:
Beat Küng 2016-09-08 14:11:57 +02:00 committed by Julian Oes
parent fbd7aac4b5
commit 83c5323c3a
4 changed files with 93 additions and 90 deletions

View File

@ -43,14 +43,15 @@
#include <px4_sem.hpp>
#include <stdlib.h>
uORB::DeviceNode::DeviceNode
(
const struct orb_metadata *meta,
const char *name,
const char *path,
int priority,
unsigned int queue_size
) :
uORB::DeviceNode::SubscriberData *uORB::DeviceNode::filp_to_sd(struct file *filp)
{
SubscriberData *sd = (SubscriberData *)(filp->f_priv);
return sd;
}
uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const char *name, const char *path,
int priority, unsigned int queue_size) :
CDev(name, path),
_meta(meta),
_data(nullptr),
@ -64,7 +65,7 @@ uORB::DeviceNode::DeviceNode
_subscriber_count(0)
{
// enable debug() calls
_debug_enabled = true;
//_debug_enabled = true;
}
uORB::DeviceNode::~DeviceNode()
@ -88,7 +89,7 @@ uORB::DeviceNode::open(struct file *filp)
if (_publisher == 0) {
_publisher = getpid();
ret = OK;
ret = PX4_OK;
} else {
ret = -EBUSY;
@ -97,11 +98,11 @@ uORB::DeviceNode::open(struct file *filp)
unlock();
/* now complete the open */
if (ret == OK) {
if (ret == PX4_OK) {
ret = CDev::open(filp);
/* open failed - not the publisher anymore */
if (ret != OK) {
if (ret != PX4_OK) {
_publisher = 0;
}
}
@ -133,7 +134,8 @@ uORB::DeviceNode::open(struct file *filp)
add_internal_subscriber();
if (ret != OK) {
if (ret != PX4_OK) {
PX4_ERR("VDev::open failed");
delete sd;
}
@ -289,12 +291,12 @@ uORB::DeviceNode::ioctl(struct file *filp, int cmd, unsigned long arg)
irqstate_t state = px4_enter_critical_section();
*(hrt_abstime *)arg = _last_update;
px4_leave_critical_section(state);
return OK;
return PX4_OK;
}
case ORBIOCUPDATED:
*(bool *)arg = appears_updated(sd);
return OK;
return PX4_OK;
case ORBIOCSETINTERVAL: {
int ret = PX4_OK;
@ -329,11 +331,11 @@ uORB::DeviceNode::ioctl(struct file *filp, int cmd, unsigned long arg)
case ORBIOCGADVERTISER:
*(uintptr_t *)arg = (uintptr_t)this;
return OK;
return PX4_OK;
case ORBIOCGPRIORITY:
*(int *)arg = sd->priority();
return OK;
return PX4_OK;
case ORBIOCSETQUEUESIZE:
//no need for locking here, since this is used only during the advertisement call,
@ -357,24 +359,19 @@ uORB::DeviceNode::ioctl(struct file *filp, int cmd, unsigned long arg)
}
ssize_t
uORB::DeviceNode::publish
(
const orb_metadata *meta,
orb_advert_t handle,
const void *data
)
uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data)
{
uORB::DeviceNode *DeviceNode = (uORB::DeviceNode *)handle;
uORB::DeviceNode *devnode = (uORB::DeviceNode *)handle;
int ret;
/* this is a bit risky, since we are trusting the handle in order to deref it */
if (DeviceNode->_meta != meta) {
if (devnode->_meta != meta) {
errno = EINVAL;
return ERROR;
}
/* call the DeviceNode write method with no file pointer */
ret = DeviceNode->write(nullptr, (const char *)data, meta->o_size);
/* call the devnode write method with no file pointer */
ret = devnode->write(nullptr, (const char *)data, meta->o_size);
if (ret < 0) {
return ERROR;
@ -398,7 +395,7 @@ uORB::DeviceNode::publish
}
}
return OK;
return PX4_OK;
}
int uORB::DeviceNode::unadvertise(orb_advert_t handle)
@ -642,14 +639,14 @@ int16_t uORB::DeviceNode::process_add_subscription(int32_t rateInHz)
ch->send_message(_meta->o_name, _meta->o_size, _data);
}
return OK;
return PX4_OK;
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
int16_t uORB::DeviceNode::process_remove_subscription()
{
return OK;
return PX4_OK;
}
//-----------------------------------------------------------------------------
@ -676,7 +673,7 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data
return ERROR;
}
return OK;
return PX4_OK;
}
uORB::DeviceMaster::DeviceMaster(Flavor f) :
@ -685,7 +682,7 @@ uORB::DeviceMaster::DeviceMaster(Flavor f) :
_flavor(f)
{
// enable debug() calls
_debug_enabled = true;
//_debug_enabled = true;
_last_statistics_output = hrt_absolute_time();
}
@ -710,7 +707,7 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
/* construct a path to the node - this also checks the node name */
ret = uORB::Utils::node_mkpath(nodepath, _flavor, meta, adv->instance);
if (ret != OK) {
if (ret != PX4_OK) {
return ret;
}
@ -762,8 +759,8 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
/* initialise the node - this may fail if e.g. a node with this name already exists */
ret = node->init();
if (ret != OK) {
/* if init failed, discard the node */
/* if init failed, discard the node and its name */
if (ret != PX4_OK) {
delete node;
if (ret == -EEXIST) {
@ -773,7 +770,7 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
if ((existing_node != nullptr) && !(existing_node->is_published())) {
/* nothing has been published yet, lets claim it */
ret = OK;
ret = PX4_OK;
} else {
/* otherwise: data has already been published, keep looking */
@ -790,7 +787,7 @@ uORB::DeviceMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
group_tries++;
} while (ret != OK && (group_tries < max_group_tries));
} while (ret != PX4_OK && (group_tries < max_group_tries));
if (ret != PX4_OK && group_tries >= max_group_tries) {
ret = -ENOMEM;
@ -900,7 +897,6 @@ void uORB::DeviceMaster::addNewDeviceNodes(DeviceNodeStatisticsData **first_node
last_node->last_lost_msg_count = last_node->node->lost_message_count();
last_node->last_pub_msg_count = last_node->node->published_message_count();
}
}
@ -1004,7 +1000,6 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
#undef CLEAR_LINE
uORB::DeviceNode *uORB::DeviceMaster::getDeviceNode(const char *nodepath)
{
lock();

View File

@ -31,8 +31,7 @@
*
****************************************************************************/
#ifndef _uORBDevices_nuttx_hpp_
#define _uORBDevices_nuttx_hpp_
#pragma once
#include <stdint.h>
#include <string.h>
@ -54,28 +53,15 @@ class Manager;
class uORB::DeviceNode : public device::CDev
{
public:
/**
* Constructor
*/
DeviceNode
(
const struct orb_metadata *meta,
const char *name,
const char *path,
int priority,
unsigned int queue_size = 1
);
/**
* Destructor
*/
DeviceNode(const struct orb_metadata *meta, const char *name, const char *path,
int priority, unsigned int queue_size = 1);
~DeviceNode();
/**
* Method to create a subscriber instance and return the struct
* pointing to the subscriber as a file pointer.
*/
virtual int open(struct file *filp);
virtual int open(struct file *filp);
/**
* Method to close a subscriber for this topic.
@ -117,12 +103,7 @@ public:
/**
* Method to publish a data to this node.
*/
static ssize_t publish
(
const orb_metadata *meta,
orb_advert_t handle,
const void *data
);
static ssize_t publish(const orb_metadata *meta, orb_advert_t handle, const void *data);
static int unadvertise(orb_advert_t handle);
@ -225,11 +206,7 @@ private:
bool _published; /**< has ever data been published */
unsigned int _queue_size; /**< maximum number of elements in the queue */
static SubscriberData *filp_to_sd(struct file *filp)
{
SubscriberData *sd = (SubscriberData *)(filp->f_priv);
return sd;
}
inline static SubscriberData *filp_to_sd(struct file *filp);
bool _IsRemoteSubscriberPresent;
int32_t _subscriber_count;
@ -253,11 +230,14 @@ private:
/**
* Check whether a topic appears updated to a subscriber.
*
* Lock must already be held when calling this.
*
* @param sd The subscriber for whom to check.
* @return True if the topic should appear updated to the subscriber
*/
bool appears_updated(SubscriberData *sd);
// disable copy and assignment operators
DeviceNode(const DeviceNode &);
DeviceNode &operator=(const DeviceNode &);
@ -325,5 +305,3 @@ private:
};
#endif

View File

@ -45,7 +45,7 @@
#include <stdlib.h>
uORB::DeviceNode::SubscriberData *uORB::DeviceNode::filp_to_sd(device::file_t *filp)
uORB::DeviceNode::SubscriberData *uORB::DeviceNode::filp_to_sd(device::file_t *filp)
{
uORB::DeviceNode::SubscriberData *sd;
@ -143,11 +143,10 @@ uORB::DeviceNode::open(device::file_t *filp)
add_internal_subscriber();
if (ret != PX4_OK) {
warnx("ERROR: VDev::open failed\n");
PX4_ERR("VDev::open failed");
delete sd;
}
//warnx("uORB::DeviceNode::Open: fd = %d flags = %d, priv = %p cdev = %p\n", filp->fd, filp->flags, filp->priv, filp->cdev);
return ret;
}
@ -158,7 +157,6 @@ uORB::DeviceNode::open(device::file_t *filp)
int
uORB::DeviceNode::close(device::file_t *filp)
{
//warnx("uORB::DeviceNode::close fd = %d", filp->fd);
/* is this the publisher closing? */
if (px4_getpid() == _publisher) {
_publisher = 0;
@ -183,7 +181,6 @@ uORB::DeviceNode::close(device::file_t *filp)
ssize_t
uORB::DeviceNode::read(device::file_t *filp, char *buffer, size_t buflen)
{
//warnx("uORB::DeviceNode::read fd = %d\n", filp->fd);
SubscriberData *sd = (SubscriberData *)filp_to_sd(filp);
/* if the object has not been written yet, return zero */
@ -240,7 +237,6 @@ uORB::DeviceNode::read(device::file_t *filp, char *buffer, size_t buflen)
ssize_t
uORB::DeviceNode::write(device::file_t *filp, const char *buffer, size_t buflen)
{
//warnx("uORB::DeviceNode::write filp = %p (null is normal)", filp);
/*
* Writes are legal from interrupt context as long as the
* object has already been initialised from thread context.
@ -373,14 +369,6 @@ uORB::DeviceNode::ioctl(device::file_t *filp, int cmd, unsigned long arg)
ssize_t
uORB::DeviceNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data)
{
//warnx("uORB::DeviceNode::publish meta = %p", meta);
if (handle == nullptr) {
warnx("uORB::DeviceNode::publish called with invalid handle");
errno = EINVAL;
return ERROR;
}
uORB::DeviceNode *devnode = (uORB::DeviceNode *)handle;
int ret;

View File

@ -31,14 +31,14 @@
*
****************************************************************************/
#ifndef _uORBDevices_posix_hpp_
#define _uORBDevices_posix_hpp_
#pragma once
#include <stdint.h>
#include <string>
#include <map>
#include "uORBCommon.hpp"
namespace uORB
{
class DeviceNode;
@ -46,6 +46,9 @@ class DeviceMaster;
class Manager;
}
/**
* Per-object device instance.
*/
class uORB::DeviceNode : public device::VDev
{
public:
@ -53,12 +56,52 @@ public:
int priority, unsigned int queue_size = 1);
~DeviceNode();
virtual int open(device::file_t *filp);
/**
* Method to create a subscriber instance and return the struct
* pointing to the subscriber as a file pointer.
*/
virtual int open(device::file_t *filp);
/**
* Method to close a subscriber for this topic.
*/
virtual int close(device::file_t *filp);
/**
* reads data from a subscriber node to the buffer provided.
* @param filp
* The subscriber from which the data needs to be read from.
* @param buffer
* The buffer into which the data is read into.
* @param buflen
* the length of the buffer
* @return
* ssize_t the number of bytes read.
*/
virtual ssize_t read(device::file_t *filp, char *buffer, size_t buflen);
/**
* writes the published data to the internal buffer to be read by
* subscribers later.
* @param filp
* the subscriber; this is not used.
* @param buffer
* The buffer for the input data
* @param buflen
* the length of the buffer.
* @return ssize_t
* The number of bytes that are written
*/
virtual ssize_t write(device::file_t *filp, const char *buffer, size_t buflen);
/**
* IOCTL control for the subscriber.
*/
virtual int ioctl(device::file_t *filp, int cmd, unsigned long arg);
/**
* Method to publish a data to this node.
*/
static ssize_t publish(const orb_metadata *meta, orb_advert_t handle, const void *data);
static int unadvertise(orb_advert_t handle);
@ -131,7 +174,7 @@ public:
protected:
virtual pollevent_t poll_state(device::file_t *filp);
virtual void poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events);
virtual void poll_notify_one(px4_pollfd_struct_t *fds, pollevent_t events);
private:
struct UpdateIntervalData {
@ -163,7 +206,7 @@ private:
bool _published; /**< has ever data been published */
unsigned int _queue_size; /**< maximum number of elements in the queue */
static SubscriberData *filp_to_sd(device::file_t *filp);
inline static SubscriberData *filp_to_sd(device::file_t *filp);
int32_t _subscriber_count;
@ -260,4 +303,3 @@ private:
hrt_abstime _last_statistics_output;
};
#endif /* _uORBDeviceNode_posix.hpp */