aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_nodehandle.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-22 09:30:43 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-22 09:30:43 +0100
commit8c4fce3654bbf4cb31314f1fb596f4fd17772589 (patch)
treebaf3d096173055675b1fbc7362e0756eec69918c /src/platforms/px4_nodehandle.h
parent2af44f5995dd121a7ce2aefd3ab1c7d8dcf3fb8d (diff)
downloadpx4-firmware-8c4fce3654bbf4cb31314f1fb596f4fd17772589.tar.gz
px4-firmware-8c4fce3654bbf4cb31314f1fb596f4fd17772589.tar.bz2
px4-firmware-8c4fce3654bbf4cb31314f1fb596f4fd17772589.zip
multiplatform: better publisher base class
Diffstat (limited to 'src/platforms/px4_nodehandle.h')
-rw-r--r--src/platforms/px4_nodehandle.h14
1 files changed, 7 insertions, 7 deletions
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h
index 8fafa168a..a25d57845 100644
--- a/src/platforms/px4_nodehandle.h
+++ b/src/platforms/px4_nodehandle.h
@@ -124,12 +124,12 @@ public:
* Advertise topic
*/
template<typename T>
- Publisher* advertise()
+ Publisher<T>* advertise()
{
ros::Publisher ros_pub = ros::NodeHandle::advertise<typename std::remove_reference<decltype(((T*)nullptr)->data())>::type &>(T::handle(), kQueueSizeDefault);
- Publisher *pub = new Publisher(ros_pub);
- _pubs.push_back(pub);
- return pub;
+ PublisherROS<T> *pub = new PublisherROS<T>(ros_pub);
+ _pubs.push_back((PublisherBase*)pub);
+ return (Publisher<T>*)pub;
}
/**
@@ -236,16 +236,16 @@ public:
* Advertise topic
*/
template<typename T>
- Publisher *advertise()
+ Publisher<T> *advertise()
{
//XXX
// uORB::PublicationBase * uorb_pub = new uORB::PublicationBase((new T())->handle());
uORB::PublicationBase * uorb_pub = new uORB::PublicationBase(T::handle());
- Publisher *pub = new Publisher(uorb_pub);
+ PublisherUORB<T> *pub = new PublisherUORB<T>(uorb_pub);
_pubs.add(pub);
- return pub;
+ return (Publisher<T>*)pub;
}
/**