ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I found this thread a bit hard to follow, but managed to figure out how to fix the problem. This is assuming you have the same error when using nav_msgs/odometry.

Wherever your Arduino libraries are located, there should be a folder for your ROS libraries. When you first installed ROS, it was named 'ros_lib', In this folder, you'll find 'ros.h', as well as 'node_handle.h' in a folder called 'ros'.

[Arduino Libraries] ---> ros_lib ---> ros.h

[Arduino Libraries] ---> ros_lib ---> ros ---> node_handle.h

The relevant portion of the ros.h file looks like:

#ifndef _ROS_H_
#define _ROS_H_

#include "ros/node_handle.h"
#include "ArduinoHardware.h"

namespace ros
{
#if defined(__AVR_ATmega8__) || defined(__AVR_ATmega168__)
  /* downsize our buffers */
  typedef NodeHandle_<ArduinoHardware, 6, 6, 150, 150> NodeHandle;

#elif defined(__AVR_ATmega328P__)

  typedef NodeHandle_<ArduinoHardware, 25, 25, 280, 280> NodeHandle;

#else

  typedef NodeHandle_<ArduinoHardware> NodeHandle;

#endif   
}

#endif

Assuming you're using the Atmega2560, you can paste this between the #elif and #else. The numbers define in order [MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE].

#elif defined(__AVR_ATmega2560__)

  typedef NodeHandle_<ArduinoHardware, 15, 15, 512, 1024> NodeHandle;

I believe this method was the proper place to change the buffer sizes, as mentioned by fergs.

An alternative solution is to alter node_handle.h instead. It seems like this is what the OP dan ended up doing.

The relevant portion of the node_handle.h file looks like:

namespace ros {

  using rosserial_msgs::TopicInfo;

  /* Node Handle */
  template<class Hardware,
           int MAX_SUBSCRIBERS=25,
           int MAX_PUBLISHERS=25,
           int INPUT_SIZE=512,
           int OUTPUT_SIZE=512>
  class NodeHandle_ : public NodeHandleBase_
  {

Here, you can change the OUTPUT_SIZE from 512 to 1024. I personally had to decrease MAX_SUBSCRIBERS and MAX_PUBLISHERS and publishers from 25 to 15, otherwise my rosserial node wouldn't work.

After doing this, save the file you editted and recompile/upload your Arduino code, and it should eliminate the buffer size error from using nav_msgs/odometry.