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

how to increase rosserial buffer size

asked 2013-08-18 20:13:45 -0600

dan gravatar image

updated 2014-01-28 17:17:42 -0600

ngrennan gravatar image

I am trying to publish an odometry message with rosserial:

nav_msgs::Odometry myOdom;

ros::Publisher odom_pub("odom", &myOdom); .... odom_pub.publish(&myOdom);

and it compiles fine, but I get an error that the message exceeds the buffer:

[ERROR] [WallTime: 1376891179.350615] Message from device dropped: message larger than buffer.

I saw in the documentation: http://www.ros.org/wiki/rosserial/Overview/Limitations

that the way to increase the buffer was by changing BUFFER_SIZE in the arduino library file ros.h However, there is no such parameter in ros.h. I did find in nodehandle.h the parameters INPUT_SIZE and OUTPUT_SIZE, so I tried changing those from 512 to 1024, but the initial INFO message that comes up still says that the max buffer size is 512.

I searched for where the error message is being sent from and found it also in nodehandle.h and changed it to include in the error note the size of the message I am trying to send. It's possible the odom message is > 512 bytes, but if I can find out how many bytes are trying to be sent, then, once I find BUFFER_SIZE, I will know what it needs to be set to.

That change did not show up in the error, so now I realize that when I am recompiling the arduino code, the changes I made to nodehandle.h are not being incorporated. The file is located in the correct place (...sketchbook/libraries/ros_lib/ros) and I closed and reopened the arduino IDE, so it should pick up the change.

Thanks for the help!

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
1

answered 2013-08-19 00:22:12 -0600

fergs gravatar image

So the proper place to change this is in rosserial_arduino/src/ros.h. The numbers supplied there will overwrite the defaults in node_handle.h. I believe we split the template parameter BUFFER_SIZE into INPUT/OUTPUT_SIZE a while ago and probably forgot to update the docs -- be sure to change the template parameters for the chip you are actually using (note the various #ifdefs for different size AVR chips). Also, if increasing the buffer size, you should probably reduce the number of pubs/subs to keep down overall memory usage.

As for the chagnes not showing up -- perhaps it's not rebuilding due to the header file change? The arduino buildsystem is pretty funky, if you turn on verbose compile/upload under the Preferences menu, you should be able to see where it is putting the built files (typically somewhere under /tmp for linux machines) -- try deleting that folder to force a full rebuild?

edit flag offensive delete link more

Comments

this comment section has character limits so that I had to ask my followup in the form of the "answer" below. Your suggestion to do a verbose build was great-- I had renamed a backup version of ros_lib to ros_lib_old and for some reason it was using the files there.

dan gravatar image dan  ( 2013-08-19 09:51:32 -0600 )edit
5

answered 2017-04-21 00:10:02 -0600

bwlim gravatar image

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.

edit flag offensive delete link more

Comments

Really clear, thank you for that explanation!

mattMGN gravatar image mattMGN  ( 2018-02-25 08:39:54 -0600 )edit
2

answered 2013-08-20 06:39:04 -0600

What board are you using? 512 is the default for the ATmega2650 and ATmega1280. If you want to increase it for these boards, define it in the ros.h according to which board you are using.

edit flag offensive delete link more

Comments

I am using an ATmega2560. Sorry, but how do I define it for that board in ros.h? Perhaps I am being a bit dense here. Is this correct to get 10 pubs, 10 subs, 1024 bytes for pubs, 512 for subs? #elif defined(__AVR_ATmega2560__) typedef NodeHandle_<arduinohardware,10,10,1024,512> NodeHandle;

dan gravatar image dan  ( 2013-08-20 07:19:23 -0600 )edit

That worked, but note that the order of the buffers seems pubs then subs. It now accepts the messages, with this error (opened a new question) raise genpy.DeserializationError(e) #most likely buffer underfill genpy.message.DeserializationError: unpack requires a string argument of length 288

dan gravatar image dan  ( 2013-08-20 07:40:52 -0600 )edit

If I'm using OpenCR board, how do I set the defined name in ros.h?

here's the link to the board info http://emanual.robotis.com/docs/en/pa...

irsyadtc gravatar image irsyadtc  ( 2019-07-24 09:16:46 -0600 )edit
0

answered 2013-08-19 09:50:15 -0600

dan gravatar image

updated 2013-08-19 11:29:15 -0600

Turns out that changing it the values in node_handle.h fixed the problem (once I figured out how to make the arduino IDE compile the correct node_handle.h). But I would like to do this correctly, so can you tell me how do I put it in ros.h? Here is the ros.h file, it makes no reference to those parameters:


> #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

edit flag offensive delete link more

Comments

for the 328; 25, 25, 280, 280 refers to the maximum publishers and subscribers and their respective buffers.

tonybaltovski gravatar image tonybaltovski  ( 2013-08-19 10:15:40 -0600 )edit
1

But that should mean the buffer size is 280, yet the INFO that shows up on execution says 512, or when I changed it in nodehandle.h it shows as 1024 and now processes the message (but, with some errors). Should I use this: typedef NodeHandle_<arduinohardware>10,10,1024,512> NodeHandle;

dan gravatar image dan  ( 2013-08-20 06:17:47 -0600 )edit
1

I've tried changing the values in both node_handle.h and ros.h and it is still giving me the buffer overrun error

Icehawk101 gravatar image Icehawk101  ( 2016-05-04 14:42:23 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2013-08-18 20:13:45 -0600

Seen: 11,903 times

Last updated: Aug 20 '13