diff options
author | Thomas Gubler <thomasgubler@gmail.com> | 2014-11-25 10:19:18 +0100 |
---|---|---|
committer | Thomas Gubler <thomasgubler@gmail.com> | 2014-11-25 10:19:18 +0100 |
commit | c167df90380fdd99d1b56024c4de104a3f0a2f85 (patch) | |
tree | 8eb7266eb1813398b8da656fa8c63b10d79df1e0 /src/platforms/px4_nodehandle.h | |
parent | 978013bbb8d67e295d92a54e16f7728013722e92 (diff) | |
download | px4-firmware-c167df90380fdd99d1b56024c4de104a3f0a2f85.tar.gz px4-firmware-c167df90380fdd99d1b56024c4de104a3f0a2f85.tar.bz2 px4-firmware-c167df90380fdd99d1b56024c4de104a3f0a2f85.zip |
ros wrapper: small reordering
Diffstat (limited to 'src/platforms/px4_nodehandle.h')
-rw-r--r-- | src/platforms/px4_nodehandle.h | 14 |
1 files changed, 11 insertions, 3 deletions
diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index bfda636b0..d66884445 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -37,12 +37,19 @@ * PX4 Middleware Wrapper Node Handle */ #pragma once + +/* includes for all platforms */ #include <px4_subscriber.h> #include <px4_publisher.h> + #if defined(__linux) || (defined(__APPLE__) && defined(__MACH__)) +/* includes when building for ros */ #include "ros/ros.h" #include <list> -#define QUEUE_SIZE_DEFAULT 1000 +#include <inttypes.h> +#else +/* includes when building for NuttX */ + #endif namespace px4 @@ -59,7 +66,7 @@ public: template<typename M> Subscriber subscribe(const char *topic, void(*fp)(M)) { - ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, QUEUE_SIZE_DEFAULT, fp); + ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, kQueueSizeDefault, fp); Subscriber sub(ros_sub); _subs.push_back(sub); return sub; @@ -67,12 +74,13 @@ public: template<typename M> Publisher advertise(const char *topic) { - ros::Publisher ros_pub = ros::NodeHandle::advertise<M>(topic, QUEUE_SIZE_DEFAULT); + ros::Publisher ros_pub = ros::NodeHandle::advertise<M>(topic, kQueueSizeDefault); Publisher pub(ros_pub); _pubs.push_back(pub); return pub; } private: + static const uint32_t kQueueSizeDefault = 1000; std::list<Subscriber> _subs; std::list<Publisher> _pubs; }; |