From b2a911b88d6a541218ef6e633be0d6693de31c8e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 22 Jan 2015 17:10:20 +0100 Subject: uorb wrapper port callback to methods and subscriber without callback --- src/platforms/px4_nodehandle.h | 53 +++++++++++++++++++++++++++++------------- 1 file changed, 37 insertions(+), 16 deletions(-) diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index e619623b9..d78c865de 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -81,8 +81,7 @@ public: template Subscriber *subscribe(void(*fp)(const T &)) { - SubscriberBase *sub = new SubscriberROS(std::bind(fp, std::placeholders::_1)); - ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault, + SubscriberBase *sub = new SubscriberROS(std::bind(fp, std::placeholders::_1)); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault, &SubscriberROS::callback, (SubscriberROS *)sub); ((SubscriberROS *)sub)->set_ros_sub(ros_sub); _subs.push_back(sub); @@ -99,7 +98,8 @@ public: { SubscriberBase *sub = new SubscriberROS(std::bind(fp, obj, std::placeholders::_1)); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(T::handle(), kQueueSizeDefault, - &SubscriberROS::callback, (SubscriberROS *)sub); + &SubscriberROS::callback, (SubscriberROS *)sub);//XXX needs cleanup in destructor ore move into class + ((SubscriberROS *)sub)->set_ros_sub(ros_sub); _subs.push_back(sub); return (Subscriber *)sub; @@ -199,7 +199,7 @@ public: template Subscriber *subscribe(void(*fp)(const T &), unsigned interval=10) //XXX interval { - uORB::SubscriptionBase * uorb_sub = new uORB::SubscriptionBase(T::handle(), interval); + uORB::SubscriptionBase * uorb_sub = new uORB::SubscriptionBase(T::handle(), interval);//XXX needs cleanup in destructor ore move into class SubscriberUORBCallback *sub_px4 = new SubscriberUORBCallback(uorb_sub, interval, std::bind(fp, std::placeholders::_1)); /* Check if this is the smallest interval so far and update _sub_min_interval */ @@ -211,25 +211,46 @@ public: return (Subscriber *)sub_px4; } + /** + * Subscribe with callback to class method + * @param fb Callback, executed on receiving a new message + * @param obj pointer class instance + */ + template + Subscriber *subscribe(void(C::*fp)(const T &), C *obj, unsigned interval=10) + { + uORB::SubscriptionBase * uorb_sub = new uORB::SubscriptionBase(T::handle(), interval);//XXX needs cleanup in destructor ore move into class + SubscriberUORBCallback *sub_px4 = new SubscriberUORBCallback(uorb_sub, interval, std::bind(fp, obj, std::placeholders::_1)); + + /* Check if this is the smallest interval so far and update _sub_min_interval */ + if (_sub_min_interval == nullptr || _sub_min_interval->get_interval() > interval) { + _sub_min_interval = sub_px4; + } + _subs.add((SubscriberNode *)sub_px4); + + return (Subscriber *)sub_px4; + } + /** * Subscribe without callback to function - * @param meta Describes the topic which nodehande should subscribe to * @param interval Minimal interval between data fetches from orb */ - // template - // Subscriber *subscribe(const struct orb_metadata *meta, - // unsigned interval) - // { - // SubscriberUORB *sub_px4 = new SubscriberUORB(meta, interval, &_subs); + template + Subscriber *subscribe(unsigned interval=10) //XXX interval + { + uORB::SubscriptionBase * uorb_sub = new uORB::SubscriptionBase(T::handle(), interval);//XXX needs cleanup in destructor ore move into class - // [> Check if this is the smallest interval so far and update _sub_min_interval <] - // if (_sub_min_interval == nullptr || _sub_min_interval->getInterval() > sub_px4->getInterval()) { - // _sub_min_interval = sub_px4; - // } + SubscriberUORB *sub_px4 = new SubscriberUORB(uorb_sub, interval); - // return (Subscriber *)sub_px4; - // } + /* Check if this is the smallest interval so far and update _sub_min_interval */ + if (_sub_min_interval == nullptr || _sub_min_interval->get_interval() > interval) { + _sub_min_interval = sub_px4; + } + _subs.add((SubscriberNode *)sub_px4); + + return (Subscriber *)sub_px4; + } /** * Advertise topic -- cgit v1.2.3