function getTransformStamped(objHandle, name, relTo, relToName) -- This function retrieves the stamped transform for a specific object t = simExtRosInterface_getTime() p = simGetObjectPosition(objHandle, relTo) o = simGetObjectQuaternion(objHandle, relTo) return { header = {stamp=t, frame_id=relToName}, child_frame_id = name, transform = { translation={x=p[1],y=p[2],z=p[3]}, rotation={x=o[1],y=o[2],z=o[3],w=o[4]} } } end ---------------------------------------------------------------------------------------------------------------------- simExtRosInterface_sendTransforms({getTransformStamped(sensorRefHandle,'SICK_TiM310_ref',baseLinkHandle,'base_link'), getTransformStamped(baseLinkHandle,'base_link',odomHandle,'odom')}) --simExtRosInterface_sendTransform(getTransformStamped(sensorRefHandle,'SICK_TiM310_ref',baseLinkHandle,'base_link') --simExtRosInterface_sendTransform(getTransformStamped(baseLinkHandle,'base_link',odomHandle,'odom'))
我们在V-rep的脚本程序中向ros系统发布了坐标系之间的变换,有时可能会出现许多错误。为了方便排查错误,ros提供了一系列tf调试工具。下面两种命令都可以以图形化的方式查看坐标系之间的tf关系:
$ rosrun tf view_frames
$ rosrun rqt_tf_tree rqt_tf_tree
打开生成的pdf文件或在弹出的rqt窗口中,可以很清楚的看出里程计坐标系odom,机器人坐标系base_link,以及激光雷达坐标系SICK_TiM310_ref之间的关系:
tf_echo命令可以用于查看两个坐标系之间具体的变换关系(注意输出的是target_frame相对于reference_frame的关系):
$ rosrun tf tf_echo reference_frame target_frame
如下图所示,会输出激光传感器坐标系SICK_TiM310_ref相对于机器人坐标系base_link的变换(V-rep模型中这两个坐标系是重合的):
在/odom话题上发布nav_msgs/Odometry消息的代码如下(注意这里直接调用函数获取到相对于odom的位置和姿态,省去了航迹推算的过程。如果在真实的小车上进行测试,就需要根据里程计数据来推算小车的位置和姿态等信息,然后再发送出去):
odomPub = simExtRosInterface_advertise('/odom', 'nav_msgs/Odometry') local pos = simGetObjectPosition(baseLinkHandle, odomHandle) local ori = simGetObjectQuaternion(baseLinkHandle, odomHandle) odom = {} odom.header = {seq=0,stamp=simExtRosInterface_getTime(), frame_id="odom"} odom.child_frame_id = 'base_link' odom.pose = { pose={position={x=pos[1],y=pos[2],z=pos[3]}, orientation={x=ori[1],y=ori[2],z=ori[3],w=ori[4]} } } simExtRosInterface_publish(odomPub, odom)
使用gmapping构建地图gmaping包是用来生成地图的,它需要从ROS系统监听多个Topic,并输出map。The slam_gmapping node takes in sensor_msgs/LaserScan messages and builds a map (nav_msgs/OccupancyGrid)
Subscribed Topics:
tf (tf/tfMessage):Transforms necessary to relate frames for laser, base, and odometry