一 .在Gazebo中仿真差速輪式機器人
在本節,我們會對前面設計的差速輪式機器人進行仿真。
你可以在mastering_ros_robot_description_pkg/urdf文件中獲取diff_wheeled_robot.xacro移動機器人的描述文件。
我們創建一個啟動文件,在Gazebo中生成仿真模型。就像我們對機械臂所做的那樣,我們可以創建一個ROS軟件包,用
seven_dof_arm_gazebo軟件包的相同依賴項啟動Gazebo仿真,我是從對應的git庫中下載的完整軟件包。
$ git clone https://github.com/jocacace/diff_wheeled_robot_gazebo.git
進入diff_wheeled_robot_gazebo/launch文件夾,並提取diff_wheeled_gazebo.launch文件。
啟動文件代碼如下:
1 <?xml version="1.0" ?> 2 <launch> 3 4 <!-- these are the arguments you can pass this launch file, for example paused:=t rue --> 5 <arg name="paused" default="false"/> 6 <arg name="use_sim_time" default="true"/> 7 <arg name="gui" default="true"/> 8 <arg name="headless" default="false"/> 9 <arg name="debug" default="false"/> 10 11 <!-- We resume the logic in empty_world.launch --> 12 <include file="$(find gazebo_ros)/launch/empty_world.launch"> 13 <arg name="debug" value="$(arg debug)" /> 14 <arg name="gui" value="$(arg gui)" /> 15 <arg name="paused" value="$(arg paused)"/> 16 <arg name="use_sim_time" value="$(arg use_sim_time)"/> 17 <arg name="headless" value="$(arg headless)"/> 18 </include> 19 20 21 <!-- urdf xml robot description loaded on the Parameter Server--> 22 23 <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find ma stering_ros_robot_description_pkg)/urdf/diff_wheeled_robot.xacro'" /> 24 25 <!-- Run a python script to the send a service call to gazebo_ros to spawn a U RDF robot --> 26 <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 27 args="-urdf -model diff_wheeled_robot -param robot_description"/> 28 29 </launch>
使用以下命令來啟動此文件:
$ roslaunch diff_wheeled_robot_gazebo diff_wheeled_gazebo.launch
仿真模型如下:
仿真成功后,接下來我們將激光雷達添加到機器人中。
1.將激光雷達添加到機器人中
我們在機器人頂部添加了激光雷達來執行高級操作,比如用該機器人進行自主導航或地圖構建。
為了將激光雷達添加到機器人中,我們應該將以下代碼添加到diff_wheeled_robot.xacro文件中:
248 <link name="hokuyo_link"> 249 <visual> 250 <origin xyz="0 0 0" rpy="0 0 0" /> 251 <geometry> 252 <box size="${hokuyo_size} ${hokuyo_size} ${hokuyo_size}"/> 253 </geometry> 254 <material name="Blue" /> 255 </visual> 256 </link> 257 <joint name="hokuyo_joint" type="fixed"> 258 <origin xyz="${base_radius - hokuyo_size/2} 0 ${base_height+hokuyo_size/4}" rp y="0 0 0" /> 259 <parent link="base_link"/> 260 <child link="hokuyo_link" /> 261 </joint> 262 <gazebo reference="hokuyo_link"> 263 <material>Gazebo/Blue</material> 264 <turnGravityOff>false</turnGravityOff> 265 <sensor type="ray" name="head_hokuyo_sensor"> 266 <pose>${hokuyo_size/2} 0 0 0 0 0</pose> 267 <visualize>false</visualize> 268 <update_rate>40</update_rate> 269 <ray> 270 <scan> 271 <horizontal> 272 <samples>720</samples> 273 <resolution>1</resolution> 274 <min_angle>-1.570796</min_angle> 275 <max_angle>1.570796</max_angle> 276 </horizontal> 277 </scan> 278 <range> 279 <min>0.10</min> 280 <max>10.0</max> 281 <resolution>0.001</resolution> 282 </range> 283 </ray> 284 <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_las er.so"> 285 <topicName>/scan</topicName> 286 <frameName>hokuyo_link</frameName> 287 </plugin> 288 </sensor> 289 </gazebo>
本節中,我們使用名稱為libgazebo_ros_laser.so的GazeboROS插件來仿真激光雷達。
完整的代碼可以在diff_wheeled_robot_with_laser.xacro描述文件中找到,該文件位於
mastering_ros_robot_description_pkg/urdf/文件夾中。
在仿真環境中添加一些物體,這樣我們就可以查看激光雷達,在這里,我們在機器人周圍添加
一些圓柱體,可以看到相應的激光視圖。
2.在Gazebo中控制機器人的移動
我們正在使用的是一個差速機器人,配有2個輪子和2個腳輪。該機器人的完整特性應該作為Gazebo-ROS插件來仿真。
基本的差速驅動插件已經實現。
要在Gazebo中控制機器人移動,我們需要添加一個名為libgazebo_ros_diff_drive.so的Gazebo-ROS插件,從而可以生成該機器人的差速驅動動作。
以下是該插件的定義及其參數的完整代碼片段:
292 <!-- Differential drive controller --> 293 <gazebo> 294 <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_driv e.so"> 295 <legacyMode>true</legacyMode> 296 <rosDebugLevel>Debug</rosDebugLevel> 297 <publishWheelTF>false</publishWheelTF> 298 <robotNamespace>/</robotNamespace> 299 <publishTf>1</publishTf> 300 <publishWheelJointState>false</publishWheelJointState> 301 <alwaysOn>true</alwaysOn> 302 <updateRate>100.0</updateRate> 303 <leftJoint>front_left_wheel_joint</leftJoint> 304 <rightJoint>front_right_wheel_joint</rightJoint> 305 <wheelSeparation>${2*base_radius}</wheelSeparation> 306 <wheelDiameter>${2*wheel_radius}</wheelDiameter> 307 <broadcastTF>1</broadcastTF> 308 <wheelTorque>30</wheelTorque> 309 <wheelAcceleration>1.8</wheelAcceleration> 310 <commandTopic>cmd_vel</commandTopic> 311 <odometryFrame>odom</odometryFrame> 312 <odometryTopic>odom</odometryTopic> 313 <robotBaseFrame>base_footprint</robotBaseFrame> 314 315 316 </plugin> 317 </gazebo>
在該插件中,我們可以提供一些參數,如機器人的車輪關節(關節應該是連續轉動型的)、車輪間距、車輪直徑、里程計話題等。
控制機器人移動的一個重要參數是:
<commandTopic>cmd_vel</commandTopic>
該參數是插件的速度指令話題,是ROS中一個Twist類型的消息(sensor_msgs/Twist)。我們可以將Twist消息發布到/cmd_vel話題中,我們就可以看到機器人開始從它的位置移動。
3.在啟動文件中添加關節狀態發布者
添加差速驅動插件之后,我們需要將關節狀態發布者加入到現有的啟動文件中,或者我們也可以創建一個新的啟動文件。
你可以在diff_wheeled_robot_gazebo/launch下看到更新后的最終啟動文件diff_wheeled_gazebo_full.launch。
啟動文件包含關節狀態發布者,這有助於在RViz中可視化顯示。以下是在此啟動文件中為關節狀態發布者添加的額外代碼:
24 <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_ publisher" ></node> 25 <!-- start robot state publisher --> 26 <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_ publisher" output="screen" > 27 <param name="publish_frequency" type="double" value="50.0" /> 28 </node>
4.添加ROS遙控節點
ROS遙控(teleop)節點通過接收鍵盤的輸入來發布ROSTwist命令。在該節點中,我們可以生成線速度和角速度,而且已經有了一個標准的遙控節點實現,我們可以重用該節點。
遙控節點是在diff_wheeled_robot_control軟件包中實現的,腳本文件夾包含diff_wheeled_robot_key節點,它就是遙控節點。
我在相應的git庫中下載了該軟件包:
$git clone https://github.com/jocacace/diff_wheeled_robot_control.git
要想成功編譯和使用該軟件包,你需要安裝joy_node軟件包:
$sudo apt install ros-melodic-joy
下面是名為keyboard_teleop的啟動文件,用來啟動遙控節點:
1 <launch> 2 <!-- differential_teleop_key already has its own built in velocity smoother --> 3 <node pkg="diff_wheeled_robot_control" type="diff_wheeled_robot_key" name="diff_w heeled_robot_key" output="screen"> 4 5 <param name="scale_linear" value="0.5" type="double"/> 6 <param name="scale_angular" value="1.5" type="double"/> 7 <remap from="turtlebot_teleop_keyboard/cmd_vel" to="/cmd_vel"/> 8 9 </node> 10 </launch>
讓我們開始控制機器人運動。
使用以下命令啟動具有完整仿真設置的Gazebo:
$ roslaunch diff_wheeled_robot_gazebo diff_wheeled_gazebo_full.launch
啟動遙控節點
$ roslaunch diff_wheeled_robot_control keyboard_teleop.launch
啟動RViz可視化機器人狀態和激光數據:
$ rosrun rviz rviz
在RViz中添加Fixed Frame:/odom,添加Laser Scan,話題設置為/scan以查看激光掃描數據,添加Robot model來查看機器人模型。
在遙控終端中,我們可以使用一些按鍵(U、I、O、J、K、L、M、“,”、“.”)進行方向調整,其他鍵(q、z、w、x、e、c、K、空格鍵)進行速度調整。
如圖顯示機器人使用機器人使用遙控在Gazebo中移動及其在RViz中的可視化。
我們可以從Gazebo工具欄上選擇基本物體,並添加到機器人環境中,也可以在左邊的面板上添加在線庫的物體:
只有當我們按下遙控節點終端內相應的按鍵時,機器人才會移動,如果該終端處於不活動狀態,按下按鍵機器人不會移動。
如果一切正常,我們可以使用機器人來探索該區域並在RViz中可視化激光數據。