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 incoming byte:
char inByte = Serial.read();
Serial.println(inByte);
Serial.println("bla");
}
}
If I send "12345" via the Arduino Serial Monitor to my Arduino UNO, I get back:
1
bla
2
bla
3
bla
4
bla
5
bla
Doing the same with the ATmega168 based motorcontroller I get:
1
bla
2
bl
3
bl
4
bl
5
bl
It thus appears that serial communication is garbled for some reason. I'll try a lower baud rate and update this post afterwards. Does anyone have tips as to what else could be done about this problem? /edit: Interestingly enough, using 9600 baud, the serial monitor seems to hang after the first output and looks like this:
1
la
After closing and opening the serial monitor again, I can again send a string and it hangs again after the first output.
/Update: I found out that this garbled communication problem only appears if the global ros::node_handle nh" is commented in. Using plain Arduino, serial communication works.
...And this also makes sense, seeing how the baud rate is set when using the node_handle instance. So I dropped that to 9600 inside the ArduinoHardware class and I'm now looking what happens.
/Update: It appears that the problem is related to memory running out. If I use the following in ros.h:
typedef NodeHandle_<ArduinoHardware, 0, 0, 0, 0> NodeHandle;
I get non-garbled serial communication. Any increase of buffer size appears to break serial communication again. When trying to connect using the rosserial python client, at least get some error messages when using very low publisher/subscriber and buffer length numbers:
stefan@SKdell:~$ rosrun rosserial_python serial_node.py /dev/ttyUSB0 _baud:=9600[INFO] [WallTime: 1330978100.090943] ROS Serial Python Node
[INFO] [WallTime: 1330978100.093375] Connected on /dev/ttyUSB0 at 9600 baud
[INFO] [WallTime: 1330978102.214480] Failed Packet Flags
[INFO] [WallTime: 1330978102.224796] Failed Packet Flags
[INFO] [WallTime: 1330978102.264249] Failed Packet Flags
Any ideas on how to scale down rosserial (or a better explanation of what's happening) are appreciated.
Originally posted by Stefan Kohlbrecher on ROS Answers with karma: 24361 on 2012-03-01
Post score: 0