这篇持续跟新,总结源码原理以供后期调取使用
根据roalaunch文件出发分析:
roslaunch odroid_machine remote_odroid.launch mname:=odroid
remote_odroid.launch:
<launch>
<arg name="mname" default="odroid0" />
#设置arg参数名称为mname,参数默认值为odroid0(可覆盖)
<include file="$(find odroid_machine)/launch/odroid_machine.launch">
#包含odroid_machin.launch文件的节点参数
<arg name="mname" value="$(arg mname)" />
</include>
<node machine="$(arg mname)" ns="$(arg mname)" name="zumy_ros_bridge" pkg="ros_zumy" type="zumy_ros_bridge.py" output="screen" >
#设置节点zumy_ros_bridge,可执行文件为包ros_zumy下的zumy_ros_bridge.py
</node>
</launch>
#到此,这个launch文件作用,定义参数名称name,包含odroid_machin.launch文件的节点参数,启动zumy_ros_bridge.py
odroid_machin.launch:
<launch>
<arg name="mname" default="odroid0" />
<arg name="odroid_machine_path" default="/home/odroid/coop_slam_workspace/src/odroid_machine" />
#定义路径
<machine name="$(arg mname)" address="$(arg mname).local" user="odroid" timeout="5.0" env-loader="$(arg odroid_machine_path)/launch/ros_env_loader.bash" />
#启动机器ros_env_loader.bash,根据上面定义路径找到文件
</launch>
zumy_ros_bridge.py:
#!/usr/bin/python
import rospy
from geometry_msgs.msg import Twist
from threading import Condition
from zumy import Zumy
from std_msgs.msg import String,Header,Int16
from sensor_msgs.msg import Imu
import socket,time
#获取不同的子文件,from 母文件 import 子文件
class ZumyROS:
def __init__(self):
self.zumy = Zumy()#zumy为Zumy()值,Zumy()在zumy.py文件中定义,from zumy import Zumy 引用
rospy.init_node('zumy_ros')#初始化节点,叫zumy_ros
#self.cmd = (0,0)
rospy.Subscriber('cmd_vel', Twist, self.cmd_callback,queue_size=1)
self.lock = Condition()#条件方式锁定对象
self.rate = rospy.Rate(70.0)# 70HZ 频率
self.name = socket.gethostname()#name=主机IP
self.heartBeat = rospy.Publisher('heartBeat', String, queue_size=5)#通过String类型发布节点到heartBeat,限制队列数为5
self.imu_pub = rospy.Publisher('imu', Imu, queue_size = 1)
self.r_enc_pub = rospy.Publisher('r_enc', Int16, queue_size = 5)
self.l_enc_pub = rospy.Publisher('l_enc', Int16, queue_size = 5)
self.imu_count = 0
def cmd_callback(self, msg):
lv = 0.6
la = 0.4
v = msg.linear.x#线速度
a = msg.angular.z#角速度
r = lv*v + la*a
l = lv*v - la*a
self.lock.acquire()#锁定对象
# self.cmd = (l,r)
self.zumy.cmd(l,r)
self.lock.release()#释放对象
def run(self):
while not rospy.is_shutdown():#检查标志,开始RUN
self.lock.acquire()
# self.zumy.cmd(*self.cmd)
# print imu and enc data
self.zumy.read_data() #运行zumy.py的read_data()
imu_data = self.zumy.read_imu()#同上,在zumy.py注释
enc_data = self.zumy.read_enc()
self.lock.release()
if len(imu_data) == 6:#获取下层数据后的算法,实现数据转化为可读数据
imu_msg = Imu()
imu_msg.header = Header(self.imu_count,rospy.Time.now(),self.name)
imu_msg.linear_acceleration.x = 9.81 * imu_data[0]
imu_msg.linear_acceleration.y = 9.81 * imu_data[1]
imu_msg.linear_acceleration.z = 9.81 * imu_data[2]
imu_msg.angular_velocity.x = 3.14 / 180.0 * imu_data[3]
imu_msg.angular_velocity.y = 3.14 / 180.0 * imu_data[4]
imu_msg.angular_velocity.z = 3.14 / 180.0 * imu_data[5]
self.imu_pub.publish(imu_msg)
if len(enc_data) == 2:
enc_msg = Int16()
enc_msg.data = enc_data[0]
self.r_enc_pub.publish(enc_msg)
enc_msg.data = enc_data[1]
self.l_enc_pub.publish(enc_msg)
self.heartBeat.publish("I am alive")
self.rate.sleep()
# if shutdown, turn off motors
self.zumy.cmd(0,0)
if __name__ == '__main__':
zr = ZumyROS()
zr.run()#定义ZumyROS()函数类,运行类中的run()函数
源码注释之后想到再补充,先到这,其他都没有什么误解了
.