自主导航系列11-gazebo的模型建立
昨天在做有关robpt_pose_ekf的时候,发现自己gazebo的知识极度欠缺,反正这段时间比较闲,我可以学一下这些基础的东西
如果不使用这个包可能会出现“卡墙”
之前的节点关系
我试着与move_base结合,这个图使用的是基于turtlebot3融合之后的产物
完成后的/tf长这样
修改的turtlebot3_roboot_pose_ekf如下
<launch> <include file="$(find turtlebot3_gazebo)/launch/turtlebot3_world.launch"/> <include file="$(find turtlebot3_slam)/launch/turtlebot3_slam.launch"/> <node name="base_imu_link" pkg="tf" type="static_transform_publisher" args="-0.032 0 0.068 0 0 0 /base_link /base_imu_link 50"/> <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf"> <param name="output_frame" value="odom"/> <param name="base_footprint_frame" value="base_footprint"/> <param name="freq" value="30.0"/> <param name="sensor_timeout" value="1.0"/> <param name="odom_used" value="true"/> <param name="imu_used" value="true"/> <param name="vo_used" value="false"/> <param name="debug" value="false"/> <param name="self_diagnose" value="false"/> <remap from="imu_data" to="imu" /> </node> </launch>
有趣的知识:当你想自己发布odom话题控制rviz里的机器人运动时,发现gazebo也发布了odom话题,此时的一种方法就是把gazebo中的odom话题改名
找到/home/jianzhuozhu/catkin_ws/src/turtlebot3/turtlebot3/turtlebot3_description/urdf
下的turtlebot3_burger.gazebo.xacro
注意:在同一目录下的turtlebot3_burger.urdf.xacro
中有包含<xacro:include filename="$(find turtlebot3_description)/urdf/turtlebot3_burger.gazebo.xacro"/>
将
<gazebo> <plugin name="turtlebot3_burger_controller" filename="libgazebo_ros_diff_drive.so"> <commandTopic>cmd_vel</commandTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <odometrySource>world</odometrySource> <publishOdomTF>true</publishOdomTF> <robotBaseFrame>base_footprint</robotBaseFrame> <publishWheelTF>false</publishWheelTF> <publishTf>true</publishTf> <publishWheelJointState>true</publishWheelJointState> <legacyMode>false</legacyMode> <updateRate>30</updateRate> <leftJoint>wheel_left_joint</leftJoint> <rightJoint>wheel_right_joint</rightJoint> <wheelSeparation>0.160</wheelSeparation> <wheelDiameter>0.066</wheelDiameter> <wheelAcceleration>1</wheelAcceleration> <wheelTorque>10</wheelTorque> <rosDebugLevel>na</rosDebugLevel> </plugin> </gazebo>
改为
<gazebo> <plugin name="turtlebot3_burger_controller" filename="libgazebo_ros_diff_drive.so"> <commandTopic>cmd_vel</commandTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <odometrySource>world</odometrySource> <publishOdomTF>false</publishOdomTF> <robotBaseFrame>base_footprint</robotBaseFrame> <publishWheelTF>false</publishWheelTF> <publishTf>true</publishTf> <publishWheelJointState>true</publishWheelJointState> <legacyMode>false</legacyMode> <updateRate>30</updateRate> <leftJoint>wheel_left_joint</leftJoint> <rightJoint>wheel_right_joint</rightJoint> <wheelSeparation>0.160</wheelSeparation> <wheelDiameter>0.066</wheelDiameter> <wheelAcceleration>1</wheelAcceleration> <wheelTorque>10</wheelTorque> <rosDebugLevel>na</rosDebugLevel> </plugin> </gazebo>