ROS环境下的串口通讯
目錄
1、前言
2、內(nèi)容
2.1 準(zhǔn)備工作
2.1.1 連接外部USB設(shè)備
2.1.2 串口調(diào)試工具的下載
2.1.3 serial庫的安裝
2.2 代碼部分
2.2.1 編寫發(fā)布節(jié)點(diǎn)
2.2.2 編寫發(fā)布節(jié)點(diǎn)
2.2.3 編輯checklists文件
2.2.4 編輯package.xml文件
2.2.5 編寫launch文件
2.2.6 運(yùn)行節(jié)點(diǎn)
3 可能的問題
引用
1、前言
最近項(xiàng)目中有一個(gè)需求,在ROS2的環(huán)境下,需要接受到兩個(gè)topic,作出邏輯判斷,通過串口發(fā)送特定報(bào)文到外接USB設(shè)備上。之前在論壇中找了好久沒有類似的文章,因此在這里記錄一下,同學(xué)們可以參考,其中如果有問題或者可以優(yōu)化的地方,歡迎大家指正。
2、內(nèi)容
2.1 準(zhǔn)備工作
由于我使用的是ros2的humble版本,因此一下工作環(huán)境皆為ubuntu22.04版本以及ROS2的humble版本。該部分工作在代碼編寫之前就需要準(zhǔn)備好。
2.1.1 連接外部USB設(shè)備
在調(diào)試之前建議鏈接USB設(shè)備,一并查看系統(tǒng)上是否有串口驅(qū)動,通常ubuntu系統(tǒng)已經(jīng)集成了串口驅(qū)動:s541,可以通過以下命令行來查看:
lsmod | grep usbserial出現(xiàn)一下類似情況說明驅(qū)動已經(jīng)存在
此刻通過頻繁插拔外界設(shè)備,之后通過下述命令進(jìn)行判斷該設(shè)備串口名稱
dmesg| grep ttyU*對話框中會彈出很多內(nèi)容,找到頻繁出現(xiàn)“conect”和“disconect”的便是我們想要的串口。
2.1.2 串口調(diào)試工具的下載
在此我們安裝使用的是cutecom工具,安裝命令見下:
sudo apt-get install cutecom在使用時(shí)可以通過以下命令打開:
sudo cutecom打開界面見下:
可以在setting部分進(jìn)行串口參數(shù)的配置,這里的將要采用的配置為:9600 8 n 1。
2.1.3 serial庫的安裝
為了完成ros和外界設(shè)備的通訊,還需要安裝serial庫文件,由于ros2中沒有集成serial庫,因此需要自己下載源碼進(jìn)行編譯安裝。btw,ros中可以直接通過apt-get進(jìn)行安裝的,這個(gè)我會再寫一份文章。
該庫雖然是針對foxy的,但是在humble中也可以使用,通過一下進(jìn)行clone和編譯
mkdir serial git clone https://github.com/ZhaoXiangBox/serial cd serial mkdir build cmake .. make此刻基本上已經(jīng)安裝編譯好了。
截至目前位置,我們已經(jīng)完成了一切準(zhǔn)備工作,下面開始進(jìn)行代碼部分。
2.2 代碼部分
我們首先整理一下需求:
1、接收兩個(gè)topic;
2、根據(jù)topic內(nèi)容進(jìn)行邏輯判斷;
3、根據(jù)判斷結(jié)果,發(fā)送16進(jìn)制的8個(gè)byte的報(bào)文到設(shè)備;
在正式編寫代碼之前,首先先建立一下ros2的工作空間和工作包
mkdir -p ~/ros2/src cd ~/ros2/src ros2 pkg create --build-type ament_cmake demo以上代碼意為,建立一個(gè)名字叫做demo的功能包使用c++進(jìn)行編寫。
2.2.1 編寫發(fā)布節(jié)點(diǎn)
首先編寫一個(gè)節(jié)點(diǎn)
cd ~/ros2/src/demo/src touch talker.cpp之后編寫代碼,talker節(jié)點(diǎn)會根據(jù)鍵盤的指令輸入0或者1。
#include <chrono> #include <functional> #include <memory> #include <string> #include "sensor_msgs/msg/image.hpp" #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp"using namespace std::chrono_literals;class MinimalPublisher : public rclcpp::Node { public:MinimalPublisher(): Node("minimal_publisher"), count_(0){publisher_ = this->create_publisher<sensor_msgs::msg::Image>("topic", 10);timer_ = this->create_wall_timer(500ms, std::bind(&MinimalPublisher::timer_callback, this));}private:void timer_callback(){int a = 0;auto message = sensor_msgs::msg::Image();int func(0);std::cout << "請輸入數(shù)字";std::cin >> func;switch (func){case 0:a = 0;break;case 1:a = 4;break;}message.height = a;publisher_->publish(message);// std::cout << message.height << std::endl;RCLCPP_INFO(get_logger(), "參數(shù)1:%d", message.height);}rclcpp::TimerBase::SharedPtr timer_;rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;size_t count_; };int main(int argc, char *argv[]) {rclcpp::init(argc, argv);rclcpp::spin(std::make_shared<MinimalPublisher>());rclcpp::shutdown();return 0; }?通過以上方式在建立一個(gè)talker1,talker1會持續(xù)發(fā)送數(shù)字4.
#include <chrono> #include <functional> #include <memory> #include <string> #include "sensor_msgs/msg/image.hpp" #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp"using namespace std::chrono_literals;class MinimalPublisher : public rclcpp::Node { public:MinimalPublisher(): Node("minimal_publisher1"), count_(0){publisher_ = this->create_publisher<sensor_msgs::msg::Image>("topic1", 10);timer_ = this->create_wall_timer(500ms, std::bind(&MinimalPublisher::timer_callback, this));}private:void timer_callback(){// int a = 0;auto message = sensor_msgs::msg::Image();message.height = 4;publisher_->publish(message);std::cout << message.height << std::endl;RCLCPP_INFO(get_logger(),"參數(shù)2:%d",message.height);}rclcpp::TimerBase::SharedPtr timer_;rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr publisher_;size_t count_; };int main(int argc, char *argv[]) {rclcpp::init(argc, argv);rclcpp::spin(std::make_shared<MinimalPublisher>());rclcpp::shutdown();return 0; }這樣,兩個(gè)發(fā)布節(jié)點(diǎn)編寫完畢。
2.2.2 編寫接收節(jié)點(diǎn)
首先需要接受兩個(gè)節(jié)點(diǎn)的話題,并作邏輯處理,之后使用serial庫文件的函數(shù)進(jìn)行數(shù)據(jù)的發(fā)送,目前我們的設(shè)備可以通過不同的報(bào)文開燈和關(guān)燈,發(fā)送報(bào)文:????? 0x01,0x05,0x0,0x02,0x00,0x00,0x6C,0x0A;為開燈。0x01,0x05,0x0,0x02,0xff,0x00,0x2D,0xFA;為關(guān)燈。
建立可執(zhí)行文件
cd ~/ros2/src/demo/src touch lis.cpp以下是具體代碼。
#include <functional> #include <memory> #include <string> #include "serial/serial.h" #include "rclcpp/rclcpp.hpp" #include "message_filters/subscriber.h" #include "message_filters/time_synchronizer.h" #include "sensor_msgs/msg/image.hpp" using std::placeholders::_1; using std::placeholders::_2;serial::Serial ros_ser; class MinimalSubscriber : public rclcpp::Node { public:MinimalSubscriber(): Node("minimal_sync_subscriber"){sub1_.subscribe(this, "topic");sub2_.subscribe(this, "topic1");sync_ = std::make_shared<message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image>>(sub1_, sub2_, 10);sync_->registerCallback(std::bind(&MinimalSubscriber::topic_callback, this, _1, _2));}private:void topic_callback(const sensor_msgs::msg::Image::ConstSharedPtr msg1,const sensor_msgs::msg::Image::ConstSharedPtr msg2) const{int c = 0;unsigned char buffer[8] = {0};c = (msg1->height) * (msg2->height);// std::cout << c << ","// << msg1->height << ","// << msg2->height << std::endl;if (c != 0){buffer[0] = 0x01;buffer[1] = 0x05;buffer[2] = 0x00;buffer[3] = 0x02;buffer[4] = 0x00;buffer[5] = 0x00;buffer[6] = 0x6C;buffer[7] = 0x0A;}else{buffer[0] = 0x01;buffer[1] = 0x05;buffer[2] = 0x00;buffer[3] = 0x02;buffer[4] = 0xff;buffer[5] = 0x00;buffer[6] = 0x2D;buffer[7] = 0xFA;}// RCLCPP_INFO(get_logger(), "結(jié)果:%d", c);for (int i = 0; i < 8; i++){std::cout << std::hex << (buffer[i] &0xff)<< " ";}std::cout<<std::endl;ros_ser.write(buffer,8);}message_filters::Subscriber<sensor_msgs::msg::Image> sub1_;message_filters::Subscriber<sensor_msgs::msg::Image> sub2_;std::shared_ptr<message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image>> sync_; };int main(int argc, char *argv[]) {rclcpp::init(argc, argv);ros_ser.setPort("/dev/ttyUSB0");ros_ser.setBaudrate(9600);serial::Timeout to =serial::Timeout::simpleTimeout(1000);ros_ser.setTimeout(to);try{ros_ser.open();}catch(serial::IOException &e){std::cout<<"unable to open"<<std::endl;return -1;}if(ros_ser.isOpen()){std::cout<<"open"<<std::endl;}else{return -1;}rclcpp::spin(std::make_shared<MinimalSubscriber>());rclcpp::shutdown();ros_ser.close();return 0; }2.2.3 編輯cmakelists文件
在cmakelist中添加代碼中的依賴,同時(shí)給三個(gè)節(jié)點(diǎn)定義可執(zhí)行文件。
添加依賴庫
find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(message_filters REQUIRED) find_package(serial REQUIRED)添加節(jié)點(diǎn)說明
add_executable(talker src/talker.cpp) ament_target_dependencies(talker rclcpp sensor_msgs) add_executable(talker1 src/talker1.cpp) ament_target_dependencies(talker1 rclcpp sensor_msgs) add_executable(lis src/lis.cpp) ament_target_dependencies(lis rclcpp message_filters serial sensor_msgs)2.2.4 編輯package.xml文件
同樣,在package文件中添加依賴說明
<buildtool_depend>ament_cmake</buildtool_depend><buildtool_depend>rclcpp</buildtool_depend><buildtool_depend>sensor_msgs</buildtool_depend><buildtool_depend>message_filters</buildtool_depend><buildtool_depend>serial</buildtool_depend>2.2.5 編寫launch文件
(未完待續(xù))
2.2.6 運(yùn)行節(jié)點(diǎn)
完成以上內(nèi)容后編譯一下功能包
cd ~/ros2 colcon build --packages-select demo(未完待續(xù))
3 可能的問題
(未完待續(xù))
引用
1、ROS2 Humble如何使用串口驅(qū)動?(Serial)_騰騰任天真的博客-CSDN博客
(未完待續(xù))
總結(jié)
以上是生活随笔為你收集整理的ROS环境下的串口通讯的全部內(nèi)容,希望文章能夠幫你解決所遇到的問題。
- 上一篇: 网站客服(qq网站客服的实现)
- 下一篇: MAMP Pro 5.3 Shark 鲨