Ros Arduino link problem
Hello,
I am using this basic script on Arduino Uno to subscribe to "cmd_vel" topic and publish "cell_voltage" topic.
include 'ros.h'
include 'std_msgs/Float32.h'
include 'geometry_msgs/Twist.h'
float x;
int sensorPin = A1;
int sensorValue = 0;
float voltageValue = 0;
ros::NodeHandle nh;
void messageCb( const geometry_msgs::Twist& vel)
{
x = vel.linear.x - 1.0;
}
std_msgs::Float32 float_msg;
ros::Publisher pu("cell_voltage", &float_msg);
ros::Subscriber<geometry_msgs::twist> su("cmd_vel" , messageCb);
void setup() {
nh.getHardware()->setBaud(115200);
nh.initNode();
nh.subscribe(su);
Serial.begin(115200);
}
void loop() {
nh.spinOnce();
delay(10);
sensorValue = analogRead(sensorPin);
voltageValue = sensorValue * 5.0 /1023.0;
float_msg.data = voltageValue;
pu.publish( &float_msg ); // THIS LINE
}
When the line pu.publish( &float_msg );
is commented, everything works fine :
pi@raspberrypi:~ $ rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0 _baud:=115200
[INFO] [WallTime: 1491989648.891986] ROS Serial Python Node
[INFO] [WallTime: 1491989648.915430] Connecting to /dev/ttyACM0 at 115200 baud
[INFO] [WallTime: 1491989652.493960] Note: subscribe buffer size is 280 bytes
[INFO] [WallTime: 1491989652.516291] Setup subscriber on cmd_vel [geometry_msgs/Twist]
But if I uncommented that line, I get this error message :
pi@raspberrypi:~ $ rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0 _baud:=115200
[INFO] [WallTime: 1491989671.577193] ROS Serial Python Node
[INFO] [WallTime: 1491989671.604281] Connecting to /dev/ttyACM0 at 115200 baud
[ERROR] [WallTime: 1491989688.725894] Unable to sync with device; possible link problem or link software version mismatch such as hydro rosserial_python with groovy Arduino
However I am using the correct version. So I don't know why I have this message.
Any ideas ?
PS : What are the HTML tags for inserting cpp code ?
Regards
Matthieu
The
preformatted text
button in the question editor will do block formatting for code, or you can indent each line by four spaces. ROS Answers uses a variant of markdown for post formatting, and while it also allows inline HTML, sometimes it's a bit too aggressive at trying to auto-close tags.