ROS入門(六)——從RRBot到自建小車控制
iwehdio的博客園:https://www.cnblogs.com/iwehdio/
參考教程:https://www.generationrobots.com/blog/en/robotic-simulation-scenarios-with-gazebo-and-ros/
1、RRBot的文件結構
-
RRbot 在工作空間下主要有三個部分:
/rrbot_description /launch rrbot_rviz.launch; rrbot.rviz /meshes hokuyo.dae /urdf rrbot.gazebo; rrbot.xacro; materials.xacro /rrbot_gazebo /worlds rrbot.world /launchr rrbot_world.launch /rrbot_control /config rrbot_conrtol.yaml /launch rrbot.control; rrbot_rqt.launch
-
回顧一下 launch 文件的相關命令:
- 啟動 launch 文件:
roslaunch 功能包名 launch文件名
。 - 節點:
<node>
。pkg:節點所在的功能包名稱。type:節點的可執行文件名稱。name:節點運行時的名稱。output 是否輸出日志、respawn 意外關閉是否重啟、required 是否必須啟動、ns 命名空間、args 輸入的參數。 - 存儲 ROS 全局參數:
<param>
。name:參數名。value:參數值。 - 從文件加載參數:
<rosparam file=filename command="load" ns="param">
。 - 內部參數:
<arg name="arg-name" default="arg-value">
。- 被調用時形式為
"$(arg arg-name)"
。
- 被調用時形式為
- 重映射:
<remap>
。from:原命名。to:映射之后的命名。 - 嵌套:
<include>
。file:包含其他 launch 文件路徑,類似頭文件。
- 啟動 launch 文件:
2、rrbot中各個包的分析
(1)、rrbot_description包
-
rrbot_rviz.launch 文件:
<launch> <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find rrbot_description)/urdf/rrbot.xacro'" /> <!-- send fake joint values --> <node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui"> <param name="use_gui" value="TRUE"/> </node> <!-- Combine joint values --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/> <!-- Show in Rviz --> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find rrbot_description)/launch/rrbot.rviz"/> </launch>
-
第一個節點啟動了關節狀態發布者的GUI界面,也就是啟動 Rviz 時我們能看到的手動調節關節狀態的滑塊。
-
第二個節點啟動了機器人的狀態發布者,發布關節的實時狀態。通過指令
rostopic echo /joint_states
可以看到發布的數據: -
第三個節點啟動 Rviz。
-
-
rrbot.xacro 文件:
<?xml version="1.0"?> <!-- Revolute-Revolute Manipulator --> <robot name="rrbot" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- Constants for robot dimensions --> <xacro:property name="PI" value="3.1415926535897931"/> <xacro:property name="mass" value="1" /> <!-- arbitrary value for mass --> <xacro:property name="width" value="0.1" /> <!-- Square dimensions (widthxwidth) of beams --> <xacro:property name="height1" value="2" /> <!-- Link 1 --> <xacro:property name="height2" value="1" /> <!-- Link 2 --> <xacro:property name="height3" value="1" /> <!-- Link 3 --> <xacro:property name="camera_link" value="0.05" /> <!-- Size of square 'camera' box --> <xacro:property name="axel_offset" value="0.05" /> <!-- Space btw top of beam and the each joint --> <!-- Import all Gazebo-customization elements, including Gazebo colors --> <xacro:include filename="$(find rrbot_description)/urdf/rrbot.gazebo" /> <!-- Import Rviz colors --> <xacro:include filename="$(find rrbot_description)/urdf/materials.xacro" />
- 這一部分引入了文件中的變量(類似於宏定義),並且關聯了rrbot.gazebo 和 materials.xacro。
<!-- Used for fixing robot to Gazebo 'base_link' --> <link name="world"/> <joint name="fixed" type="fixed"> <parent link="world"/> <child link="link1"/> </joint> <!-- Base Link --> <link name="link1"> <collision> <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height1}"/> </geometry> </collision> <visual> <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/> <geometry> <box size="${width} ${width} ${height1}"/> </geometry> <material name="orange"/> </visual> <inertial> <origin xyz="0 0 ${height1/2}" rpy="0 0 0"/> <mass value="${mass}"/> <inertia ixx="${mass / 12.0 * (width*width + height1*height1)}" ixy="0.0" ixz="0.0" iyy="${mass / 12.0 * (height1*height1 + width*width)}" iyz="0.0" izz="${mass / 12.0 * (width*width + width*width)}"/> </inertial> </link> <joint name="joint1" type="continuous"> <parent link="link1"/> <child link="link2"/> <origin xyz="0 ${width} ${height1 - axel_offset}" rpy="0 0 0"/> <axis xyz="0 1 0"/> <dynamics damping="0.7"/> </joint>
- 這一部分先是聲明了世界是一個 link ,而且與 RRBot 最下邊的一個連桿是固連的(與世界固連的 模型需要做如此聲明)。
- 然后聲明了最下方的連桿 link1。
<collision>
標簽是碰撞屬性,<visual>
標簽是視覺屬性,一般而言二者相同。其中的 origin 表示質心,geometry 指定了幾何形狀和尺寸。<inertila>
標簽是慣性屬性,mass 表示質量,inertia 表示轉動慣量。 - 然后聲明了下方的關節 joint1。type 表示關節的連接類型。
<parent>
和<child>
指定連接關系中的父與子(連接時子運動父不動)。origin 表示關節的連接位置。axis 表示關節的鏈接方向是 x、y、z。dynamics 表示阻尼。 - 中間和上方的連桿也完全相同。
<!-- Hokuyo Laser --> <link name="hokuyo_link"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="0.1 0.1 0.1"/> </geometry> </collision> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <mesh filename="package://rrbot_description/meshes/hokuyo.dae"/> </geometry> </visual> <inertial> <mass value="1e-5" /> <origin xyz="0 0 0" rpy="0 0 0"/> <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" /> </inertial> </link> <joint name="camera_joint" type="fixed"> <axis xyz="0 1 0" /> <origin xyz="${camera_link} 0 ${height3 - axel_offset*2}" rpy="0 0 0"/> <parent link="link3"/> <child link="camera_link"/> </joint>
- 這一部分是對激光雷達的模型定義。其實與普通的 link 並沒有區別,只不過激光雷達導的是創建好的 hokuyo.dae 模型。
- 相機的模型定義類似,在該文件中並沒有體現出傳感器的特殊之處。
<transmission name="tran1"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint1"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="motor1"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> <transmission name="tran2"> <type>transmission_interface/SimpleTransmission</type> <joint name="joint2"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> </joint> <actuator name="motor2"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission>
- 這部分是關於傳動的聲明,每個
<transmission>
中定義了一個主動傳動。<type>
中指定了傳動類型,<joint>
中指定了所要傳動的關節和硬件層接口。<actuator>
定義了傳動的執行器,mechanicalReduction 是減速比。
-
rrbot.gazebo 文件:
<!-- ros_control plugin --> <gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/rrbot</robotNamespace> <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> </plugin> </gazebo>
- 這一部分指定了 ros_control 插件。通過 gazebo 標簽內包含
<plugin>
標簽,指定產假名、機器人的名字空間和機器人模型類型。
<!-- Link3 --> <gazebo reference="link3"> <mu1>0.2</mu1> <mu2>0.2</mu2> <material>Gazebo/Orange</material> </gazebo>
- 這一部分描述了 link 的物理屬性。mu 表示摩擦系數,material 表示材料,這里指定的是自己定義的材料。
<!-- hokuyo --> <gazebo reference="hokuyo_link"> <sensor type="gpu_ray" name="head_hokuyo_sensor"> <pose>0 0 0 0 0 0</pose> <visualize>false</visualize> <update_rate>40</update_rate> <ray> <scan> <horizontal> <samples>720</samples> <resolution>1</resolution> <min_angle>-1.570796</min_angle> <max_angle>1.570796</max_angle> </horizontal> </scan> <range> <min>0.10</min> <max>30.0</max> <resolution>0.01</resolution> </range> <noise> <type>gaussian</type> <!-- Noise parameters based on published spec for Hokuyo laser achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and stddev of 0.01m will put 99.7% of samples within 0.03m of the true reading. --> <mean>0.0</mean> <stddev>0.01</stddev> </noise> </ray> <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_gpu_laser.so"> <topicName>/rrbot/laser/scan</topicName> <frameName>hokuyo_link</frameName> </plugin> </sensor> </gazebo> </robot>
- sensor 標簽指定了這個 link 是一個傳感器。update_rate 是刷新率。scan 標簽中指定了采樣率、解析度和最大最小傳感角度。range 標簽中設置了最大最小傳感距離和解析度。noise 標簽中指定了噪聲。
<plugin>
中指定了一個插件,使用話題向外發布激光雷達的數據。 - 相機的基本流程與之類似,但有許多不同的屬性。
- 這一部分指定了 ros_control 插件。通過 gazebo 標簽內包含
-
material.xacro 文件:
<?xml version="1.0"?> <robot> <material name="black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> </robot>
- 為材料指定 RGBA 顏色屬性。
(2)、rrbot_gazebo包
-
rrbot_world 文件:
<?xml version="1.0" ?> <sdf version="1.4"> <!-- We use a custom world for the rrbot so that the camera angle is launched correctly --> <world name="default"> <include> <uri>model://ground_plane</uri> </include> <!-- Global light source --> <include> <uri>model://sun</uri> </include> <!-- Focus camera on tall pendulum --> <gui fullscreen='0'> <camera name='user_camera'> <pose>4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190</pose> <view_controller>orbit</view_controller> </camera> </gui> </world> </sdf>
- 創建世界,引入空地和太陽模型,並且指定視角。
-
rrobot_world.launch 文件:
<launch> <!-- these are the arguments you can pass this launch file, for example paused:=true --> <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"/> <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched --> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(find rrbot_gazebo)/worlds/rrbot.world"/> <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>
- 這一部分指定了launch文件內的宏定義參數,引入了空世界launch文件。
<!-- Load the URDF into the ROS Parameter Server --> <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find rrbot_description)/urdf/rrbot.xacro'" /> <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot --> <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -model rrbot -param robot_description"/> </launch>
- param 標簽將 URDF 模型的路徑加載到 ROS 參數服務器中。
- node 節點運行了 urdf_spawner 腳本啟動了一個服務,從 ROS 參數服務器中取出 robot_description 路徑指向了 URDF 文件加載到世界中。
(3)、rrbot_control 包
-
rrbot_control.launch 文件:
<launch> <!-- Load joint controller configurations from YAML file to parameter server --> <rosparam file="$(find rrbot_control)/config/rrbot_control.yaml" command="load"/> <!-- load the controllers --> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/rrbot" args="joint_state_controller joint1_position_controller joint2_position_controller"/> <!-- convert joint states to TF transforms for rviz, etc --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen"> <remap from="/joint_states" to="/rrbot/joint_states" /> </node> </launch>
- rosparam 標簽載入 yaml 配置文件。
- 第一個節點啟動了 joint_state_controller、joint1_position_controller、 joint2_position_controller 三個控制器。
- 第二個節點啟動了 robot_state_publisher 話題發布者。並且通過重映射重命名。
-
rrbot_rqt.launch 文件:
<launch> <!-- Load RQT with a pre-setup GUI for Baxter controls from a perspective file --> <node name="rrbot_rqt" pkg="rqt_gui" type="rqt_gui" respawn="false" output="screen" args="--perspective-file $(find rrbot_control)/launch/rrbot_rqt.perspective"/> </launch>
- 通過運行 rrbot_rqt.perspective 運行 rqt 的 GUI界面。
-
rrbot_control.yaml 文件:
rrbot: # Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Position Controllers --------------------------------------- joint1_position_controller: type: effort_controllers/JointPositionController joint: joint1 pid: {p: 100.0, i: 0.01, d: 10.0} joint2_position_controller: type: effort_controllers/JointPositionController joint: joint2 pid: {p: 100.0, i: 0.01, d: 10.0}
- 先是指定了 joint_state_controller 關節狀態發布者的類型和一秒內的發布速率。
- 然后指定了 joint1_position_controller 和 joint2_position_controller 關節位置控制者的類型、所控制的關節和 PID 參數。
3、自己做一個移動小車
(1)、創建底盤
-
先創建工作空間,將移動小車命名為 mycar。創建 mycar_description、mycar_gazebo 和 mycar_control。
-
進入 mycar_gazebo 下的 worlds 目錄,創建包含空地和太陽的最基本的世界文件 mycar.world。
<?xml version="1.0"?> <sdf version="1.4"> <world name="myworld"> <include> <uri>model://sun</uri> </include> <include> <uri>model://ground_plane</uri> </include> </world> </sdf>
-
進入 mycar_gazebo 下的 worlds 目錄,創建最基本的啟動世界文件 mycar.world 的 launch 文件 mycar_world.launch。
<launch> <include file="$(find gazebo_ros)/launch/empty_world.launch"> <arg name="world_name" value="$(find mycar_gazebo)/worlds/mybot.world"/> <arg name="gui" value="true"/> </include> </launch>
-
進入 mycar.descripiton 下的 urdf 目錄,創建小車模型文件 mycar.urdf。
<?xml version="1.0"?> <robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- Put here the robot description --> <!-- 宏定義各個部分的尺寸 --> <xacro:property name="PI" value="3.1415926535897931"/> <xacro:property name="chassisHeight" value="0.1"/> <xacro:property name="chassisLength" value="0.4"/> <xacro:property name="chassisWidth" value="0.2"/> <xacro:property name="chassisMass" value="50"/> <xacro:property name="casterRadius" value="0.05"/> <xacro:property name="casterMass" value="5"/> <xacro:property name="wheelWidth" value="0.05"/> <xacro:property name="wheelRadius" value="0.1"/> <xacro:property name="wheelPos" value="0.2"/> <xacro:property name="wheelMass" value="5"/> <xacro:property name="cameraSize" value="0.05"/> <xacro:property name="cameraMass" value="0.1"/> <!-- 導入三個依賴文件 --> <xacro:include filename="$(find mycar_description)/urdf/mycar.gazebo" /> <xacro:include filename="$(find mycar_description)/urdf/materials.xacro" /> <xacro:include filename="$(find mycar_description)/urdf/macros.xacro" /> <link name="footprint" /> <joint name="base_joint" type="fixed"> <parent link="footprint"/> <child link="chassis"/> </joint> <!-- 添加一個矩形底座 --> <link name='chassis'> <collision> <origin xyz="0 0 ${wheelRadius}" rpy="0 0 0"/> <geometry> <box size="${chassisLength} ${chassisWidth} ${chassisHeight}"/> </geometry> </collision> <visual> <origin xyz="0 0 ${wheelRadius}" rpy="0 0 0"/> <geometry> <box size="${chassisLength} ${chassisWidth} ${chassisHeight}"/> </geometry> <material name="orange"/> </visual> <inertial> <origin xyz="0 0 ${wheelRadius}" rpy="0 0 0"/> <mass value="${chassisMass}"/> <box_inertia m="${chassisMass}" x="${chassisLength}" y="${chassisWidth}" z="${chassisHeight}"/> </inertial> </link> </robot>
- 這一部分先是宏定義了小車各部分的尺寸,引入了依賴文件。
- 然后創建了小車的矩形底盤部分,小車的其他部分將在稍后添加。
-
進入 mycar.descripiton 下的 urdf 目錄,創建小車在gazebo中的屬性文件 mycar.gazebo。目前只指定了矩形底盤的材料。
<?xml version="1.0"?> <robot xmlns:xacro="http://www.ros.org/wiki/xacro"> <gazebo reference="chassis"> <material>Gazebo/Orange</material> </gazebo> </robot>
-
進入 mycar.descripiton 下的 urdf 目錄,創建小車的材料屬性文件 materials.xacro。此處指定了所有小車需要用到的材料(顏色)。
<?xml version="1.0"?> <robot> <material name="black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> <material name="blue"> <color rgba="0.0 0.0 0.8 1.0"/> </material> <material name="green"> <color rgba="0.0 0.8 0.0 1.0"/> </material> <material name="grey"> <color rgba="0.2 0.2 0.2 1.0"/> </material> <material name="orange"> <color rgba="${255/255} ${108/255} ${10/255} 1.0"/> </material> <material name="brown"> <color rgba="${222/255} ${207/255} ${195/255} 1.0"/> </material> <material name="red"> <color rgba="0.8 0.0 0.0 1.0"/> </material> <material name="white"> <color rgba="1.0 1.0 1.0 1.0"/> </material> </robot>
-
進入 mycar.descripiton 下的 urdf 目錄,創建小車的屬性宏定義文件 macros.xacro。
<?xml version="1.0"?> <robot> <macro name="cylinder_inertia" params="m r h"> <inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0" iyy="${m*(3*r*r+h*h)/12}" iyz = "0" izz="${m*r*r/2}" /> </macro> <macro name="box_inertia" params="m x y z"> <inertia ixx="${m*(y*y+z*z)/12}" ixy = "0" ixz = "0" iyy="${m*(x*x+z*z)/12}" iyz = "0" izz="${m*(x*x+z*z)/12}" /> </macro> <macro name="sphere_inertia" params="m r"> <inertia ixx="${2*m*r*r/5}" ixy = "0" ixz = "0" iyy="${2*m*r*r/5}" iyz = "0" izz="${2*m*r*r/5}" /> </macro> </robot>
- 對一些屬性的宏定義,這里是對圓柱、矩形和球形的轉動慣量的宏定義,通過輸入的 params 中的參數計算轉動慣量,在 mycar.urdf 中有用到。
-
在 mycar.gazebo 目錄下的 mybot_world.launch 文件中添加內容,使得世界啟動時加載機器人模型。
<!-- urdf xml robot description loaded on the Parameter Server, converting the xacro into a proper urdf file--> <param name="robot_description" command="$(find xacro)/xacro.py '$(find mycar_description)/urdf/mycar.xacro'" /> <!-- push robot_description to factory and spawn robot in gazebo --> <node name="mycar_spawn" pkg="gazebo_ros" type="spawn_model" output="screen" args="-urdf -param robot_description -model mycar" />
- 這部分首先將 robot_description 下的 mycar.xacro 路徑存儲到 ROS 參數服務器中,然后再加載入世界。
- 一定要注意不要將中文注釋粘貼進去。
-
運行 mycar_world.launch 文件:
$ roslaunch mycar_gazebo mycar_world.launch
-
運行結果為:
(2)、添加輪子
-
在 mycar.xacro 文件中添加以添加球形腳輪:
<joint name="fixed" type="fixed"> <parent link="chassis"/> <child link="caster_wheel"/> </joint> <link name="caster_wheel"> <collision> <origin xyz="${casterRadius-chassisLength/2} 0 ${casterRadius-chassisHeight+wheelRadius}" rpy="0 0 0"/> <geometry> <sphere radius="${casterRadius}"/> </geometry> </collision> <visual> <origin xyz="${casterRadius-chassisLength/2} 0 ${casterRadius-chassisHeight+wheelRadius}" rpy="0 0 0"/> <geometry> <sphere radius="${casterRadius}"/> </geometry> <material name="red"/> </visual> <inertial> <origin xyz="${casterRadius-chassisLength/2} 0 ${casterRadius-chassisHeight+wheelRadius}" rpy="0 0 0"/> <mass value="${casterMass}"/> <sphere_inertia m="${casterMass}" r="${casterRadius}"/> </inertial> </link>
-
在 materilas.xacro 文件中添加腳輪的屬性:
<gazebo reference="caster_wheel"> <mu1>0.0</mu1> <mu2>0.0</mu2> <material>Gazebo/Red</material> </gazebo>
-
在 macro.xacro 宏定義文件中,為兩個輪子使用宏定義簡化書寫。
<macro name="wheel" params="lr tY"> <link name="${lr}_wheel"> <collision> <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" /> <geometry> <cylinder length="${wheelWidth}" radius="${wheelRadius}"/> </geometry> </collision> <visual> <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" /> <geometry> <cylinder length="${wheelWidth}" radius="${wheelRadius}"/> </geometry> <material name="black"/> </visual> <inertial> <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" /> <mass value="${wheelMass}"/> <cylinder_inertia m="${wheelMass}" r="${wheelRadius}" h="${wheelWidth}"/> </inertial> </link> <gazebo reference="${lr}_wheel"> <mu1 value="1.0"/> <mu2 value="1.0"/> <kp value="10000000.0" /> <kd value="1.0" /> <fdir1 value="1 0 0"/> <material>Gazebo/Black</material> </gazebo> <joint name="${lr}_wheel_hinge" type="continuous"> <parent link="chassis"/> <child link="${lr}_wheel"/> <origin xyz="${-wheelPos+chassisLength/2} ${tY*wheelWidth/2+tY*chassisWidth/2} ${wheelRadius}" rpy="0 0 0" /> <axis xyz="0 1 0" rpy="0 0 0" /> <limit effort="100" velocity="100"/> <joint_properties damping="0.0" friction="0.0"/> </joint> <transmission name="${lr}_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${lr}_wheel_hinge"> <hardwareInterface>hardware_interface/ffortJointInterface</hardwareInterface> </joint> <actuator name="${lr}Motor"> <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface> <mechanicalReduction>10</mechanicalReduction> </actuator> </transmission> </macro>
- 宏定義的標簽是
<wheel>
,指定了 link 鏈接和 joint 關節,以及其屬性。最后定義了傳動。輸入的參數為左右輪和沿Y軸的正反方向。
- 宏定義的標簽是
-
將宏定義運用於 mycar.xacro 文件中。
<wheel lr="left" tY="1"/> <wheel lr="right" tY="-1"/>
-
運行 mycar_world.launch 文件:
$ roslaunch mycar_gazebo mycar_world.launch
-
運行結果為:
(3)、將小車連接到ROS
-
在 mybot.gazebo 中添加插件訪問車輪的關節。
<gazebo> <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"> <robotNamespace>/mycar</robotNamespace> </plugin> </gazebo>
-
在 mycar_control 包下的 config 目錄創建 mycar_control.yaml 配置文件。該文件將定義三個控制器:每個車輪一個控制權,通過變速箱標簽與關節的連接表示;一個用於發布關節狀態的控制器。它還定義了用於此控制器的PID增益:
mycar: # Publish all joint states ----------------------------------- joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Effort Controllers --------------------------------------- leftWheel_effort_controller: type: effort_controllers/JointEffortController joint: left_wheel_hinge pid: {p: 100.0, i: 0.1, d: 10.0} rightWheel_effort_controller: type: effort_controllers/JointEffortController joint: right_wheel_hinge pid: {p: 100.0, i: 0.1, d: 10.0}
-
在 mycar_control 包下的 launch 目錄創建 mycar_control.launch 文件用於啟動控制器。
<launch> <!-- Load joint controller configurations from YAML file to parameter server --> <rosparam file="$(find mycar_control)/config/mycar_control.yaml" command="load"/> <!-- load the controllers --> <node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" ns="/mycar" args="joint_state_controller rightWheel_effort_controller leftWheel_effort_controller" /> <!-- convert joint states to TF transforms for rviz, etc --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen"> <param name="robot_description" command="$(find xacro)/xacro.py '$(find mycar_description)/urdf/mycar.xacro'" /> <remap from="/joint_states" to="/mycar/joint_states" /> </node> </launch>
- 加載配置和控制器。
- 啟動一個節點,該節點發布機器人狀態信息。
-
在 mybot_world.launch 中添加一行來啟動控制器:
<!-- ros_control mybot launch file --> <include file="$(find mycar_control)/launch/mycar_control.launch" />
-
啟動世界:
$ roslaunch mycar_gazebo mycar_world.launch
-
查看話題列表,可以看到三個相關的話題話題:/mycar/joint_states、
/mycar/leftWheel_effort_controller/command和
/mycar/rightWheel_effort_controller/command。查看第一個話題的數據和第二個話題的信息如下圖。 -
發布運動指令與停止指令:
$ rostopic pub -1 /mycar/leftWheel_effort_controller/command std_msgs/Float64 "data: 1.5" $ rostopic pub -1 /mycar/rightWheel_effort_controller/command std_msgs/Float64 "data: 1.0" $ rostopic pub -1 /mycar/leftWheel_effort_controller/command std_msgs/Float64 "data: 0.0" $ rostopic pub -1 /mycar/rightWheel_effort_controller/command std_msgs/Float64 "data: 0.0"
-
小車開始運動:
(4)、機器人的遙控
-
之前的配置允許我們可以單獨控制關節,但是當想讓移動機器人四處移動時,這樣做並不方便。使用另一個稱為差分驅動器的插件來簡化,在 mycar.gazebo 中添加:
<gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <alwaysOn>true</alwaysOn> <updateRate>100</updateRate> <leftJoint>left_wheel_hinge</leftJoint> <rightJoint>right_wheel_hinge</rightJoint> <wheelSeparation>${chassisWidth+wheelWidth}</wheelSeparation> <wheelDiameter>${2*wheelRadius}</wheelDiameter> <torque>20</torque> <commandTopic>mycar/cmd_vel</commandTopic> <odometryTopic>mycar/odom_diffdrive</odometryTopic> <odometryFrame>odom</odometryFrame> <robotBaseFrame>footprint</robotBaseFrame> </plugin> </gazebo>
- 此插件將訂閱由
<commandTopic>
標記指定的cmd_vel主題。
- 此插件將訂閱由
-
要使用鍵盤對機器人進行遙控,可以使用turtlesim或turtlebot軟件包中提供的遙控節點。我們只需要重新映射主題名稱即可將其連接到我們的機器人:
$ rosrun turtlesim turtle_teleop_key /turtle1/cmd_vel:=/mycar/cmd_vel
-
用鍵盤控制機器人:
(5)、添加相機
-
在 mycar.xacro 中添加照相機:
<joint name="camera_fix" type="fixed"> <parent link="chassis"/> <child link="camera"/> <origin xyz="${chassisLength/2} 0 ${chassisHeight}" rpy="0 0 0" /> <axis xyz="1 0 0" rpy="0 0 0" /> </joint> <link name="camera"> <collision> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="${cameraSize} ${cameraSize} ${cameraSize}"/> </geometry> </collision> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> <geometry> <box size="${cameraSize} ${cameraSize} ${cameraSize}"/> </geometry> <material name="blue"/> </visual> <inertial> <mass value="${cameraMass}" /> <origin xyz="0 0 0" rpy="0 0 0"/> <box_inertia m="${cameraMass}" x="${cameraSize}" y="${cameraSize}" z="${cameraSize}" /> </inertial> </link>
-
在 mycar.gazebo 文件中添加相機插件:
<gazebo reference="camera"> <material>Gazebo/Blue</material> <sensor type="camera" name="camera1"> <update_rate>30.0</update_rate> <camera name="head"> <horizontal_fov>1.3962634</horizontal_fov> <image> <width>800</width> <height>800</height> <format>R8G8B8</format> </image> <clip> <near>0.02</near> <far>300</far> </clip> </camera> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> <alwaysOn>true</alwaysOn> <updateRate>0.0</updateRate> <cameraName>mycar/camera1</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName> <frameName>camera_link</frameName> <hackBaseline>0.07</hackBaseline> <distortionK1>0.0</distortionK1> <distortionK2>0.0</distortionK2> <distortionK3>0.0</distortionK3> <distortionT1>0.0</distortionT1> <distortionT2>0.0</distortionT2> </plugin> </sensor> </gazebo>
-
使用image_view工具直接對相機圖像進行可視化:
$ rosrun image_view image_view image:=/mycar/camera1/image_raw
-
結果為:
iwehdio的博客園:https://www.cnblogs.com/iwehdio/