aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-11-25 10:49:29 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-11-25 10:49:29 +0100
commit5b80a2ae38121f8e3aa81b60ec594979f764ee38 (patch)
treea5b58c326688cd847a44661624fb455b88f47f84
parentc37ff71e625310cdc777719a04c3702d9afa1f7f (diff)
parent72f9fab4a22bd96ad83aced62a481b484b2d69bc (diff)
downloadpx4-firmware-5b80a2ae38121f8e3aa81b60ec594979f764ee38.tar.gz
px4-firmware-5b80a2ae38121f8e3aa81b60ec594979f764ee38.tar.bz2
px4-firmware-5b80a2ae38121f8e3aa81b60ec594979f764ee38.zip
Merge remote-tracking branch 'upstream/pr/1040' into uorbtinymerge
Conflicts: mavlink/include/mavlink/v1.0 src/modules/mc_att_control/mc_att_control_main.cpp
-rw-r--r--src/drivers/roboclaw/RoboClaw.cpp2
-rw-r--r--src/modules/controllib/block/Block.cpp4
-rw-r--r--src/modules/controllib/block/Block.hpp12
-rw-r--r--src/modules/controllib/uorb/blocks.cpp18
-rw-r--r--src/modules/uORB/Publication.cpp6
-rw-r--r--src/modules/uORB/Publication.hpp96
-rw-r--r--src/modules/uORB/Subscription.cpp16
-rw-r--r--src/modules/uORB/Subscription.hpp110
8 files changed, 195 insertions, 69 deletions
diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp
index fdaa7f27b..eb9453b50 100644
--- a/src/drivers/roboclaw/RoboClaw.cpp
+++ b/src/drivers/roboclaw/RoboClaw.cpp
@@ -65,7 +65,7 @@ RoboClaw::RoboClaw(const char *deviceName, uint16_t address,
_pulsesPerRev(pulsesPerRev),
_uart(0),
_controlPoll(),
- _actuators(NULL, ORB_ID(actuator_controls_0), 20),
+ _actuators(ORB_ID(actuator_controls_0), 20),
_motor1Position(0),
_motor1Speed(0),
_motor1Overflow(0),
diff --git a/src/modules/controllib/block/Block.cpp b/src/modules/controllib/block/Block.cpp
index 6768bfa7e..f3cd87728 100644
--- a/src/modules/controllib/block/Block.cpp
+++ b/src/modules/controllib/block/Block.cpp
@@ -101,7 +101,7 @@ void Block::updateParams()
void Block::updateSubscriptions()
{
- uORB::SubscriptionBase *sub = getSubscriptions().getHead();
+ uORB::SubscriptionNode *sub = getSubscriptions().getHead();
int count = 0;
while (sub != NULL) {
@@ -119,7 +119,7 @@ void Block::updateSubscriptions()
void Block::updatePublications()
{
- uORB::PublicationBase *pub = getPublications().getHead();
+ uORB::PublicationNode *pub = getPublications().getHead();
int count = 0;
while (pub != NULL) {
diff --git a/src/modules/controllib/block/Block.hpp b/src/modules/controllib/block/Block.hpp
index 9bd80b15b..d2f9cdf07 100644
--- a/src/modules/controllib/block/Block.hpp
+++ b/src/modules/controllib/block/Block.hpp
@@ -46,8 +46,8 @@
// forward declaration
namespace uORB {
- class SubscriptionBase;
- class PublicationBase;
+ class SubscriptionNode;
+ class PublicationNode;
}
namespace control
@@ -83,15 +83,15 @@ public:
protected:
// accessors
SuperBlock *getParent() { return _parent; }
- List<uORB::SubscriptionBase *> & getSubscriptions() { return _subscriptions; }
- List<uORB::PublicationBase *> & getPublications() { return _publications; }
+ List<uORB::SubscriptionNode *> & getSubscriptions() { return _subscriptions; }
+ List<uORB::PublicationNode *> & getPublications() { return _publications; }
List<BlockParamBase *> & getParams() { return _params; }
// attributes
const char *_name;
SuperBlock *_parent;
float _dt;
- List<uORB::SubscriptionBase *> _subscriptions;
- List<uORB::PublicationBase *> _publications;
+ List<uORB::SubscriptionNode *> _subscriptions;
+ List<uORB::PublicationNode *> _publications;
List<BlockParamBase *> _params;
private:
diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp
index e8fecef0d..454d0db19 100644
--- a/src/modules/controllib/uorb/blocks.cpp
+++ b/src/modules/controllib/uorb/blocks.cpp
@@ -82,16 +82,16 @@ void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
SuperBlock(parent, name),
// subscriptions
- _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
- _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
- _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
- _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
- _missionCmd(&getSubscriptions(), ORB_ID(position_setpoint_triplet), 20),
- _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
- _status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
- _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
+ _att(ORB_ID(vehicle_attitude), 20, &getSubscriptions()),
+ _attCmd(ORB_ID(vehicle_attitude_setpoint), 20, &getSubscriptions()),
+ _ratesCmd(ORB_ID(vehicle_rates_setpoint), 20, &getSubscriptions()),
+ _pos(ORB_ID(vehicle_global_position), 20, &getSubscriptions()),
+ _missionCmd(ORB_ID(position_setpoint_triplet), 20, &getSubscriptions()),
+ _manual(ORB_ID(manual_control_setpoint), 20, &getSubscriptions()),
+ _status(ORB_ID(vehicle_status), 20, &getSubscriptions()),
+ _param_update(ORB_ID(parameter_update), 1000, &getSubscriptions()), // limit to 1 Hz
// publications
- _actuators(&getPublications(), ORB_ID(actuator_controls_0))
+ _actuators(ORB_ID(actuator_controls_0), &getPublications())
{
}
diff --git a/src/modules/uORB/Publication.cpp b/src/modules/uORB/Publication.cpp
index cd0b30dd6..fd5c511ef 100644
--- a/src/modules/uORB/Publication.cpp
+++ b/src/modules/uORB/Publication.cpp
@@ -53,10 +53,10 @@ namespace uORB {
template<class T>
Publication<T>::Publication(
- List<PublicationBase *> * list,
- const struct orb_metadata *meta) :
+ const struct orb_metadata *meta,
+ List<PublicationNode *> * list) :
T(), // initialize data structure to zero
- PublicationBase(list, meta) {
+ PublicationNode(meta, list) {
}
template<class T>
diff --git a/src/modules/uORB/Publication.hpp b/src/modules/uORB/Publication.hpp
index 8650b3df8..1c48929e4 100644
--- a/src/modules/uORB/Publication.hpp
+++ b/src/modules/uORB/Publication.hpp
@@ -38,6 +38,8 @@
#pragma once
+#include <assert.h>
+
#include <uORB/uORB.h>
#include <containers/List.hpp>
@@ -49,55 +51,112 @@ namespace uORB
* Base publication warapper class, used in list traversal
* of various publications.
*/
-class __EXPORT PublicationBase : public ListNode<uORB::PublicationBase *>
+class __EXPORT PublicationBase
{
public:
- PublicationBase(
- List<PublicationBase *> * list,
- const struct orb_metadata *meta) :
+ /**
+ * Constructor
+ *
+ *
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ */
+ PublicationBase(const struct orb_metadata *meta) :
_meta(meta),
_handle(-1) {
- if (list != NULL) list->add(this);
}
- void update() {
+
+ /**
+ * Update the struct
+ * @param data The uORB message struct we are updating.
+ */
+ void update(void * data) {
if (_handle > 0) {
- orb_publish(getMeta(), getHandle(), getDataVoidPtr());
+ orb_publish(getMeta(), getHandle(), data);
} else {
- setHandle(orb_advertise(getMeta(), getDataVoidPtr()));
+ setHandle(orb_advertise(getMeta(), data));
}
}
- virtual void *getDataVoidPtr() = 0;
+
+ /**
+ * Deconstructor
+ */
virtual ~PublicationBase() {
orb_unsubscribe(getHandle());
}
+// accessors
const struct orb_metadata *getMeta() { return _meta; }
int getHandle() { return _handle; }
protected:
+// accessors
void setHandle(orb_advert_t handle) { _handle = handle; }
+// attributes
const struct orb_metadata *_meta;
orb_advert_t _handle;
};
+/**
+ * alias class name so it is clear that the base class
+ * can be used by itself if desired
+ */
+typedef PublicationBase PublicationTiny;
+
+/**
+ * The publication base class as a list node.
+ */
+class __EXPORT PublicationNode :
+ public PublicationBase,
+ public ListNode<PublicationNode *>
+{
+public:
+ /**
+ * Constructor
+ *
+ *
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ * @param list A pointer to a list of subscriptions
+ * that this should be appended to.
+ */
+ PublicationNode(const struct orb_metadata *meta,
+ List<PublicationNode *> * list=nullptr) :
+ PublicationBase(meta) {
+ if (list != nullptr) list->add(this);
+ }
+
+ /**
+ * This function is the callback for list traversal
+ * updates, a child class must implement it.
+ */
+ virtual void update() = 0;
+};
+
/**
* Publication wrapper class
*/
template<class T>
class Publication :
public T, // this must be first!
- public PublicationBase
+ public PublicationNode
{
public:
/**
* Constructor
*
- * @param list A list interface for adding to list during construction
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
+ * @param meta The uORB metadata (usually from
+ * the ORB_ID() macro) for the topic.
+ * @param list A list interface for adding to
+ * list during construction
*/
- Publication(List<PublicationBase *> * list,
- const struct orb_metadata *meta);
+ Publication(const struct orb_metadata *meta,
+ List<PublicationNode *> * list=nullptr);
+
+ /**
+ * Deconstructor
+ **/
virtual ~Publication();
+
/*
* XXX
* This function gets the T struct, assuming
@@ -106,6 +165,13 @@ public:
* seem to be available
*/
void *getDataVoidPtr();
+
+ /**
+ * Create an update function that uses the embedded struct.
+ */
+ void update() {
+ PublicationBase::update(getDataVoidPtr());
+ }
};
} // namespace uORB
diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp
index 44b6debc7..69969307e 100644
--- a/src/modules/uORB/Subscription.cpp
+++ b/src/modules/uORB/Subscription.cpp
@@ -56,21 +56,13 @@
namespace uORB
{
-bool __EXPORT SubscriptionBase::updated()
-{
- bool isUpdated = false;
- orb_check(_handle, &isUpdated);
- return isUpdated;
-}
-
template<class T>
Subscription<T>::Subscription(
- List<SubscriptionBase *> * list,
- const struct orb_metadata *meta, unsigned interval) :
+ const struct orb_metadata *meta,
+ unsigned interval,
+ List<SubscriptionNode *> * list) :
T(), // initialize data structure to zero
- SubscriptionBase(list, meta) {
- setHandle(orb_subscribe(getMeta()));
- orb_set_interval(getHandle(), interval);
+ SubscriptionNode(meta, interval, list) {
}
template<class T>
diff --git a/src/modules/uORB/Subscription.hpp b/src/modules/uORB/Subscription.hpp
index 34e9a83e0..bab1ef2ea 100644
--- a/src/modules/uORB/Subscription.hpp
+++ b/src/modules/uORB/Subscription.hpp
@@ -38,10 +38,11 @@
#pragma once
+#include <assert.h>
+
#include <uORB/uORB.h>
#include <containers/List.hpp>
-
namespace uORB
{
@@ -49,8 +50,7 @@ namespace uORB
* Base subscription warapper class, used in list traversal
* of various subscriptions.
*/
-class __EXPORT SubscriptionBase :
- public ListNode<SubscriptionBase *>
+class __EXPORT SubscriptionBase
{
public:
// methods
@@ -58,23 +58,42 @@ public:
/**
* Constructor
*
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ *
+ * @param interval The minimum interval in milliseconds
+ * between updates
*/
- SubscriptionBase(
- List<SubscriptionBase *> * list,
- const struct orb_metadata *meta) :
+ SubscriptionBase(const struct orb_metadata *meta,
+ unsigned interval=0) :
_meta(meta),
_handle() {
- if (list != NULL) list->add(this);
+ setHandle(orb_subscribe(getMeta()));
+ orb_set_interval(getHandle(), interval);
}
- bool updated();
- void update() {
+
+ /**
+ * Check if there is a new update.
+ * */
+ bool updated() {
+ bool isUpdated = false;
+ orb_check(_handle, &isUpdated);
+ return isUpdated;
+ }
+
+ /**
+ * Update the struct
+ * @param data The uORB message struct we are updating.
+ */
+ void update(void * data) {
if (updated()) {
- orb_copy(_meta, _handle, getDataVoidPtr());
+ orb_copy(_meta, _handle, data);
}
}
- virtual void *getDataVoidPtr() = 0;
+
+ /**
+ * Deconstructor
+ */
virtual ~SubscriptionBase() {
orb_unsubscribe(_handle);
}
@@ -90,30 +109,79 @@ protected:
};
/**
+ * alias class name so it is clear that the base class
+ */
+typedef SubscriptionBase SubscriptionTiny;
+
+/**
+ * The publication base class as a list node.
+ */
+class __EXPORT SubscriptionNode :
+
+ public SubscriptionBase,
+ public ListNode<SubscriptionNode *>
+{
+public:
+ /**
+ * Constructor
+ *
+ *
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ * @param interval The minimum interval in milliseconds
+ * between updates
+ * @param list A pointer to a list of subscriptions
+ * that this should be appended to.
+ */
+ SubscriptionNode(const struct orb_metadata *meta,
+ unsigned interval=0,
+ List<SubscriptionNode *> * list=nullptr) :
+ SubscriptionBase(meta, interval) {
+ if (list != nullptr) list->add(this);
+ }
+
+ /**
+ * This function is the callback for list traversal
+ * updates, a child class must implement it.
+ */
+ virtual void update() = 0;
+};
+
+/**
* Subscription wrapper class
*/
template<class T>
class __EXPORT Subscription :
public T, // this must be first!
- public SubscriptionBase
+ public SubscriptionNode
{
public:
/**
* Constructor
*
- * @param list A list interface for adding to list during construction
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
- * @param interval The minimum interval in milliseconds between updates
+ * @param meta The uORB metadata (usually from
+ * the ORB_ID() macro) for the topic.
+ * @param interval The minimum interval in milliseconds
+ * between updates
+ * @param list A list interface for adding to
+ * list during construction
*/
- Subscription(
- List<SubscriptionBase *> * list,
- const struct orb_metadata *meta, unsigned interval);
+ Subscription(const struct orb_metadata *meta,
+ unsigned interval=0,
+ List<SubscriptionNode *> * list=nullptr);
/**
* Deconstructor
*/
virtual ~Subscription();
+
+ /**
+ * Create an update function that uses the embedded struct.
+ */
+ void update() {
+ SubscriptionBase::update(getDataVoidPtr());
+ }
+
/*
* XXX
* This function gets the T struct, assuming