Browse Source

define default queue size

sbg
Thomas Gubler 10 years ago
parent
commit
0a3492fc32
  1. 3
      src/platforms/px4_nodehandle.h

3
src/platforms/px4_nodehandle.h

@ -41,6 +41,7 @@
#if defined(__linux) || (defined(__APPLE__) && defined(__MACH__)) #if defined(__linux) || (defined(__APPLE__) && defined(__MACH__))
#include "ros/ros.h" #include "ros/ros.h"
#include <list> #include <list>
#define QUEUE_SIZE_DEFAULT 1000
#endif #endif
namespace px4 namespace px4
@ -56,7 +57,7 @@ public:
template<class M> template<class 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, 1000, fp); ros::Subscriber ros_sub = ros::NodeHandle::subscribe(topic, QUEUE_SIZE_DEFAULT, fp);
//XXX create list here, for ros and nuttx //XXX create list here, for ros and nuttx
Subscriber sub(ros_sub); Subscriber sub(ros_sub);
_subs.push_back(sub); _subs.push_back(sub);

Loading…
Cancel
Save