ROS实操入门系列(三)1、Topic通讯小结 2、编写ros驱动实现电机控制和编码器读取
Topic通讯小结
控制板驱动
代码实现及工具调试
完整代码
https://www.lanqiao.cn/courses/2947,提供准备好的云主机ros环境,进行实操,课程包括了 Topic 通讯, Service 通讯,ROS 自定义消息,URDF可视化,TF坐标转换等技术要点。每个技术点都会结合例子先把原理讲解清楚,为了达到学以致用的目的,我们会再进行知识拓展,针对每个技术点实现对应的生动有趣的需求,保证学完后会有很大的收获。
Topic通讯小结Topic通讯特点
通讯模型是通过publisher和subscriber来建立的
数据通讯是异步的
没有响应机制,不关心接收方是否接收到
数据收发方式为 多对多
应用场景
Topic通讯的特点,在获取一些传感器数据时我们会用到。
例如,GPS芯片,陀螺仪,摄像头,激光雷达,温度传感器,湿度传感器等传感器。
通常,我们会为这些传感器开发驱动程序。在ROS生态中,我们开发的驱动其实就是去写一个Node节点
工作内容
在节点中,通常要完成两个方面的工作:
1.获取传感器数据
2.将传感器数据发布出去
传感器数据获得是需要根据实际的传感器的接口方式,按照指定的协议去读取。
例如,有的传感器和主机连接方式采用的串口RS232进行连接的,就得按照这种固定的通讯协议来获取传感器的数据。
发布传感器数据,就是将获得的数据按照ROS的规则,采用Publisher的方式发布出去。如果谁关心这个数据,就去订阅就可以了。
控制板驱动
功能回顾
(我之前写的通过python实现CH340串口通信 https://blog.csdn.net/qq_20550447/article/details/108304841)
之前我们的下位机protocol.hex提供了简单的功能,我们上位机通过串口通信也实现这些功能
ros 驱动
驱动的作用就是作为上位机和下位机的统一桥梁。ros中,就是通过一个node来实现驱动的。
电机控制
电机驱动功能我们会集成到ros控制板驱动里,功能需要继续的对外开放,也就是谁想驱动电机都可以,给我的驱动发消息就行。
那么,我的ros驱动中,负责电机驱动的,就必须能够接收到消息,也就是扮演一个订阅者
-
编码器读取
电机驱动功能我们会集成到ros控制板驱动里,功能需要继续的对外开放,也就是谁想知道当前的转速都可以,来订阅我的消息就行。
那么,我的ros驱动中,负责提供编码器数据的,就必须能够往外发送消息,也就是扮演一个发布者。
代码实现及工具调试
下位机烧录protocol.hex文件
-
创建一个电机指令的订阅者
# 创建一个电机指令的订阅者
motor_topic_name = '/motor'
rospy.Subscriber(motor_topic_name, Int32, motor_callback)
实现电机回调
def motor_callback(msg):
if not isinstance(msg, Int32): return
# 接受到其他节点发送的数据
pwm = msg.data
# 给下位机发送指令
# 电机的驱动
pack = struct.pack('h', pwm)
# 自己定制的协议 0x03表示电机
data = bytearray([0x03, pack[0], pack[1]])
ser.write(data)
创建一个编码器发布者
# 创建一个编码器发布者
encoder_topic_name = '/rpm'
rpm_publisher = rospy.Publisher(encoder_topic_name, Float32, queue_size=100)
和下位机进行通讯
while not rospy.is_shutdown():
# 阻塞式的函数
read = ser.read(2)
data = bytearray([])
data.extend(read)
# bytearray 数据 -> 数字类型
data = struct.unpack('h', data)[0]
rpm = data / 100.0
# 将数据发布出去
msg = Float32()
msg.data = rpm
rpm_publisher.publish(msg)
调试
1.查看节点信息
通过 rqt_publisher 调试电机,运行后轮子会转动
rosrun rqt_publisher rqt_publisher
通过rqt_topic调试编码器,运行后value显示转速
rosrun rqt_topic rqt_topic
完整代码
#!/usr/bin/env python
# coding:utf-8
import rospy
import serial
import struct
from std_msgs.msg import Int32
from std_msgs.msg import Float32
def motor_callback(msg):
if not isinstance(msg, Int32): return
# 接受到其他节点发送的数据
pwm = msg.data
# 给下位机发送指令
# 电机的驱动
pack = struct.pack('h', pwm)
data = bytearray([0x03, pack[0], pack[1]])
ser.write(data)
if __name__ == '__main__':
# 创建节点
rospy.init_node('my_driver_node')
# 串口创建
# 重试机制
count = 0
while count < 10:
count += 1
try:
ser = serial.Serial(port='/dev/ttyUSB0', baudrate=115200)
# 如果出错了,后面的代码就不执行了
# 能到达这个位置说明,链接成功
break
except Exception as e:
print(e)
# 创建一个电机指令的订阅者
motor_topic_name = '/motor'
rospy.Subscriber(motor_topic_name, Int32, motor_callback)
# 编码器发布者
encoder_topic_name = '/rpm'
rpm_publisher = rospy.Publisher(encoder_topic_name, Float32, queue_size=100)
# 和下位机进行通讯
while not rospy.is_shutdown():
# 阻塞式的函数
read = ser.read(2)
data = bytearray([])
data.extend(read)
# bytearray 数据 -> 数字类型
data = struct.unpack('h', data)[0]
rpm = data / 100.0
# 将数据发布出去
msg = Float32()
msg.data = rpm
rpm_publisher.publish(msg)
rospy.spin()
https://www.lanqiao.cn/courses/2947,提供准备好的云主机ros环境,进行实操,课程包括了 Topic 通讯, Service 通讯,ROS 自定义消息,URDF可视化,TF坐标转换等技术要点。每个技术点都会结合例子先把原理讲解清楚,为了达到学以致用的目的,我们会再进行知识拓展,针对每个技术点实现对应的生动有趣的需求,保证学完后会有很大的收获。
评论(0)
您还未登录,请登录后发表或查看评论