diff options
-rw-r--r-- | src/examples/subscriber/subscriber.cpp | 4 | ||||
-rw-r--r-- | src/platforms/px4_nodehandle.h | 12 |
2 files changed, 8 insertions, 8 deletions
diff --git a/src/examples/subscriber/subscriber.cpp b/src/examples/subscriber/subscriber.cpp index b87231880..093697d8e 100644 --- a/src/examples/subscriber/subscriber.cpp +++ b/src/examples/subscriber/subscriber.cpp @@ -32,9 +32,9 @@ using namespace px4; /** * This tutorial demonstrates simple receipt of messages over the PX4 middleware system. */ -void rc_channels_callback(const PX4_TOPIC_T(rc_channels) *msg) +void rc_channels_callback(const PX4_TOPIC_T(rc_channels) &msg) { - PX4_INFO("I heard: [%lu]", msg->timestamp_last_valid); + PX4_INFO("I heard: [%lu]", msg.timestamp_last_valid); } namespace px4 { diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index 34a605647..972792d53 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -69,24 +69,24 @@ public: }; template<typename M> - Subscriber subscribe(const char *topic, void(*fp)(M)) { + Subscriber * subscribe(const char *topic, void(*fp)(M)) { ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, fp); - Subscriber sub(ros_sub); + Subscriber * sub = new Subscriber(ros_sub); _subs.push_back(sub); return sub; } template<typename M> - Publisher advertise(const char *topic) { + Publisher * advertise(const char *topic) { ros::Publisher ros_pub = ros::NodeHandle::advertise<M>(topic, kQueueSizeDefault); - Publisher pub(ros_pub); + Publisher *pub = new Publisher(ros_pub); _pubs.push_back(pub); return pub; } private: static const uint32_t kQueueSizeDefault = 1000; - std::list<Subscriber> _subs; - std::list<Publisher> _pubs; + std::list<Subscriber*> _subs; + std::list<Publisher*> _pubs; }; #else class __EXPORT NodeHandle |