diff options
author | James Goppert <james.goppert@gmail.com> | 2014-03-16 16:14:56 -0400 |
---|---|---|
committer | James Goppert <james.goppert@gmail.com> | 2014-03-20 12:12:42 -0400 |
commit | fd6590cfa7e14436fa8af6a0569b6382cd39069a (patch) | |
tree | 4edc6f8aac6be73ef92519d352d77645d06decd7 | |
parent | 2c32cdf16bb02a9ae4d47b60cb32553fefb33738 (diff) | |
download | px4-firmware-fd6590cfa7e14436fa8af6a0569b6382cd39069a.tar.gz px4-firmware-fd6590cfa7e14436fa8af6a0569b6382cd39069a.tar.bz2 px4-firmware-fd6590cfa7e14436fa8af6a0569b6382cd39069a.zip |
Moved UOrbPubliction/Subscription to uORB::Publication/Subscription
-rw-r--r-- | src/drivers/md25/md25.cpp | 4 | ||||
-rw-r--r-- | src/drivers/md25/md25.hpp | 4 | ||||
-rw-r--r-- | src/drivers/roboclaw/RoboClaw.cpp | 2 | ||||
-rw-r--r-- | src/drivers/roboclaw/RoboClaw.hpp | 4 | ||||
-rw-r--r-- | src/modules/att_pos_estimator_ekf/KalmanNav.hpp | 16 | ||||
-rw-r--r-- | src/modules/controllib/block/Block.cpp | 8 | ||||
-rw-r--r-- | src/modules/controllib/block/Block.hpp | 16 | ||||
-rw-r--r-- | src/modules/controllib/module.mk | 2 | ||||
-rw-r--r-- | src/modules/controllib/uorb/blocks.hpp | 22 | ||||
-rw-r--r-- | src/modules/uORB/Publication.cpp (renamed from src/modules/controllib/uorb/UOrbPublication.cpp) | 4 | ||||
-rw-r--r-- | src/modules/uORB/Publication.hpp (renamed from src/modules/controllib/uorb/UOrbPublication.hpp) | 33 | ||||
-rw-r--r-- | src/modules/uORB/Subscription.cpp (renamed from src/modules/controllib/uorb/UOrbSubscription.cpp) | 10 | ||||
-rw-r--r-- | src/modules/uORB/Subscription.hpp (renamed from src/modules/controllib/uorb/UOrbSubscription.hpp) | 35 | ||||
-rw-r--r-- | src/modules/uORB/module.mk | 4 |
14 files changed, 81 insertions, 83 deletions
diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index d43e3aef9..6d5e805ea 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -52,7 +52,7 @@ #include <arch/board/board.h> #include <mavlink/mavlink_log.h> -#include <controllib/uorb/UOrbPublication.hpp> +#include </uORB/Publication.hpp> #include <uORB/topics/debug_key_value.h> #include <drivers/drv_hrt.h> @@ -587,7 +587,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu float prev_revolution = md25.getRevolutions1(); // debug publication - control::UOrbPublication<debug_key_value_s> debug_msg(NULL, + uORB::Publication<debug_key_value_s> debug_msg(NULL, ORB_ID(debug_key_value)); // sine wave for motor 1 diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index 1661f67f9..962c6b881 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -46,7 +46,7 @@ #include <poll.h> #include <stdio.h> -#include <controllib/uorb/UOrbSubscription.hpp> +#include <uORB/Subscription.hpp> #include <uORB/topics/actuator_controls.h> #include <drivers/device/i2c.h> @@ -270,7 +270,7 @@ private: struct pollfd _controlPoll; /** actuator controls subscription */ - control::UOrbSubscription<actuator_controls_s> _actuators; + uORB::Subscription<actuator_controls_s> _actuators; // local copy of data from i2c device uint8_t _version; diff --git a/src/drivers/roboclaw/RoboClaw.cpp b/src/drivers/roboclaw/RoboClaw.cpp index d65a9be36..dd5e4d3e0 100644 --- a/src/drivers/roboclaw/RoboClaw.cpp +++ b/src/drivers/roboclaw/RoboClaw.cpp @@ -53,7 +53,7 @@ #include <arch/board/board.h> #include <mavlink/mavlink_log.h> -#include <controllib/uorb/UOrbPublication.hpp> +#include <uORB/Publication.hpp> #include <uORB/topics/debug_key_value.h> #include <drivers/drv_hrt.h> diff --git a/src/drivers/roboclaw/RoboClaw.hpp b/src/drivers/roboclaw/RoboClaw.hpp index e9f35cf95..58994d6fa 100644 --- a/src/drivers/roboclaw/RoboClaw.hpp +++ b/src/drivers/roboclaw/RoboClaw.hpp @@ -45,7 +45,7 @@ #include <poll.h> #include <stdio.h> -#include <controllib/uorb/UOrbSubscription.hpp> +#include <uORB/Subscription.hpp> #include <uORB/topics/actuator_controls.h> #include <drivers/device/i2c.h> @@ -169,7 +169,7 @@ private: struct pollfd _controlPoll; /** actuator controls subscription */ - control::UOrbSubscription<actuator_controls_s> _actuators; + uORB::Subscription<actuator_controls_s> _actuators; // private data float _motor1Position; diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp index 46ee4b6c8..caf93bc78 100644 --- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp +++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp @@ -47,8 +47,8 @@ #include <mathlib/mathlib.h> #include <controllib/blocks.hpp> #include <controllib/block/BlockParam.hpp> -#include <controllib/uorb/UOrbSubscription.hpp> -#include <controllib/uorb/UOrbPublication.hpp> +#include <uORB/Subscription.hpp> +#include <uORB/Publication.hpp> #include <uORB/topics/vehicle_attitude.h> #include <uORB/topics/vehicle_global_position.h> @@ -138,13 +138,13 @@ protected: math::Matrix<3,3> C_nb; /**< direction cosine matrix from body to nav frame */ math::Quaternion q; /**< quaternion from body to nav frame */ // subscriptions - control::UOrbSubscription<sensor_combined_s> _sensors; /**< sensors sub. */ - control::UOrbSubscription<vehicle_gps_position_s> _gps; /**< gps sub. */ - control::UOrbSubscription<parameter_update_s> _param_update; /**< parameter update sub. */ + uORB::Subscription<sensor_combined_s> _sensors; /**< sensors sub. */ + uORB::Subscription<vehicle_gps_position_s> _gps; /**< gps sub. */ + uORB::Subscription<parameter_update_s> _param_update; /**< parameter update sub. */ // publications - control::UOrbPublication<vehicle_global_position_s> _pos; /**< position pub. */ - control::UOrbPublication<vehicle_local_position_s> _localPos; /**< local position pub. */ - control::UOrbPublication<vehicle_attitude_s> _att; /**< attitude pub. */ + uORB::Publication<vehicle_global_position_s> _pos; /**< position pub. */ + uORB::Publication<vehicle_local_position_s> _localPos; /**< local position pub. */ + uORB::Publication<vehicle_attitude_s> _att; /**< attitude pub. */ // time stamps uint64_t _pubTimeStamp; /**< output data publication time stamp */ uint64_t _predictTimeStamp; /**< prediction time stamp */ diff --git a/src/modules/controllib/block/Block.cpp b/src/modules/controllib/block/Block.cpp index b964d40a3..0b4cce979 100644 --- a/src/modules/controllib/block/Block.cpp +++ b/src/modules/controllib/block/Block.cpp @@ -43,8 +43,8 @@ #include "Block.hpp" #include "BlockParam.hpp" -#include "../uorb/UOrbSubscription.hpp" -#include "../uorb/UOrbPublication.hpp" +#include "uORB/Subscription.hpp" +#include "uORB/Publication.hpp" namespace control { @@ -100,7 +100,7 @@ void Block::updateParams() void Block::updateSubscriptions() { - UOrbSubscriptionBase *sub = getSubscriptions().getHead(); + uORB::SubscriptionBase *sub = getSubscriptions().getHead(); int count = 0; while (sub != NULL) { @@ -118,7 +118,7 @@ void Block::updateSubscriptions() void Block::updatePublications() { - UOrbPublicationBase *pub = getPublications().getHead(); + uORB::PublicationBase *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 258701f27..6a8e1b5b9 100644 --- a/src/modules/controllib/block/Block.hpp +++ b/src/modules/controllib/block/Block.hpp @@ -44,6 +44,12 @@ #include "List.hpp" +// forward declaration +namespace uORB { + class SubscriptionBase; + class PublicationBase; +} + namespace control { @@ -55,8 +61,6 @@ static const uint8_t blockNameLengthMax = 80; // forward declaration class BlockParamBase; -class UOrbSubscriptionBase; -class UOrbPublicationBase; class SuperBlock; /** @@ -79,15 +83,15 @@ public: protected: // accessors SuperBlock *getParent() { return _parent; } - List<UOrbSubscriptionBase *> & getSubscriptions() { return _subscriptions; } - List<UOrbPublicationBase *> & getPublications() { return _publications; } + List<uORB::SubscriptionBase *> & getSubscriptions() { return _subscriptions; } + List<uORB::PublicationBase *> & getPublications() { return _publications; } List<BlockParamBase *> & getParams() { return _params; } // attributes const char *_name; SuperBlock *_parent; float _dt; - List<UOrbSubscriptionBase *> _subscriptions; - List<UOrbPublicationBase *> _publications; + List<uORB::SubscriptionBase *> _subscriptions; + List<uORB::PublicationBase *> _publications; List<BlockParamBase *> _params; }; diff --git a/src/modules/controllib/module.mk b/src/modules/controllib/module.mk index d815a8feb..f0139a4b7 100644 --- a/src/modules/controllib/module.mk +++ b/src/modules/controllib/module.mk @@ -37,7 +37,5 @@ SRCS = test_params.c \ block/Block.cpp \ block/BlockParam.cpp \ - uorb/UOrbPublication.cpp \ - uorb/UOrbSubscription.cpp \ uorb/blocks.cpp \ blocks.cpp diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp index 7c80c4b2b..a8a70507e 100644 --- a/src/modules/controllib/uorb/blocks.hpp +++ b/src/modules/controllib/uorb/blocks.hpp @@ -62,8 +62,8 @@ extern "C" { } #include "../blocks.hpp" -#include "UOrbSubscription.hpp" -#include "UOrbPublication.hpp" +#include <uORB/Subscription.hpp> +#include <uORB/Publication.hpp> namespace control { @@ -94,16 +94,16 @@ class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock { protected: // subscriptions - UOrbSubscription<vehicle_attitude_s> _att; - UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd; - UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd; - UOrbSubscription<vehicle_global_position_s> _pos; - UOrbSubscription<position_setpoint_triplet_s> _missionCmd; - UOrbSubscription<manual_control_setpoint_s> _manual; - UOrbSubscription<vehicle_status_s> _status; - UOrbSubscription<parameter_update_s> _param_update; + uORB::Subscription<vehicle_attitude_s> _att; + uORB::Subscription<vehicle_attitude_setpoint_s> _attCmd; + uORB::Subscription<vehicle_rates_setpoint_s> _ratesCmd; + uORB::Subscription<vehicle_global_position_s> _pos; + uORB::Subscription<position_setpoint_triplet_s> _missionCmd; + uORB::Subscription<manual_control_setpoint_s> _manual; + uORB::Subscription<vehicle_status_s> _status; + uORB::Subscription<parameter_update_s> _param_update; // publications - UOrbPublication<actuator_controls_s> _actuators; + uORB::Publication<actuator_controls_s> _actuators; public: BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name); virtual ~BlockUorbEnabledAutopilot(); diff --git a/src/modules/controllib/uorb/UOrbPublication.cpp b/src/modules/uORB/Publication.cpp index f69b39d90..ed67b485d 100644 --- a/src/modules/controllib/uorb/UOrbPublication.cpp +++ b/src/modules/uORB/Publication.cpp @@ -32,8 +32,8 @@ ****************************************************************************/ /** - * @file UOrbPublication.cpp + * @file Publication.cpp * */ -#include "UOrbPublication.hpp" +#include "Publication.hpp" diff --git a/src/modules/controllib/uorb/UOrbPublication.hpp b/src/modules/uORB/Publication.hpp index 6f1f3fc1c..7fa6bcc17 100644 --- a/src/modules/controllib/uorb/UOrbPublication.hpp +++ b/src/modules/uORB/Publication.hpp @@ -32,32 +32,29 @@ ****************************************************************************/ /** - * @file UOrbPublication.h + * @file Publication.h * */ #pragma once #include <uORB/uORB.h> -#include "../block/Block.hpp" -#include "../block/List.hpp" +#include <controllib/block/List.hpp> -namespace control +namespace uORB { -class Block; - /** * Base publication warapper class, used in list traversal * of various publications. */ -class __EXPORT UOrbPublicationBase : public ListNode<control::UOrbPublicationBase *> +class __EXPORT PublicationBase : public ListNode<uORB::PublicationBase *> { public: - UOrbPublicationBase( - List<UOrbPublicationBase *> * list, + PublicationBase( + List<PublicationBase *> * list, const struct orb_metadata *meta) : _meta(meta), _handle(-1) { @@ -71,7 +68,7 @@ public: } } virtual void *getDataVoidPtr() = 0; - virtual ~UOrbPublicationBase() { + virtual ~PublicationBase() { orb_unsubscribe(getHandle()); } const struct orb_metadata *getMeta() { return _meta; } @@ -83,12 +80,12 @@ protected: }; /** - * UOrb Publication wrapper class + * Publication wrapper class */ template<class T> -class UOrbPublication : +class Publication : public T, // this must be first! - public UOrbPublicationBase + public PublicationBase { public: /** @@ -98,13 +95,13 @@ public: * @param meta The uORB metadata (usually from the ORB_ID() macro) * for the topic. */ - UOrbPublication( - List<UOrbPublicationBase *> * list, + Publication( + List<PublicationBase *> * list, const struct orb_metadata *meta) : T(), // initialize data structure to zero - UOrbPublicationBase(list, meta) { + PublicationBase(list, meta) { } - virtual ~UOrbPublication() {} + virtual ~Publication() {} /* * XXX * This function gets the T struct, assuming @@ -115,4 +112,4 @@ public: void *getDataVoidPtr() { return (void *)(T *)(this); } }; -} // namespace control +} // namespace uORB diff --git a/src/modules/controllib/uorb/UOrbSubscription.cpp b/src/modules/uORB/Subscription.cpp index 022cadd24..6e8830708 100644 --- a/src/modules/controllib/uorb/UOrbSubscription.cpp +++ b/src/modules/uORB/Subscription.cpp @@ -32,20 +32,20 @@ ****************************************************************************/ /** - * @file UOrbSubscription.cpp + * @file Subscription.cpp * */ -#include "UOrbSubscription.hpp" +#include "Subscription.hpp" -namespace control +namespace uORB { -bool __EXPORT UOrbSubscriptionBase::updated() +bool __EXPORT SubscriptionBase::updated() { bool isUpdated = false; orb_check(_handle, &isUpdated); return isUpdated; } -} // namespace control +} // namespace uORB diff --git a/src/modules/controllib/uorb/UOrbSubscription.hpp b/src/modules/uORB/Subscription.hpp index d337d89a8..55fb95d51 100644 --- a/src/modules/controllib/uorb/UOrbSubscription.hpp +++ b/src/modules/uORB/Subscription.hpp @@ -32,28 +32,25 @@ ****************************************************************************/ /** - * @file UOrbSubscription.h + * @file Subscription.h * */ #pragma once #include <uORB/uORB.h> -#include "../block/Block.hpp" -#include "../block/List.hpp" +#include <controllib/block/List.hpp> -namespace control +namespace uORB { -class Block; - /** * Base subscription warapper class, used in list traversal * of various subscriptions. */ -class __EXPORT UOrbSubscriptionBase : - public ListNode<control::UOrbSubscriptionBase *> +class __EXPORT SubscriptionBase : + public ListNode<SubscriptionBase *> { public: // methods @@ -64,8 +61,8 @@ public: * @param meta The uORB metadata (usually from the ORB_ID() macro) * for the topic. */ - UOrbSubscriptionBase( - List<UOrbSubscriptionBase *> * list, + SubscriptionBase( + List<SubscriptionBase *> * list, const struct orb_metadata *meta) : _meta(meta), _handle() { @@ -78,7 +75,7 @@ public: } } virtual void *getDataVoidPtr() = 0; - virtual ~UOrbSubscriptionBase() { + virtual ~SubscriptionBase() { orb_unsubscribe(_handle); } // accessors @@ -93,12 +90,12 @@ protected: }; /** - * UOrb Subscription wrapper class + * Subscription wrapper class */ template<class T> -class __EXPORT UOrbSubscription : +class __EXPORT Subscription : public T, // this must be first! - public UOrbSubscriptionBase + public SubscriptionBase { public: /** @@ -109,11 +106,11 @@ public: * for the topic. * @param interval The minimum interval in milliseconds between updates */ - UOrbSubscription( - List<UOrbSubscriptionBase *> * list, + Subscription( + List<SubscriptionBase *> * list, const struct orb_metadata *meta, unsigned interval) : T(), // initialize data structure to zero - UOrbSubscriptionBase(list, meta) { + SubscriptionBase(list, meta) { setHandle(orb_subscribe(getMeta())); orb_set_interval(getHandle(), interval); } @@ -121,7 +118,7 @@ public: /** * Deconstructor */ - virtual ~UOrbSubscription() {} + virtual ~Subscription() {} /* * XXX @@ -134,4 +131,4 @@ public: T getData() { return T(*this); } }; -} // namespace control +} // namespace uORB diff --git a/src/modules/uORB/module.mk b/src/modules/uORB/module.mk index 5ec31ab01..0c29101fe 100644 --- a/src/modules/uORB/module.mk +++ b/src/modules/uORB/module.mk @@ -41,4 +41,6 @@ MODULE_COMMAND = uorb MODULE_STACKSIZE = 4096 SRCS = uORB.cpp \ - objects_common.cpp + objects_common.cpp \ + Publication.cpp \ + Subscription.cpp |