aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-26 13:58:59 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-26 13:59:15 +0100
commit5ce3028892a36176ddc8e3aa30d11e4a520b768e (patch)
tree18045c7a2fd60390a9279c7f5b4ce2f0c4d58d48
parent5dacb36d277fe107979555c2a50131944f4c76c4 (diff)
downloadpx4-firmware-ros_messagelayer_merge_attctl_functionptr_nuttx_bringup.tar.gz
px4-firmware-ros_messagelayer_merge_attctl_functionptr_nuttx_bringup.tar.bz2
px4-firmware-ros_messagelayer_merge_attctl_functionptr_nuttx_bringup.zip
-rw-r--r--src/examples/subscriber/subscriber_example.cpp2
-rw-r--r--src/platforms/px4_nodehandle.h27
-rw-r--r--src/platforms/px4_subscriber.h4
3 files changed, 15 insertions, 18 deletions
diff --git a/src/examples/subscriber/subscriber_example.cpp b/src/examples/subscriber/subscriber_example.cpp
index bc0975a2b..79715a234 100644
--- a/src/examples/subscriber/subscriber_example.cpp
+++ b/src/examples/subscriber/subscriber_example.cpp
@@ -75,7 +75,7 @@ SubscriberExample::SubscriberExample() :
_n.subscribe<px4_vehicle_attitude>(&SubscriberExample::vehicle_attitude_callback, this, 1000);
/* Class Method 3 */
- // _n.subscribe<px4_vehicle_rates_setpoint>(&SubscriberExample::vehicle_rates_setpoint_callback, this, 1000);
+ _n.subscribe<px4_vehicle_rates_setpoint>(&SubscriberExample::vehicle_rates_setpoint_callback, this, 1000);
PX4_INFO("subscribed");
}
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h
index 70ec1cfe0..83a3e422d 100644
--- a/src/platforms/px4_nodehandle.h
+++ b/src/platforms/px4_nodehandle.h
@@ -187,14 +187,13 @@ public:
*/
template<typename T>
- // Subscriber<T> *subscribe(void(*fp)(const T &), unsigned interval)
- void subscribe(void(*fp)(const T &), unsigned 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);
- // return (Subscriber<T> *)sub_px4;
+ update_sub_min_interval(interval, sub_px4);
+ _subs.add((SubscriberNode *)sub_px4);
+ return (Subscriber<T> *)sub_px4;
}
/**
@@ -203,14 +202,13 @@ public:
* @param obj pointer class instance
*/
template<typename T, typename C>
- // Subscriber<T> *subscribe(void(C::*fp)(const T &), C *obj, unsigned interval)
- void subscribe(void(C::*fp)(const T &), C *obj, unsigned interval)
+ 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);
- // return (Subscriber<T> *)sub_px4;
+ update_sub_min_interval(interval, sub_px4);
+ _subs.add((SubscriberNode *)sub_px4);
+ return (Subscriber<T> *)sub_px4;
}
/**
@@ -219,14 +217,13 @@ public:
*/
template<typename T>
- // Subscriber<T> *subscribe(unsigned interval)
- void subscribe(unsigned 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);
- // return (Subscriber<T> *)sub_px4;
+ update_sub_min_interval(interval, sub_px4);
+ _subs.add((SubscriberNode *)sub_px4);
+ return (Subscriber<T> *)sub_px4;
}
/**
diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h
index 9f32966dc..6ca35b173 100644
--- a/src/platforms/px4_subscriber.h
+++ b/src/platforms/px4_subscriber.h
@@ -244,8 +244,8 @@ public:
*/
SubscriberUORBCallback(unsigned interval,
std::function<void(const T &)> cbf) :
- SubscriberUORB<T>(interval)//,
- // _cbf(cbf)
+ SubscriberUORB<T>(interval),
+ _cbf(cbf)
{}
virtual ~SubscriberUORBCallback() {};