Arduino与ROS通信报错 “ Unable to sync with device; possible link problem or link software version mismatch”
1、问题描述:
使用设备Arduino UNO,IMU。使用JY901.cpp和JY901.h。模拟ros_lib中的Hello Word程序发布topic。Arduino编译通过。ros端输入命令rosrun rosserial_python serial_node.py /dev/ttyACM0 如下错误。
2、解决方案
先讲一讲我试过的几种方法:
2.1 在.ino文件上方加入#define USE_USBCON;
这个解决方案只适用于部分Arduino型号,可以在ros_lib 下的ArduinoHardware.h中有提到原因,如下图
2.2 端口波特率设置的问题
Arduino上的波特率设置要和ros中的一致,可以在ros命令行中添加 _baud:=57600(这个要和你设置的一样)
rosrun rosserial_python serial_node.py /dev/ttyACM0 _baud:=57600
2.3 软硬串口问题
试过这些方法都不行,最后在这里发现有位老哥说Arduino软硬串口的问题,链接在这里,我的理解是这样的,Arduino 与pc机串口通信是通过硬串口传输,而我imu引脚也是插在了rx上,代码中出现了读取信息。会不会是冲突了。然后我查到可以用软串口来读,具体做法是,在.ino文件中用软串口来读取IMU信息,试了一下,问题解决。下图加高亮的是我添加的代码。
#include <Wire.h>
#include <JY901.h>
#include <ros.h>
#include <std_msgs/Float32MultiArray.h>
#include <SoftwareSerial.h> //加入软串口头文件
ros::NodeHandle nh;
SoftwareSerial Serial1(2,3); //定义软串口
std_msgs::Float32MultiArray acc_msg;
ros::Publisher acc_pub("jy901_acc", &acc_msg);
std_msgs::Float32MultiArray gyro_msg;
ros::Publisher gyro_pub("jy901_gyro", &gyro_msg);
std_msgs::Float32MultiArray ang_msg;
ros::Publisher ang_pub("jy901_angle", &ang_msg);
void setup()
{
Serial.begin(57600);
Serial1.begin(9600); //软串口开启
nh.initNode();
nh.advertise(acc_pub);
nh.advertise(gyro_pub);
nh.advertise(ang_pub);
}
void loop()
{
nh.spinOnce();
acc_msg.data_length = 3;
acc_msg.data[0] = (float)JY901.stcAcc.a[0] / 32768 * 16;
acc_msg.data[1] = (float)JY901.stcAcc.a[1] / 32768 * 16;
acc_msg.data[2] = (float)JY901.stcAcc.a[2] / 32768 * 16;
acc_pub.publish( &acc_msg );
delay(100);
gyro_msg.data_length = 3;
gyro_msg.data[0] = (float)JY901.stcGyro.w[0] / 32768 * 2000;
gyro_msg.data[1] = (float)JY901.stcGyro.w[1] / 32768 * 2000;
gyro_msg.data[2] = (float)JY901.stcGyro.w[2] / 32768 * 2000;
gyro_pub.publish( &gyro_msg );
delay(100);
ang_msg.data_length = 3;
ang_msg.data[0] = (float)JY901.stcAngle.Angle[0] / 32768 * 180;
ang_msg.data[1] = (float)JY901.stcAngle.Angle[1] / 32768 * 180;
ang_msg.data[2] = (float)JY901.stcAngle.Angle[2] / 32768 * 180;
ang_pub.publish( &ang_msg );
delay(100);
while (Serial1.available()) //用软串口
{
JY901.CopeSerialData(Serial1.read()); //这边也改成用软串口读取
}
}
以上代码是根据这位老哥改编的,链接在这里。