上一篇 (139条消息) ROS2将键盘方向键控制指令通过串口发送_识龟成鳖的博客-CSDN博客,实现了电脑键盘4个方向键读取,并通过话题发送出来,另一个节点接收话题并通过串口发送。当时用虚拟串口工具socat测试都没问题,但接到usb串口实物后发现发送出来的数据有问题,安装cutecom测试硬件驱动都没有问题,定位问题在发送程序,但很久都没解决。限于目前的能力,只能另外再找库。初步想法:电脑读取4个方向键节点不变,另建一个python功能包,接收方向键话题,再用python3-serial库将控制数据发送到串口。
参考博客:
(139条消息) ROS2实现虚拟串口通信_ros与主机通过虚拟串口通信_ff925的博客-CSDN博客
(139条消息) 使用python serial 库发送16进制数据_python serial以16进制发送_New农民工的博客-CSDN博客
以及古月居的python话题例程
《ROS2入门21讲图文教程 | 10、话题》 - 古月居 (guyuehome.com)
一、安装python3-serial库
sudo apt-get install python3-serial
二、新建python功能包
~/dev_A1/src$ ros2 pkg create --build-type ament_python header_python
进入~/dev_A1/src/header_python/header_python$文件夹
gedit header_python_subscriber.py
将以下代码复制到新建文件
#!/usr/bin/env python3
# -*- coding: utf-8 -*-
import time
import serial
import rclpy # ROS2 Python接口库
from rclpy.node import Node # ROS2 节点类
from std_msgs.msg import String # ROS2标准定义的String消息
serial_port = serial.Serial(
port="/dev/ttyUSB0",
baudrate=115200,
bytesize=serial.EIGHTBITS,
parity=serial.PARITY_NONE,
stopbits=serial.STOPBITS_ONE,
)
"""
创建一个订阅者节点
"""
class SubscriberNode(Node):
def __init__(self, name):
super().__init__(name) # ROS2节点父类初始化
self.sub = self.create_subscription(\
String, "subscribe_and_publish", self.listener_callback, 10) # 创建订阅者对象(消息类型、话题名、订阅者回调函数、队列长度)
self.get_logger().info('I am subscriber')
def listener_callback(self, msg): # 创建回调函数,执行收到话题消息后对数据的处理
self.get_logger().info('I heard: "%s"' % msg.data) # 输出日志信息,提示订阅收到的话题消息
if msg.data=="1000":
myinput=[0xff, 0x31, 0x01, 0x00, 0x00, 0x31, 0x00, 0x00, 0x00, 0xFC]
elif msg.data=="0100":
myinput=[0xff, 0x31, 0x00, 0x00, 0x00, 0x31, 0x01, 0x00, 0x00, 0xFC]
elif msg.data=="0010":
myinput=[0xff, 0x32, 0x01, 0x00, 0x00, 0x31, 0x00, 0x00, 0x00, 0xFC]
elif msg.data=="0001":
myinput=[0xff, 0x31, 0x01, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0xFC]
else:
myinput=[0xff, 0x32, 0x01, 0x01, 0x00, 0x32, 0x00, 0x01, 0x00, 0xFC]
serial_port.write(myinput)
serial_port.write('\r\n'.encode())
def main(args=None): # ROS2节点主入口main函数
rclpy.init(args=args) # ROS2 Python接口初始化
node = SubscriberNode("header_python_subscriber_node") # 创建ROS2节点对象并进行初始化
rclpy.spin(node) # 循环等待ROS2退出
node.destroy_node() # 销毁节点对象
rclpy.shutdown() # 关闭ROS2 Python接口
serial_port.close()
三、修改setup.py文件如下:
from setuptools import setup
package_name = 'header_python'
setup(
name=package_name,
version='0.0.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='sean',
maintainer_email='@todo.todo',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'header_python_subscriber_node = header_python.header_python_subscriber:main',
],
},
)
四、编译
cd ~/dev_A1/
colcon build
五、测试
5.1先进入上篇的发布节点功能包,打开发布节点
source install/setup.bash
ros2 run cpp_header serial_publisher1_node
5.2插好串口线,一个接虚拟机,一个接windows
打开一个终端,修改ttyusb0权限
sudo chmod 666 ttyUSB0
5.3进入接收节点功能包,启动接收节点
source install/setup.bash
ros2 run header_python header_python_subscriber_node
5.4在windows 打开串口助手软件,接收串口数据,选择16进制方式接收