aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_subscriber.h
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2015-01-23 08:03:26 +0100
committerThomas Gubler <thomasgubler@gmail.com>2015-01-23 08:12:46 +0100
commit16c85c6d1870f6f410cf75fc0fe3cb386eb9f6ee (patch)
tree88b175f99a908194eca02079a8e55279e4904a4b /src/platforms/px4_subscriber.h
parent59f05a7195ae4a2d57e276c31e12bcf6af477408 (diff)
downloadpx4-firmware-16c85c6d1870f6f410cf75fc0fe3cb386eb9f6ee.tar.gz
px4-firmware-16c85c6d1870f6f410cf75fc0fe3cb386eb9f6ee.tar.bz2
px4-firmware-16c85c6d1870f6f410cf75fc0fe3cb386eb9f6ee.zip
move uorb::publisherbase into constructor of publisher
Diffstat (limited to 'src/platforms/px4_subscriber.h')
-rw-r--r--src/platforms/px4_subscriber.h7
1 files changed, 4 insertions, 3 deletions
diff --git a/src/platforms/px4_subscriber.h b/src/platforms/px4_subscriber.h
index e086cd4c2..17a95f12d 100644
--- a/src/platforms/px4_subscriber.h
+++ b/src/platforms/px4_subscriber.h
@@ -107,21 +107,22 @@ public:
SubscriberROS(ros::NodeHandle *rnh) :
px4::Subscriber<T>(),
_cbf(NULL),
- _ros_sub(rnh->subscribe(T::handle(), 1, &SubscriberROS<T>::callback, this))
+ _ros_sub(rnh->subscribe(T::handle(), kQueueSizeDefault, &SubscriberROS<T>::callback, this))
{}
/**
* Construct Subscriber by providing a callback function
*/
- //XXX queue default
SubscriberROS(ros::NodeHandle *rnh, std::function<void(const T &)> cbf) :
_cbf(cbf),
- _ros_sub(rnh->subscribe(T::handle(), 1, &SubscriberROS<T>::callback, this))
+ _ros_sub(rnh->subscribe(T::handle(), kQueueSizeDefault, &SubscriberROS<T>::callback, this))
{}
virtual ~SubscriberROS() {};
protected:
+ static const uint32_t kQueueSizeDefault = 1; /**< Size of queue for ROS */
+
/**
* Called on topic update, saves the current message and then calls the provided callback function
* needs to use the native type as it is called by ROS