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

Revision history [back]

So, it would appear that we're just using too much RAM for the 168:

$ avr-size HelloWorld.cpp.elf
text       data     bss     dec     hex filename
5132        144    1345    6621    19dd HelloWorld.cpp.elf

The ATMEGA168 has only 1K of SRAM, but our bss and data is about 1.5k.

You could do the following:

  • checkout from hg, build and copy to your libraries directory as usual.
  • edit line 48 of your <sketchbook>/libraries/ros_lib/ros.h to read:

    typedef NodeHandle_<ArduinoHardware, 5, 5, 100, 100> NodeHandle;

When I did this, I had the following for size:

avr-size HelloWorld.cpp.elf
text       data     bss     dec     hex filename
5120        144     441    5705    1649 HelloWorld.cpp.elf

So, it would appear that we're just using too much RAM for the 168:

$ avr-size HelloWorld.cpp.elf
text       data     bss     dec     hex filename
5132        144    1345    6621    19dd HelloWorld.cpp.elf

The ATMEGA168 has only 1K of SRAM, but our bss and data is about 1.5k.

You could do the following:

  • checkout from hg, build and copy to your libraries directory as usual.
  • edit line 48 of your <sketchbook>/libraries/ros_lib/ros.h to read:

    typedef NodeHandle_<ArduinoHardware, 5, 5, 100, 100> NodeHandle;

When I did this, I had the following for size:

avr-size HelloWorld.cpp.elf
text       data     bss     dec     hex filename
5120        144     441    5705    1649 HelloWorld.cpp.elf

This will limit you to only 5 publishers, 5 subscribers, and messages must be <100 bytes long. The buffers we maintain use a lot of memory since many messages can get quite large.

Please let me know if this does solve your problem, if it does, I'll get a tutorial up on ros.org so that others can tune the performance of rosserial to their hardware.