ROS爲上位機與STM32爲下位機串口通訊(一)

STM32通過串口向ROS上位機發送信息

主要實現了STM32 通過串口向ROS上位機發送數據,發佈者將接收到的數據發佈出去並打印出來,訂閱者訂閱發佈者發佈的消息並打印出來,最後通過roslaunch啓動。

STM32端

u16 times=0;
int arr[10] = {0,1,2,3,4,5,6,7,8,9};
int main(void)
{   
	NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
	delay_init(168);		
	uart_init(115200);	    //波特率115200
	while(1)
	{
			times++;
			printf("%3d\r\n",times);
			if(times>=100) times=0; 
			delay_ms(100);   
	}
}

ROS端

創建工作空間

mkdir -p ~/serial/src
cd ~/serial/src
catkin_init_workspace 

編譯

cd ~/serial/
catkin_make

設置環境變量

echo "source ~/serial/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

創建功能包

catkin_create_pkg serial_communication roscpp std_msgs

在/catkin_ws/src/serial_communication/src/下新建serial_communication_pub.cpp和serial_communication_sub.cpp
serial_communication_pub.cpp內容如下

#include <string>
#include <ros/ros.h>// 包含ROS的頭文件
#include <boost/asio.hpp>//包含boost庫函數
#include <boost/bind.hpp>
#include <std_msgs/String.h>//ros定義的String數據類型

using namespace std;
using namespace boost::asio;//定義一個命名空間,用於後面的讀寫操作

unsigned char times_buf[5];//接收區

int main(int argc,char** argv)
{
    ros::init(argc,argv,"serial_communication_pub");//初始化節點
    ros::NodeHandle n;//創建節點句柄
    /*創建一個Publisher,發佈名爲chatter的topic,消息類型爲std_msgs::String*/
    ros::Publisher chatter_pub = n.advertise<std_msgs::String>("chatter",1000);
    ros::Rate loop_rate(10);//設置循環頻率10Hz

    io_service iosev;
    serial_port sp(iosev, "/dev/ttyUSB0");//定義傳輸的串口
    sp.set_option(serial_port::baud_rate(115200));//波特率115200
    sp.set_option(serial_port::flow_control());//串口選項允許更改流量控制,默認值0
    sp.set_option(serial_port::parity());//奇偶性,默認值爲none
    sp.set_option(serial_port::stop_bits()); //停止位,默認值爲1
    sp.set_option(serial_port::character_size(8));  //數據位,默認值爲8

    while(ros::ok())
    {
        read(sp,buffer(times_buf));
        string str(&times_buf[0],&times_buf[4]);//將數組轉化爲字符串

        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;
}


serial_communication_sub.cpp內容如下

#include <ros/ros.h>
#include <std_msgs/String.h>

//接收到訂閱消息後,進入消息回調函數執行任務
void chatterCallback(const std_msgs::String::ConstPtr& msg)
{
  ROS_INFO("I hear:%s",msg->data.c_str());
}

int main(int argc, char **argv)
{
    /* code for main function */
    ros::init(argc, argv, "serial_communication_sub");//初始化ROS節點
    
    ros::NodeHandle n;//創建節點句柄

    /*創建一個Subscriber,訂閱名爲chatter的話題,註冊回調函數chatterCallback*/
    ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
    
    ros::spin();//循環等待回調函數
    return 0;
}

打開 ~/serial/src/serial_communication/CMakeLists.txt, 最後面加上:

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

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

保存
在/catkin_ws/src/serial_communication/下新建文件夾launch
並在launch文件夾下新建一個serial_communication_pub.launch文件
未見內容如下

<launch>
	<node pkg="serial_communication" type="serial_communication_pub" name="serial_communication_pub" output="screen" />
	<node pkg="serial_communication" type="serial_communication_sub" name="serial_communication_sub" output="screen" />
</launch>

寫好後記得再次編譯

cd ~/serial/
catkin_make

最後運行

autolabor@autolabor-host:~$ roslaunch serial_communication serial_communication_pub.launch 
... logging to /home/autolabor/.ros/log/b1175c24-a2e2-11e9-8d53-000c299981e9/roslaunch-autolabor-host-11059.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://autolabor-host:40439/

SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.13

NODES
  /
    serial_communication_pub (serial_communication/serial_communication_pub)
    serial_communication_sub (serial_communication/serial_communication_sub)

auto-starting new master
process[master]: started with pid [11069]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to b1175c24-a2e2-11e9-8d53-000c299981e9
process[rosout-1]: started with pid [11082]
started core service [/rosout]
process[serial_communication_pub-2]: started with pid [11099]
process[serial_communication_sub-3]: started with pid [11100]
[ INFO] [1562743016.360922738]:  51
[ INFO] [1562743016.365478840]: I hear: 51
[ INFO] [1562743016.460078115]:  52
[ INFO] [1562743016.460510462]: I hear: 52
[ INFO] [1562743016.560876337]:  53
[ INFO] [1562743016.561298464]: I hear: 53
[ INFO] [1562743016.664422539]:  54
[ INFO] [1562743016.664840175]: I hear: 54
[ INFO] [1562743016.761167086]:  55
[ INFO] [1562743016.761580444]: I hear: 55
[ INFO] [1562743016.860703796]:  56
[ INFO] [1562743016.861023292]: I hear: 56
[ INFO] [1562743016.973725366]:  57
[ INFO] [1562743016.974084649]: I hear: 57
[ INFO] [1562743017.060380804]:  58
[ INFO] [1562743017.060940934]: I hear: 58
[ INFO] [1562743017.160667823]:  59
[ INFO] [1562743017.161122159]: I hear: 59
[ INFO] [1562743017.260142425]:  60
[ INFO] [1562743017.260559162]: I hear: 60
[ INFO] [1562743017.360150478]:  61
[ INFO] [1562743017.362249269]: I hear: 61
[ INFO] [1562743017.460271112]:  62
[ INFO] [1562743017.460853910]: I hear: 62

運行之前要先

sudo minicom

否則打印出的數據有問題

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章