diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index f473bf629e..e228dfca53 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -106,8 +106,6 @@ public: template Subscriber * subscribe(const struct orb_metadata *meta, std::function callback) { - // Subscriber * subscribe(const struct orb_metadata *meta, std::function callback) { - // Subscriber * subscribe(const struct orb_metadata *meta, CallbackFunction callback) { unsigned interval = 0;//XXX decide how to wrap this, ros equivalent? //XXX Subscriber *sub = new SubscriberPX4(meta, interval, callback, &_subs); @@ -124,7 +122,9 @@ public: void spinOnce(); void spin() { - //XXX: call callbacks and do not return until task is terminated + while (true) { //XXX + spinOnce(); + } } private: static const uint16_t kMaxSubscriptions = 100; diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h index 71c3a766db..efec8f2a39 100644 --- a/src/platforms/px4_subscriber.h +++ b/src/platforms/px4_subscriber.h @@ -80,11 +80,10 @@ public: SubscriberPX4(const struct orb_metadata *meta, unsigned interval, std::function callback, - // std::function callback, - // CallbackFunction callback, List * list) : Subscriber(), - uORB::Subscription(meta, interval, list) + uORB::Subscription(meta, interval, list), + _callback(callback) //XXX store callback {} ~SubscriberPX4() {}; @@ -94,13 +93,11 @@ public: uORB::Subscription::update(); /* Call callback which performs actions based on this data */ - // _callback(); + _callback(uORB::Subscription::getData()); }; private: - // std::function _callback; - // CallbackFunction _callback; - std::function _callback; + std::function _callback; }; #endif