aboutsummaryrefslogtreecommitdiff
path: root/src/platforms/px4_subscriber.h
diff options
context:
space:
mode:
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