如果完成了前兩步,那么其實我們已經可以去連接我們的現實中的機器人了。
但是,做機器人所需要的材料還沒有到,所以我們這里先在電腦平台上仿真一下。這里我們用到的就算gazebo物理仿真環境,他能很好的和ROS結合來幫助我們學習。
如果您安裝的是ROS完整版並使用的是ubuntu 桌面版的話,gazebo其實已經安裝到電腦中了。
什么是Gazebo?
Gazebo是一款優秀的開源仿真平台,可以實現動力學仿真、傳感器仿真等。它能夠模擬復雜和現實的環境中關節型機器人,能為機器人模型添加現實世界的物理性質。Gazebo里有force,physics的選項,可以為機器人添加例如重力,阻力等,Gazebo有一個很接近真實的物理仿真引擎,要記得一般的地面是沒有阻力的,和現實世界有區別。
具體有關Gazebo的介紹和使用以及如何安裝可以參考博文: 機器人仿真軟件Gazebo介紹
使用Gazebo進行仿真的步驟
配置機器人模型
第一步:為link添加慣性參數和碰撞屬性。因為是物理仿真,所以我要給我們的模型這些物理參數。
<visual>
</visual>
第二步:為link添加愛gazebo標簽
第三步:為joint添加傳動裝置
<!-- Transmission is important to link the joints and the controller -->
<transmission name="${prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_wheel_joint" >
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
第四步:添加gazebo控制器插件
部分參數解釋:
<robotNamespace>: 機器人的命名空間
<leftJoint>和<<rightJoint>>: 左右輪轉動的關節joint
<wheelSeparation> 和 <wheelDiameter>: 機器人模型的相關尺寸,在計算差速參數時需要用到
<commandTopic>: 控制器訂閱的速度控制話題,生成全局命名時要結合<robotNamespace>中設置的命名空間
<odometryFrame>: 里程計數據的參考坐標系,一般命名為odom
下面是我的代碼:
<?xml version="1.0" ?> <robot name="mwRobot" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- No Chinese annotations exist. --> <!-- PROPERTY LIST --> <xacro:property name="M_PI" value="3.1415926"/> <xacro:property name="base_radius" value="0.40"/> <xacro:property name="base_height" value="0.725"/> <xacro:property name="base_mass" value="20.0"/> <xacro:property name="wheel_radius" value="0.095"/> <xacro:property name="wheel_length" value="0.015"/> <xacro:property name="wheel_joint_y" value="0.16305"/> <xacro:property name="wheel_joint_z" value="0.025"/> <xacro:property name="wheel_mass" value="2.0"/> <xacro:property name="caster_radius" value="0.050"/> <!-- wheel_radius - ( base_length/2 - wheel_joint_z) --> <xacro:property name="caster_length" value="0.03"/> <xacro:property name="caster_joint_x" value="0.1305"/> <xacro:property name="caster_joint_z" value="0.0475"/> <xacro:property name="caster_mass" value="0.03"/> <!-- Defining the colors used in this robot --> <material name="yellow"> <color rgba="1 0.4 0 1"/> </material> <material name="black"> <color rgba="0 0 0 0.95"/> </material> <material name="gray"> <color rgba="0.75 0.75 0.75 1"/> </material> <material name="base_color"> <color rgba="0.70 0.70 0.70 1"/> </material> <material name="wheel_color"> <color rgba="0.30 0.30 0.30 1"/> </material> <material name="caster_color"> <color rgba="0.20 0.20 0.20 1"/> </material> <xacro:macro name="wheel" params="prefix reflect angle"> <!-- The connection between the wheel and the main body --> <joint name ="${prefix}_wheel_joint" type="continuous"> <origin xyz="0 ${reflect*wheel_joint_y} ${-wheel_joint_z}" rpy="0 0 0" /> <parent link="base_link"/> <child link="${prefix}_wheel_link"/> <axis xyz="0 1 0"/> </joint> <!-- The definition of the wheel --> <link name="${prefix}_wheel_link"> <visual> <origin xyz="0 0 0" rpy="${M_PI/2} 0 ${angle}" /> <geometry> <mesh filename="package://mwRobot_description/meshes/${prefix}_wheel_link.STL" /> </geometry> <material name="wheel_color"/> </visual> <collision> <origin xyz="0 0 0" rpy="${M_PI/2} 0 ${angle}" /> <geometry> <mesh filename="package://mwRobot_description/meshes/${prefix}_wheel_link.STL" /> </geometry> </collision> <inertial> <origin xyz="0 0 0" /> <mass value="${wheel_mass}" /> <inertia ixx="${wheel_mass*(3*wheel_radius*wheel_radius+wheel_length*wheel_length)/12}" ixy="0.0" ixz="0.0" iyy="${wheel_mass*(3*wheel_radius*wheel_radius+wheel_length*wheel_length)/12}" iyz="0.0" izz="${wheel_mass*(wheel_radius*wheel_radius)/2}" /> </inertial> </link> <gazebo reference="${prefix}_wheel_link"> <material>Gazebo/Black</material> </gazebo> <!-- Transmission is important to link the joints and the controller --> <transmission name="${prefix}_wheel_joint_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}_wheel_joint" > <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${prefix}_wheel_joint_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <xacro:macro name="caster" params="prefix reflect"> <!-- Joint of universal wheel and main body --> <joint name ="${prefix}_caster_joint" type="continuous"> <origin xyz="${reflect*caster_joint_x} 0 ${-caster_joint_z}" rpy="0 0 0" /> <parent link="base_link"/> <child link="${prefix}_caster_link"/> <axis xyz="0 1 1"/> </joint> <!-- Definition of universal wheel --> <link name="${prefix}_caster_link"> <visual> <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" /> <geometry> <mesh filename="package://mwRobot_description/meshes/caster_link.STL" /> </geometry> <material name="caster_color"/> </visual> <collision> <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" /> <geometry> <mesh filename="package://mwRobot_description/meshes/caster_link.STL" /> </geometry> </collision> <inertial> <origin xyz="0 0 0" /> <mass value="${caster_mass}" /> <inertia ixx="${caster_mass*(3*caster_radius*caster_radius+caster_length*caster_length)/12}" ixy="0.0" ixz="0.0" iyy="${caster_mass*(3*caster_radius*caster_radius+caster_length*caster_length)/12}" iyz="0.0" izz="${caster_mass*(caster_radius*caster_radius)/2}" /> </inertial> </link> <gazebo reference="${prefix}_caster_link"> <material>Gazebo/Black</material> </gazebo> </xacro:macro> <!-- Robot main body --> <xacro:macro name="mwRobot_MainPart"> <!-- The joints between robots and his shadow --> <joint name="base_footprint_joint" type="fixed"> <origin xyz="0 0 0.0725" rpy="0 0 0" /> <parent link="base_footprint"/> <child link="base_link" /> </joint> <!-- Projection of robot body on the ground --> <link name="base_footprint"> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <box size="0.001 0.001 0.001" /> </geometry> </visual> </link> <gazebo reference="base_footprint"> <turnGravityOff>false</turnGravityOff> </gazebo> <link name="base_link"> <visual> <origin xyz="0 0 0" rpy="0 0 ${M_PI/2}" /> <geometry> <mesh filename="package://mwRobot_description/meshes/base_link.STL" /> </geometry> <material name="base_color"/> </visual> <collision> <origin xyz="0 0 ${base_height/3}" rpy="0 0 ${M_PI/2}" /> <geometry> <mesh filename="package://mwRobot_description/meshes/base_link.STL" /> </geometry> </collision> <inertial> <origin xyz="0 0 ${base_height/3}" /> <mass value="${base_mass}" /> <inertia ixx="${base_height*base_mass*base_radius/18.0}" ixy="0.0" ixz="0.0" iyy="${base_height*base_mass*base_radius/18.0}" iyz="0.0" izz="${base_height*base_mass*base_radius/18.0}" /> </inertial> </link> <gazebo reference="$base_link"> <material>Gazebo/Gray</material> </gazebo> <wheel prefix="left" reflect="-1" angle="${M_PI}"/> <wheel prefix="right" reflect="1" angle="0"/> <caster prefix="front" reflect="-1"/> <caster prefix="back" reflect="1"/> <!-- controller --> <gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <rosDebugLevel>Debug</rosDebugLevel> <publishWheelTF>true</publishWheelTF> <robotNamespace>/</robotNamespace> <publishTf>1</publishTf> <publishWheelJointState>true</publishWheelJointState> <alwaysOn>true</alwaysOn> <updateRate>100.0</updateRate> <legacyMode>true</legacyMode> <leftJoint>left_wheel_joint</leftJoint> <rightJoint>right_wheel_joint</rightJoint> <wheelSeparation>${wheel_joint_y*2}</wheelSeparation> <wheelDiameter>${2*wheel_radius}</wheelDiameter> <broadcastTF>1</broadcastTF> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> <commandTopic>cmd_vel</commandTopic> <odometryFrame>odom</odometryFrame> <odometryTopic>odom</odometryTopic> <robotBaseFrame>base_footprint</robotBaseFrame> </plugin> </gazebo> </xacro:macro> </robot>
創建仿真環境
首先,我們需要在launch文件中修改配置來啟動gazebo並加載我們的模型。
以下是我launch文件的內容。
<!-- 利用urdf建立模型 --> <launch> <!-- 設置launch文件的參數 --> <arg name="paused" default="false" /> <arg name="use_sim_time" default="true" /> <arg name="gui" default="true" /> <arg name="headless" default="false" /> <arg name="debug" default="false" /> <!-- 運行gazebo仿真環境 --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="debug" value="$(arg debug)" /> <arg name="gui" value="$(arg gui)" /> <arg name="paused" value="$(arg paused)" /> <arg name="use_sim_time" value="$(arg use_sim_time)" /> <arg name="headless" value="$(arg headless)" /> </include> <arg name="model" default="$(find xacro)/xacro --inorder '$(find mwRobot_description)/urdf/gazebo/mwRobot_CompleteModel_gazebo.xacro'"/> <param name="robot_description" command="$(arg model)" /> <!-- 顯示關節控制插件,可以使關節回到中心位置也能設置關節為隨機角度 --> <!-- param name="use_gui" value="true" / --> <!-- 運行joint_state_publisher節點,發布機器人的關節狀態 --> <node name="joint_state_publisher_mwRobot" pkg="joint_state_publisher" type="joint_state_publisher" /> <!-- 運行robot_state_publisher節點,將機器人各個links、joints之間的關系通過tf發布 --> <node name="mwRobot_state_publisher_mwRobot" pkg="robot_state_publisher" type="state_publisher" /> <!-- 運行rviz可視化界面 --> <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model mwRobot -param robot_description"/> </launch>
然后我們運行啟動新的launch文件。
但是會發現啟動失敗,這其實是因為Gazebo啟動的時候嘗試從 http://models.gazebosim.org/ 下載世界模型,但是沒有成功所導致的。。。
解決方法如下:
在終端中運行如下命令:
$ wget -r -R "index\.html*" http://models.gazebosim.org/
該命令會遞歸的下載http://models.gazebosim.org/ 目錄下面的所有文件。
之后你會得到一個文件夾models.gazebosim.org,它幾乎包含了你所需的所有的世界和機器人模型。 然后在終端運行
cd ~
mkdir -p .gazebo/models
最后,將文件夾models/gazebosim.org/下的所有目錄剪切到 ~/.gazebo/models文件夾下面,再重新啟動gazebo,系統就會成功的啟動gazebo。
下載成功后,重新運行launch文件,將會啟動成功。
roslaunch mwRobot_description display_mwRobot_CompleteModel_gazebo.launch
如下圖所示:


如上圖所示,我們可以放置一些模型到仿真空間中。
我們可以安裝一些小工具來測試機器人能否移動。
sudo apt-get install ros-indigo-arbotix-*
sudo apt-get install ros-indigo-joystick-drivers
sudo apt-get install joystick
執行完上面的三句語句后,運行roslaunch運行仿真,然后在另一個終端啟動arbotix_gui,即可打開一個仿真的搖桿界面,此時我們就可以控制機器人移動。

現在我們可以給地圖添加模型了。
