From 998646f03b229ae86bd6e57ff0bd15dd1763c342 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 11 Dec 2014 15:33:32 +0100 Subject: add base class and template subscriber class as well to improve interface to get last msg value --- src/platforms/px4_nodehandle.h | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) (limited to 'src/platforms/px4_nodehandle.h') diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index c24a18303..9bd792c69 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -77,13 +77,13 @@ public: * @param fb Callback, executed on receiving a new message */ template - Subscriber *subscribe(const char *topic, void(*fp)(const M&)) + Subscriber *subscribe(const char *topic, void(*fp)(const M&)) { - Subscriber *sub = new SubscriberROS(std::bind(fp, std::placeholders::_1)); + SubscriberBase *sub = new SubscriberROS(std::bind(fp, std::placeholders::_1)); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS::callback, (SubscriberROS*)sub); ((SubscriberROS*)sub)->set_ros_sub(ros_sub); _subs.push_back(sub); - return sub; + return (Subscriber *)sub; } /** @@ -92,13 +92,13 @@ public: * @param fb Callback, executed on receiving a new message */ template - Subscriber *subscribe(const char *topic, void(T::*fp)(const M&), T *obj) + Subscriber *subscribe(const char *topic, void(T::*fp)(const M&), T *obj) { - Subscriber *sub = new SubscriberROS(std::bind(fp, obj, std::placeholders::_1)); + SubscriberBase *sub = new SubscriberROS(std::bind(fp, obj, std::placeholders::_1)); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS::callback, (SubscriberROS*)sub); ((SubscriberROS*)sub)->set_ros_sub(ros_sub); _subs.push_back(sub); - return sub; + return (Subscriber *)sub; } /** @@ -106,13 +106,13 @@ public: * @param topic Name of the topic */ template - Subscriber *subscribe(const char *topic) + Subscriber *subscribe(const char *topic) { - Subscriber *sub = new SubscriberROS(); + SubscriberBase *sub = new SubscriberROS(); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, &SubscriberROS::callback, (SubscriberROS*)sub); ((SubscriberROS*)sub)->set_ros_sub(ros_sub); _subs.push_back(sub); - return sub; + return (Subscriber *)sub; } /** @@ -141,10 +141,10 @@ public: private: static const uint32_t kQueueSizeDefault = 1000; /**< Size of queue for ROS */ - std::list _subs; /**< Subcriptions of node */ - std::list _pubs; /**< Publications of node */ + std::list _subs; /**< Subcriptions of node */ + std::list _pubs; /**< Publications of node */ }; -#else +#else //Building for NuttX class __EXPORT NodeHandle { public: @@ -164,7 +164,7 @@ public: */ template - Subscriber *subscribe(const struct orb_metadata *meta, + Subscriber *subscribe(const struct orb_metadata *meta, std::function callback, unsigned interval) { @@ -175,7 +175,7 @@ public: _sub_min_interval = sub_px4; } - return (Subscriber *)sub_px4; + return (Subscriber *)sub_px4; } /** -- cgit v1.2.3