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

Using rosserial for a ATmega168/Arduino based motorcontroller

asked 2012-03-01 08:51:52 -0600

updated 2012-03-05 08:27:14 -0600

I once again tried to use rosserial for a Atmega168 based microcontroller (this one). As described in the manual of the microcontroller, one should set the Arduino IDE to use the "Nano with ATmega168" setting. Flashing for example the Arduino "blink" example works fine, but I can't get the controller to work with rosserial. I installed the current rosserial version as described in the Arduino IDE setup tutorial. I then also confirmed that the rosserial installation works in principle by testing with a Arduino UNO, which works fine.

Flashing rosserial "HelloWorld" example on the ATmega168 based microcontroller with the Arduino IDE, I get the following:

Binary sketch size: 8528 bytes (of a 14336 byte maximum)

Starting the rosserial python node, this is then the output:

stefan@SKdell:~/rosext/rosserial/rosserial_python/nodes$ rosrun rosserial_python serial_node.py /dev/ttyUSB0
[INFO] [WallTime: 1330634524.911609] ROS Serial Python Node
[INFO] [WallTime: 1330634524.913857] Connected on /dev/ttyUSB0 at 57600 baud
[ERROR] [WallTime: 1330634539.916433] Lost sync with device, restarting...
[ERROR] [WallTime: 1330634554.926519] Lost sync with device, restarting...
[ERROR] [WallTime: 1330634569.928740] Lost sync with device, restarting...
[ERROR] [WallTime: 1330634584.938269] Lost sync with device, restarting...
[ERROR] [WallTime: 1330634599.943257] Lost sync with device, restarting...
[ERROR] [WallTime: 1330634614.953234] Lost sync with device, restarting...

The subscriber example shows the same symptoms (flashing looks fine, but rosserial never connects). They look a bit like the sketch uses too much memory, but rosserial now reduces the num of publishers/subscribers for ATmega168 and I confirmed via a #error in ros.h that it indeed uses the nodehandle with the lower subscriber number. Any suggestions are welcome.

/Update: To gain some further insights, I started with the Arduino "Blink" example and added rosserial stuff step by step to see when problems start. This is what I got:

#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle  nh;

void messageCb( const std_msgs::Empty& toggle_msg){
  digitalWrite(13, HIGH-digitalRead(13));   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );

void setup() {                
  // initialize the digital pin as an output.
  // Pin 13 has an LED connected on most Arduino boards:
  pinMode(13, OUTPUT);     
  nh.initNode();
  nh.subscribe(sub);
}

void loop() {
//  nh.spinOnce();  // <-- As soon as this is commented in, blinking stops
  digitalWrite(13, HIGH);   // set the LED on
  delay(1000);              // wait for a second
  digitalWrite(13, LOW);    // set the LED off
  delay(1000);              // wait for a second
}

When I comment in the nh.spinOnce() call, the light stops blinking. My understanding is that normally, this call should not block when there is no rosserial connection, or is this a misconception? A connection using the rosserial_python client does not work, as described further above.

Update 2: For testing serial communication, I use the following code:

#include <ros.h>
#include <std_msgs/Empty.h>

ros::NodeHandle  nh;

void messageCb( const std_msgs::Empty& toggle_msg){
  digitalWrite(13, HIGH-digitalRead(13));   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );

void setup() {                
  pinMode(13, OUTPUT);     
  nh.initNode();
}

void loop() {
  //nh.spinOnce();

  if (Serial.available() > 0) {
      // get ...
(more)
edit retag flag offensive close merge delete

4 Answers

Sort by » oldest newest most voted
3

answered 2012-03-07 23:07:02 -0600

dornhege gravatar image

So, I've also been playing around with similar problems trying to send an Imu message (about 320 bytes) using a 328 (set in rosserial for 280 bytes) and I couldn't get it to work.

This is what I have learning by experimenting with that problem and also by comparing a 328 nano with a 168 nano.

First it is important to note that adjusting memory needs to be done from both sides, i.e. setting the buffers too low will also be a problem because then the initialization messages won't fit. For the HelloWorld example I needed to set a minimum size of 79 (this will increase if the topic name is longer).

I tried to increase the buffer to get to the working area for sending strings in the helloworld example and found out that on the 168 ros::NodeHandle_<ArduinoHardware, 2, 2, 80, 105> nh; is the highest setting that works. So, depending on what you want to send this might be sufficient although the memory limit is quite harsh.

I tried to play around the same way on the 328 Nano for the Imu message, but did not succeed. Interestingly enough it didn't even work on a Mega that is setup to 512 by default. There were no error messages, but also nothing happened.

Digging through the code, these sizes really are just the size of the used buffer. Serial data is sent byte-wise in a for loop. Judging from that, if 280 for in- and output buffer is OK, so should 320 for one and 240 for the other - regarding memory-consumption. This is something that I do not understand, yet. It would be interesting to see if someone knows the reasons for these limits.

edit flag offensive delete link more

Comments

Thanks a lot for your suggestions, I'll try them out later. Regarding your long messages: From looking at the Arduino HardwareSerial.cpp code (which seems to be used also when running rosserial) RX_BUFFER_SIZE is set to 128 by default. Have you tried playing around with that?

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2012-03-08 03:36:39 -0600 )edit

It works with the <ArduinoHardware, 2, 2, 80, 105> setting you proposed. Thanks again!

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2012-03-08 08:31:49 -0600 )edit

Thanks, I didn't look at the arduino libraries yet. I can now report that playing around with the serial buffer size in hardwareserial.cpp also doesn't work.

dornhege gravatar image dornhege  ( 2012-03-09 00:35:27 -0600 )edit
0

answered 2012-03-04 01:34:37 -0600

Procópio gravatar image

Have you tried a smaller baud rate?

edit flag offensive delete link more

Comments

Yes, but to no avail (tried 9600). I'll edit my OP with some new insights.

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2012-03-04 04:45:13 -0600 )edit
0

answered 2012-03-03 05:28:10 -0600

Kevin gravatar image

Yes, rosserial is still very much a work in progress. I have yet to get it working on OSX yet.

edit flag offensive delete link more
0

answered 2012-03-01 08:55:30 -0600

punching gravatar image

I just installed ROS for the first time and connected to an Arduino 2560. The first couple of times I tried it I got the exact same result. I restarted and tried a few more times and with no changes it finally started working. Curious myself.

Once it did work I got a message after the 57600 baud comment that I need to start the publisher.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-03-01 08:51:52 -0600

Seen: 5,480 times

Last updated: Mar 07 '12