STM32
直播中

李红

8年用户 1341经验值
私信 关注
[问答]

求大佬分享ROS与STM32的串口通信的程序

求大佬分享ROS与STM32的串口通信的程序

回帖(1)

高志新

2021-12-6 14:07:56

STM32程序
参考上一篇 Ubuntu16之STM32开发–点灯和串口通信, 主要代码节选如下:


uint8_t count = 0;




  while (1)
  {
                ++count;
                HAL_GPIO_TogglePin(LD2_GPIO_Port, LD2_Pin);
                printf("Hello, %3drn", count);
                HAL_Delay(100);
  }


每100ms串口发送给上位机 “Hello, %3drn” 的字符, 串口识别为 /dev/ttyACM0.


ROS程序
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
catkin_create_pkg serial_communication roscpp std_msgs
cd serial_communication/src       
touch serial_communication.cpp
gedit serial_communication.cpp  # code serial_communication.cpp


~/catkin_ws/src/serial_communication/src/serial_communication.cpp 内容:


//reference: https://www.cnblogs.com/li-yao7758258/p/5794005.html


#include
#include // 包含ROS的头文件
#include //包含boost库函数
#include
#include "std_msgs/String.h" //ros定义的String数据类型


using namespace std;
using namespace boost::asio; //定义一个命名空间,用于后面的读写操作


unsigned char buf[12]; //定义字符串长度


int main(int argc, char **argv)
{


  ros::init(argc, argv, "serial_communication"); //初始化节点
  ros::NodeHandle n;


  ros::Publisher chatter_pub = n.advertise("chatter", 1000); //定义发布消息的名称及sulv


  ros::Rate loop_rate(10);


  io_service iosev;
  serial_port sp(iosev, "/dev/ttyACM0"); //定义传输的串口
  sp.set_option(serial_port::baud_rate(115200));
  sp.set_option(serial_port::flow_control());
  sp.set_option(serial_port::parity());
  sp.set_option(serial_port::stop_bits());
  sp.set_option(serial_port::character_size(8));


  while (ros::ok())
  {
    //write(sp, buffer(buf1, 6));  //write the speed for cmd_val
    //write(sp, buffer("Hellq world", 12));
    read(sp, buffer(buf));
    string str(&buf[0], &buf[11]); //将数组转化为字符串
    //if (buf[10] == 'n')
    {
      std_msgs::String msg;
      std::stringstream ss;
      ss << str;


      msg.data = ss.str();


      ROS_INFO("%s", msg.data.c_str()); //打印接受到的字符串
      chatter_pub.publish(msg);         //发布消息


      ros::spinOnce();


      loop_rate.sleep();
    }
  }


  iosev.run();
  return 0;
}


保存后, 打开 ~/catkin_ws/src/serial_communication/CMakeLists.txt, 最后面加上:


add_executable(serial_communication src/serial_communication.cpp)
target_link_libraries(serial_communication ${catkin_LIBRARIES})


保存.


# 第一个终端
roscore


# 第二个终端
cd ~/catkin_ws
catkin_make
source devel/setup.bash
chmod 777 /dev/ttyACM0
# 如果之前 CuteCom 已经打开, 记得关了, 免得USB虚拟串口占用.  
rosrun serial_communication serial_communication


然后就会看到ROS中打印出如下信息:


lz@lz-pc:~/catkin_ws$ rosrun serial_communication serial_communication
[ INFO] [1542939474.069999764]: Hello,  74
[ INFO] [1542939474.169567482]: Hello,  75
[ INFO] [1542939474.269443664]: Hello,  76
[ INFO] [1542939474.369511941]: Hello,  77
[ INFO] [1542939474.469562788]: Hello,  78
[ INFO] [1542939474.569548019]: Hello,  79
[ INFO] [1542939474.669471010]: Hello,  80
[ INFO] [1542939474.769552072]: Hello,  81
[ INFO] [1542939474.869545703]: Hello,  82
[ INFO] [1542939474.969443991]: Hello,  83
举报

更多回帖

发帖
×
20
完善资料,
赚取积分