RoArm-M2-S ROS2 串口通信节点教程
RoArm-M2-S ROS2 串口通信节点教程
本教程用于学习运行 RoArm-M2-S ROS2 串口通信节点来控制机械臂运动。
简介
在 ROS2 中,节点(Node)、话题(Topic)、订阅(Subscription)和发布(Publisher)是核心概念,用于实现分布式系统中的通信。ROS2 中的每个节点负责的是一个单一的、模块化的任务,每个节点都可以通过话题、服务等与其他节点发送和接收数据。
在我们 ROS2 的例程中,提供了两个 ROS2 包(packages),都位于 roarm_ws_em0/src 中,其中 roarm 是 URDF 模型相关的包,serial_ctrl 是串口通信节点相关的包。serial_ctrl 节点用于将 URDF 包发布的姿态信息通过串口发送给机械臂,从而控制机械臂动作,姿态信息指的是机械臂各个舵机的绝对角度度数。在本教程中,我们会介绍这个节点的程序结构,以及这个节点的工作原理。
代码介绍
串口通信节点的主程序位于 serial_ctrl 中,文件名称为 serial_ctrl_py.py,由 python 语言编写,本教程介绍这个文件中的代码。
import rclpy from rclpy.node import Node import array from sensor_msgs.msg import JointState from std_msgs.msg import Float64 import json import serial
前三行为负责 ROS2 的 python 接口和节点类;
中间两行为姿态信息的数据格式;
最后两行为用于串口通信的库和用于编码解码 json 数据的库(串口通信采用 JSON 数据格式通信)。
ser = serial.Serial("/dev/ttyUSB0",115200)
实例化串口通信对象,我们这里使用的串口设备为 USB0(此处是数字0),如果你将此程序移植到了其它设备上,需要更改这里的设备以及波特率。
class MinimalSubscriber(Node): def __init__(self): super().__init__('serial_ctrl') self.position = [] self.subscription = self.create_subscription( JointState, 'joint_states', self.listener_callback, 10) self.subscription # prevent unused variable warning def posGet(self, radInput, direcInput, multiInput): if radInput == 0: return 2047 else: getPos = int(2047 + (direcInput * radInput / 3.1415926 * 2048 * multiInput) + 0.5) return getPos def listener_callback(self, msg): a = msg.position data = json.dumps({'T':102,'base':a[0],'shoulder':a[1],'elbow':a[2],'hand':a[3]+3.1415926,'spd':0,'acc':0}) + "\n" ser.write(data.encode()) print(data)
MinimalSubscriber 继承自 Node,用于定义一个 ROS2 节点;__init__(self) 中定义了节点的名称 serial_ctrl。
create_subscription():表示创建一个订阅器,订阅器名为“joint_states”的 JointState 消息,回调函数为 listener_callback,消息的队列长度为
10;
posGet()函数:用于计算关节位置的函数,输入弧度制的角度、方向,以及减速比的参数后计算关节位置;
listener_callback()函数:订阅器的回调函数,当接收到 JointState 消息时被调用,从消息中获取弧度制的角度信息,并且将弧度制的角度信息转换成舵机的位置数据,将舵机的位置数据封装成JSON格式并通过串口发送给机械臂。
def main(args=None): rclpy.init(args=args) minimal_subscriber = MinimalSubscriber() rclpy.spin(minimal_subscriber) # Destroy the node explicitly # (optional - otherwise it will be done automatically # when the garbage collector destroys the node object) minimal_subscriber.destroy_node() rclpy.shutdown()
main()函数中,首先初始化 rclpy,再创建 MinimalPublisher 对象,rclpy.spin()表示进入循环,minimal_subscriber.destroy_node()表示节点被销毁。
运行串口通信节点
首先将机械臂接通电源,使用 USB 线将机械臂与电脑连接。连接后,回到虚拟机,点击“设备”>“USB”,选择自己电脑对应的接口连接,这样机械臂就会连接到虚拟机上了。
打开一个新的终端。
sudo chmod 777 /dev/ttyUSB0 如果这里报错,很可能就是您的虚拟机没有与机械臂相连接。 cd roarm_ws_em0 配置源文件 source install/setup.bash
启动rviz2,请在终端中输入以下命令:
ros2 launch roarm roarm.launch.py
rviz2窗口会出现,显示出这个机械臂的模型。
上述终端不用关闭,打开一个新的终端,运行以下命令:
cd roarm_ws_em0 source install/setup.bash
使用以下命令来运行串口通信节点,第一个serial_ctrl是roarm/src目录下的包,第二个是serial_ctrl包里面的serial_ctrl节点:
ros2 run serial_ctrl serial_ctrl
此时您应该打开了四个窗口,一个运行roarm.launch.py的终端窗口,一个运行serial_ctrl节点的终端窗口,一个rviz2中的机械臂模型窗口,一个控制面板窗口。调整这些窗口的位置,使您可以看到机械臂模型窗口,并且确保运行serial_ctrl节点的终端处于活动状态,接下来就可以通过拖拽控制面板的滑块来控制rviz2中的机械臂模型运动了,现实中的机械臂产品将跟着一起运动。
再次打开一个新的窗口,运行以下命令来查看所有正在运行的节点列表:
ros2 node list
可以看见系统中正在运行的节点的名称,使用ros2 node info <node_name>命令来获取有关节点的更多信息,它会返回一系列的订阅者、发布者、服务和动作信息。
我们这里查看串口通信节点/serial_ctrl的信息,请运行以下命令:
ros2 node info /serial_ctrl
输出会显示以下内容:
自此,我们可以通过运行串口通信节点来控制机械臂的运动了。
RoArm-M2-S 教程目录
RoArm-M2-S 使用教程
- RoArm-M2-S_Web端使用
- RoArm-M2-S_开发工具使用
- RoArm-M2-S_JSON指令含义
- RoArm-M2-S_WIFI配置
- RoArm-M2-S_机械臂控制
- RoArm-M2-S_末端关节设置
- RoArm-M2-S_FLASH文件系统操作
- RoArm-M2-S_步骤录制和重现
- RoArm-M2-S_ESP-NOW控制
- RoArm-M2-S_Python串口通信控制
- RoArm-M2-S_Python HTTP请求通信