rosserial_python fails but rosserial_server doesn't
Hi guys,
I have a sketch in an Arduino that is publishing into ROS (with a custom message) some data that he gets form a bluetooth connection (HC-05) from another arduino.
Here is the code:
#include <SoftwareSerial.h>
#include <ros.h>
#include <ros/time.h>
//#include <sensor_msgs/Range.h>
#include <pkg_2/msg_2.h>
//variables globales
char Buffer[11];
int SoF=0x01;
int Eof=0x04;
int i=0;
int trama_ok=0;
//declaracion objetos
SoftwareSerial BT(10,11); //Rx,Tx: pins 7,8 de la placa OBJETO BLUETOOTH
ros::NodeHandle nh;
pkg_2::msg_2 range_msg;
ros::Publisher pub_range( "/ultrasound", &range_msg);
void setup()
{
nh.initNode();
nh.advertise(pub_range);
delay(1);
//Serial.begin(9600);
BT.begin(9600);
delay(1);
}
void loop()
{
if (BT.available())
{
int a=BT.read();
Buffer[i]=a;
i++;
if (i==11){
range_msg.obstacle = Buffer[1];
range_msg.state_m1 = 9;
range_msg.state_m2 = Buffer[3];
range_msg.state_m3 = Buffer[4];
range_msg.state_m4 = Buffer[5];
range_msg.d_left = Buffer[6];
range_msg.d_right = Buffer[7];
range_msg.d_center = Buffer[8];
pub_range.publish(&range_msg);
nh.spinOnce();
i=0;
delay(1000);
}
}
}
Pay no attention to the names of the topics and stuff, it's just a recycled code from an Ultrasound sketch.
The thing is, when I try to connect to the arduino with rosserial_python:
$ rosrun rosserial_python serial_node.py /dev/ttyACM0
It gives me the next error:
dani@ROS:~/catkin_ws$ rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0
[INFO] [WallTime: 1462188244.111483] ROS Serial Python Node
[INFO] [WallTime: 1462188244.122188] Connecting to /dev/ttyACM0 at 57600 baud
[ERROR] [WallTime: 1462188261.230066] Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino
Fortunately, when I use rosserial_server:
$ roslaunch rosserial_server serial.launch
Everything is published efficiently and smoothly.
The question: Why is this happening? How is that rosserial_server can handle the connection and rosserial_python can't? I must say that the previous ROS sketches that i worked with (which didn't involve any SoftwareSerial external connection) worked perfectly with rosserial_python
.