建造属于你的无人驾驶车!
本专栏持续更新中…
程序源码:https://github.com/kkmd66/ZZX_RUN
Solidworks模型文件:https://github.com/kkmd66/ZZX_RUN/releases
为XACRO模型添加GAZEBO属性与运动控制插件
第一步,在《建造属于你的无人驾驶车——(三)Solidworks模型导出为URDF模型》中的XACRO模型中添加XACRO描述
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
第二步,继续添加激光雷达插件
<!--lidar_link-->
<gazebo reference="lidar_link">
<sensor type="ray" name="rplidar">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3</min_angle>
<max_angle>3</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>6.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>lidar_link</frameName>
</plugin>
</sensor>
</gazebo>
第三步,继续添加运动模型插件
这里四轮差速,选择滑动控制
<!-- Drive controller -->
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>100.0</updateRate>
<robotNamespace></robotNamespace>
<leftFrontJoint>left_front_wheel_link_joint</leftFrontJoint>
<rightFrontJoint>right_front_wheel_link_joint</rightFrontJoint>
<leftRearJoint>left_behind_wheel_link_joint</leftRearJoint>
<rightRearJoint>right_behind_wheel_link_joint</rightRearJoint>
<wheelSeparation>0.64</wheelSeparation>
<wheelDiameter>0.33</wheelDiameter>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
<odometryFrame>odom</odometryFrame>
<torque>1000</torque>
<topicName>cmd_vel</topicName>
<broadcastTF>1</broadcastTF>
</plugin>
</gazebo>
第四步,继续添加控制插件
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/zzx_run_robot</robotNamespace>
<legacyModeNS>true</legacyModeNS>
</plugin>
</gazebo>
第五步,添加GAZEBO属性,增大轮子摩擦属性
<!--friction-->
<gazebo reference="left_front_wheel_link">
<mu1>10000</mu1>
<mu2>10000</mu2>
<kp>10000000</kp>
<kd>1</kd>
</gazebo>
<gazebo reference="left_behind_wheel_link">
<mu1>10000</mu1>
<mu2>10000</mu2>
<kp>10000000</kp>
<kd>1</kd>
</gazebo>
<gazebo reference="right_front_wheel_link">
<mu1>10000</mu1>
<mu2>10000</mu2>
<kp>10000000</kp>
<kd>1</kd>
</gazebo>
<gazebo reference="right_behind_wheel_link">
<mu1>10000</mu1>
<mu2>10000</mu2>
<kp>10000000</kp>
<kd>1</kd>
</gazebo>
</robot>
最后
有问题可以和我交流哦~
WeChat ID:kkmd66-2