rosserial
rosserial copied to clipboard
Buffersize for Arduino Micro (ATmega32U4)
hi everyone,
I'am part of a small team and we are using ROS and rosserial for our two Arduino Micros. This works great until we hit around ~80% usage of the data storage on the arduino (which happens with very little code on our side). After that point we are running out of memory during runtime and weird stuff starts happening. To fix this we are currently patching the ros.h file for our chip with an additional defined(__AVR_ATmega32U4__)
in line 48 of the ros.h (link to line).
With this patch our code seems to run without problems but we are not sure if this is the right approach. Could this break something inside of rosserial?
If this is the right way maybe it would make sense to also change it in the ros.h of the library.
The atmega32u4 is using the default buffer size of 512 bytes which is ridiculously big since atmega32u4 only have 2.5KB of SRAM in total.
It should not break anything if you spin your node handle faster than messages come in and out.
A PR would be good, but I think it would be better to add the additional define to line 52, as mega32u4 and mega328p are pretty similar in term of specs.
We define the NodeHandle size in our own sketch. Maybe that saves you having your own copy of rosserial.
E.g.
// Save Arduino memory.
#define MAX_SUBSCRIBERS 1
#define MAX_PUBLISHERS 1
#define INPUT_SIZE 256
#define OUTPUT_SIZE 256
ros::NodeHandle_<ArduinoHardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE,
OUTPUT_SIZE>
nh;