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

How to publish a array msgs with large data size in Arduino?

asked 2014-02-02 04:17:04 -0500

bisimai111 gravatar image

updated 2014-04-20 14:16:14 -0500

Evgeny gravatar image

Dear all, I amtrying to publish a msgs with large data size on Arduino. I have tried both Float32MultiArray and Laserscan msgs. However, when i increase the data_length more than 7, it shows an error in the terminal [INFO] [WallTime: 1391356801.758318] Failed Packet Flags after the command "rosrun rosserial_python serial_node.py /dev/ttyACM0" (the code as attached). If I keep the size below 7, the msgs can be published normally.

Could you help me and give me some suggestion, please? thank you!!

#include <ros.h>
#include <ros time.h="">
#include <std_msgs float32multiarray.h="">


ros::NodeHandle  nh;
std_msgs::Float32MultiArray range_msg;
ros::Publisher pub_range("/test", &amp;range_msg);

void setup()
{
  nh.initNode();

  range_msg.data_length=100;

  nh.advertise(pub_range);

}

long range_time;

void loop()
{
  //publish the adc value every 50 milliseconds
  //since it takes that long for the sensor to stabilize

  if ( millis() &gt;= range_time ) {

    for(int i=0;i&lt;100;i++)
    {
      range_msg.data[i]=0.01222331221;
    }

    pub_range.publish(&amp;range_msg);

    range_time =  millis() + 50;
  }

  nh.spinOnce();
}</std_msgs></ros></ros.h>
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2014-02-02 19:10:47 -0500

David Galdeano gravatar image

changing from 6,6,150,150 to 100,100,150,150 will change the number of Publishers/Subscribers from 6 to 100 and do not change the buffer size (150). try to change:

typedef NodeHandle_<arduinohardware, 25,="" 280="" 280,=""> NodeHandle;

to

typedef NodeHandle_<arduinohardware, 25,="" 512="" 512,=""> NodeHandle;

in 'rosserial/rosserial_arduino/src/ros_lib/ros.h' if you use the ATmega328P. Dont forget to run make_libraries.py. If you are using an arduino uno, think of upgrading to a arduino mega.</arduinohardware,&gt;<>

edit flag offensive delete link more

Comments

Thank you, i am using Mega2560 Arduino chip.so I change typedef NodeHandle_<arduinohardware,> 25, 25, 280, 280> to typedef NodeHandle_<arduinohardware,> 25, 25, 512, 512> and how to run "rosrun rosserial_arduino make_libraries.py" under sketchbook. Biz I am using fuerte version so that I cannot

bisimai111 gravatar image bisimai111  ( 2014-02-02 20:28:56 -0500 )edit

if you just make the change on sketchbook/Libraries/ros_lib/ros.h it should be ok! Run rosrun rosserial_arduino make_libraries.py is only for the case of changing the original sources of the rosserial lib.

David Galdeano gravatar image David Galdeano  ( 2014-02-02 20:54:28 -0500 )edit

Dear Galdeano, thanks but i got the same error "Failed Packet Flags" after only changed it. When I reduce the size below 7, it works again. It is so wired.

bisimai111 gravatar image bisimai111  ( 2014-02-02 21:28:55 -0500 )edit

ok, try to upgrade only the 280 (or 150) to 512 part. You can try to lower the use of nh.spinOnce() by using larger delay in your code, to be sure that the spped of usb com is not the bottleneck.

David Galdeano gravatar image David Galdeano  ( 2014-02-02 22:05:14 -0500 )edit

Dear Galdeano, appreciate for your detailed explanation. But i try only the 280 (or 150) to 512 part when i increase the size bigger than 30. It still shows the same error. Actually i want to achieve 240 data_length for msgs and I am using virtual box on mac laptop. Is the virtual box ACM0 port problem? thanks again

bisimai111 gravatar image bisimai111  ( 2014-02-03 02:18:13 -0500 )edit
0

answered 2014-02-02 14:30:33 -0500

fergs gravatar image

The buffer size is limited. See http://wiki.ros.org/rosserial/Overvie... for an overview of the sizes currently used as defaults. Depending on the processor you are using and what other things you are running, you might be OK to increase the buffer sizes. You would do this by adjusting the ros.h file template parameters to a new buffer size.

edit flag offensive delete link more

Comments

Thank you and I try to increase them from 6,6,150,150 to 100,100,150,150 as shown below (ros.h). It still does not work, may i know how to change it or what is its format? thanks > NodeHandle_<arduinohardware, 6,="" 6,=""> 150, 150> NodeHandle; > > #elif defined(__AVR_ATmega328P__) > > typedef NodeHandle_<arduinohardware,> 25, 25, 280, 280> NodeHandle; > > #else

bisimai111 gravatar image bisimai111  ( 2014-02-02 18:38:34 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-02-02 04:17:04 -0500

Seen: 3,226 times

Last updated: Apr 20 '14