使用ROS通过串口获取遥控器信号(二)

2023-11-17

使用ROS通过串口获取遥控器信号(二)

十:编写串口通信节点

sudo gedit ~/catkin_ws/src/uart_communication/src/commu.cpp

加入以下代码,根据实际情况修改自己的代码,注意serial的API函数可以从ROS -wiki中搜索得到,根据自己需求调用相应的函数

#include <ros/ros.h>
#include <std_msgs/String.h>
#include<uart_communication/remoter_Raw.h>
#include <serial/serial.h>

serial::Serial ser; //声明串口对象 


int main (int argc, char **argv)
{
  ros::init(argc, argv, "commun");//创建名为commun的ROS节点
  ros::NodeHandle n;//创建节点句柄
  ros::Publisher pub=n.advertise<uart_communication::remoter_Raw>("remoter_message",1000); //向remoter_message话题发布uart_communication::remoter_Raw消息
  ros::Rate loop_rate(10);//循环频率10ms

   try 
    { 
   		 //设置串口属性,并打开串口 
        ser.setPort("/dev/ttyTHS2"); //根据自己的设备进行修改
        ser.setBaudrate(115200); //设置波特率
        serial::Timeout to = serial::Timeout::simpleTimeout(1000); 
        ser.setTimeout(to); 
        ser.open(); 
    } 
    catch (serial::IOException& e) 
    { 
        ROS_ERROR("Unable to open the port "); 
        return -1; 
    } 

    //检测串口是否已经打开,并给出提示信息 
    if(ser.isOpen()) 
    { 
        ROS_INFO("chassis serial port initialized"); 
    } 
    else 
    { 
        return -1; 
    }

  uart_communication::remoter_Raw wh; //定义消息变量
  uint8_t c[8]={0}; //存储消息的数组
  int size=0;
  while(ros::ok())
  {
    size=ser.read(c,1); //读取帧头,1个字节,存储到c[0]
    if(size==1)
    {    
        ROS_INFO("%x\r\n",c[0]); 
    }
    if(c[0]==0xFF) //判断
    {
        size=ser.read(c+1,6); //连续读取6个字节,存储到c[1]-c[6]
        if(size==6)
        {   
            size=ser.read(c+7,1); //读取帧尾,存储到c[7]
            if(size==1)
            {
                ROS_INFO("%x\r\n",c[7]);
                if(c[7]==0xEE)//判断
                {
                    ROS_INFO("%x,%x,%x,%x,%x,%x,%x,%x\r\n",c[0],c[1],c[2],c[3],c[4],c[5],c[6],c[7]); //打印出来
                }
            }
        }        
    }
    //修改消息
    wh.header.frame_id="/remoter";
    wh.header.stamp=ros::Time::now();
    wh.ch1=c[1];
    wh.ch2=c[2];
    wh.ch3=c[3];
    wh.ch4=c[4];
    wh.ch5=c[5];
    wh.ch6=c[6];   
    //发布
    pub.publish(wh);

    ros::spinOnce();//循环等待回调函数
    loop_rate.sleep();//按照循环频率延时
	
  }
  return 0;
}

在CMakeList.txt中加入:

add_executable(uart_communication src/commu.cpp)
target_link_libraries(uart_communication ${catkin_LIBRARIES})
add_dependencies(uart_communication ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
cd ~/catkin_ws
catkin_make 

十一:实现效果在这里插入图片描述

本人通过USB-TTL连接电脑和开发板进行的测试,在电脑端通过串口十六进制发送:
ff aa bb cc dd 33 44 ee

ROS端:

roscore
rosrun uart_communication uart_communication/commu.cpp //另一个终端//另一个终端

rostopic echo /remoter_message  //另一个终端

在这里插入图片描述

在这里插入图片描述

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

使用ROS通过串口获取遥控器信号(二) 的相关文章

随机推荐