aboutsummaryrefslogtreecommitdiff
path: root/src/platforms
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-23 09:02:04 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-23 09:02:04 +0100
commitda7ad9a3329db43144b5ca3e60c6c56d22fdc3d4 (patch)
tree841ff98c149f1df687838f123ca096336e9399a7 /src/platforms
parentaf943cf16adb79ab33097bd560a85fee203a5215 (diff)
downloadpx4-firmware-da7ad9a3329db43144b5ca3e60c6c56d22fdc3d4.tar.gz
px4-firmware-da7ad9a3329db43144b5ca3e60c6c56d22fdc3d4.tar.bz2
px4-firmware-da7ad9a3329db43144b5ca3e60c6c56d22fdc3d4.zip
multiplatform: re-enable interval functionality (for uorb)
Diffstat (limited to 'src/platforms')
-rw-r--r--src/platforms/px4_nodehandle.h15
1 files changed, 9 insertions, 6 deletions
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h
index 2f92ead5a..80be9ec52 100644
--- a/src/platforms/px4_nodehandle.h
+++ b/src/platforms/px4_nodehandle.h
@@ -79,7 +79,7 @@ public:
* @param fb Callback, executed on receiving a new message
*/
template<typename T>
- Subscriber<T> *subscribe(void(*fp)(const T &))
+ Subscriber<T> *subscribe(void(*fp)(const T &), unsigned interval)
{
SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this, std::bind(fp, std::placeholders::_1));
_subs.push_back(sub);
@@ -92,7 +92,7 @@ public:
* @param obj pointer class instance
*/
template<typename T, typename C>
- Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj)
+ Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj, unsigned interval)
{
SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this, std::bind(fp, obj, std::placeholders::_1));
_subs.push_back(sub);
@@ -103,7 +103,7 @@ public:
* Subscribe with no callback, just the latest value is stored on updates
*/
template<typename T>
- Subscriber<T> *subscribe()
+ Subscriber<T> *subscribe(unsigned interval)
{
SubscriberBase *sub = new SubscriberROS<T>((ros::NodeHandle*)this);
_subs.push_back(sub);
@@ -186,8 +186,9 @@ public:
*/
template<typename T>
- Subscriber<T> *subscribe(void(*fp)(const T &), unsigned interval=10) //XXX interval
+ Subscriber<T> *subscribe(void(*fp)(const T &), unsigned interval)
{
+ (void)interval;
SubscriberUORBCallback<T> *sub_px4 = new SubscriberUORBCallback<T>(interval, std::bind(fp, std::placeholders::_1));
update_sub_min_interval(interval, sub_px4);
_subs.add((SubscriberNode *)sub_px4);
@@ -200,8 +201,9 @@ public:
* @param obj pointer class instance
*/
template<typename T, typename C>
- Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj, unsigned interval=10)
+ Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj, unsigned interval)
{
+ (void)interval;
SubscriberUORBCallback<T> *sub_px4 = new SubscriberUORBCallback<T>(interval, std::bind(fp, obj, std::placeholders::_1));
update_sub_min_interval(interval, sub_px4);
_subs.add((SubscriberNode *)sub_px4);
@@ -214,8 +216,9 @@ public:
*/
template<typename T>
- Subscriber<T> *subscribe(unsigned interval=10) //XXX interval
+ Subscriber<T> *subscribe(unsigned interval)
{
+ (void)interval;
SubscriberUORB<T> *sub_px4 = new SubscriberUORB<T>(interval);
update_sub_min_interval(interval, sub_px4);
_subs.add((SubscriberNode *)sub_px4);