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

rosserial_arduino: trouble with too much messaging?

asked 2011-08-25 16:00:49 -0600

brice rebsamen gravatar image

Hi

I started playing around with an Arduino Uno and rosserial. I am trying to control 2 stepper motors (really a motor controller via pulse/dir signal, using the AccelStepper library), a PWM signal, and few infrequent IOs. The pulse generation is a bit intensive because I need to generate a fairly large number of steps per seconds (about 1000 steps per seconds per motor).

I tested it, motor by motor and it seems to be alright. However, when I connect the arduino to the joystick (via ROS / rosserial python_node), it sends quite a large number of messages (I counted up to 160 messages per seconds). The motor start spinning when I touch the joystick, but after a while the arduino seems to hang.

My guess is that I am sending to many messages, thus stalling the communication channel and overloading the arduino with message decoding. Could this be?

Based on this assumption, I started to write a filter: on the PC side, a node receives the messages destined to the Arduino (i.e. set the position of motor 1 to x), and only send the latest commands, aggregated in one message, every xx ms (currently 25 ms). This will definitely reduce the amount of communication on the serial line and the amount of decoding on the arduino's side, but as a drawback, it will reduce the responsiveness of my hardware: motors will be updated less frequently (I think it should be OK for my application though).

I will try to report whether this is a successful strategy. Right now I am having a problem with rosserial and custom messages...

edit retag flag offensive close merge delete

Comments

So it turned out that limiting the amount of messages transferred solved the problem. First of all, too many messages don't add anything, as my hardware cannot respond that fast anyway. I decided to write a filter node that only transmits the latest commands in an aggregated msg at a fixed rate.
brice rebsamen gravatar image brice rebsamen  ( 2011-08-31 17:31:21 -0600 )edit

2 Answers

Sort by ยป oldest newest most voted
9

answered 2011-08-25 17:09:54 -0600

adasta gravatar image

updated 2011-08-25 17:10:42 -0600

You could be saturating the serial communication.

rosserial runs at 57600 baud. If it is a larger message, like geometry_msg/Twist for example, you would need a minimum of 67840 baud to send messages that fast. ( (8 x 3 x 2 bytes per message + 5 bytes message overhead ) x 160 x 8 bits per byte)

You have two options if this is the case. Limit the messages like you are doing. The only reason the joy stick is sending that many messages is because it sends a message everytime the joystick angle changes. It is very sensitive.

The other option is to increase the Arduino's baud rate.To modify what baud rate your rosserial uses, you need to update both the Arduino and the python serial_node. In the Arduino program, this means that you must set rate before you initialize the node. You set the baud rate by accessing the hardware object and setting its internal baud rate.

nh.getHardware()->setBaud(115200); //or what ever baud you want

Next, when you launch the serial node, you must set a private baud param to the specified baud rate.

<node name="rosserial_node" type="serial_node.py" pkg="rosserial_python">
    <param name="baud" value="115200"/>
</node>

Another possible problem could be that you are not calling nh.spin() enough. The Arduino's Serial circular buffer is only 80 bytes. If you happen to be sending data very fast and calling nh.spin() very slowly, then it will cause these kinds of problems.

edit flag offensive delete link more

Comments

Do you call setBaud before or after nh.initNode()?

Cerin gravatar image Cerin  ( 2017-02-05 23:39:31 -0600 )edit
1

answered 2011-08-25 16:50:45 -0600

tfoote gravatar image

It certainly seems possible to overload an arduino with messages. For the downsampling I suggest that you look at the throttle node

edit flag offensive delete link more

Comments

It would also be important to understand what the bandwidth of the mechanical system is. It may be that the motors can only respond on the order of 10 Hz (fairly common), so sending messages at 160 Hz doesn't really "add" anything to the control system.
mjcarroll gravatar image mjcarroll  ( 2011-08-26 02:49:11 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-08-25 16:00:49 -0600

Seen: 4,751 times

Last updated: Aug 25 '11