大家好,我是夢筆生花,我們一起來動手創建一個兩輪差速的移動機器人fishbot。
機器人除了雷達之外,還需要IMU加速度傳感器以及可以驅動的輪子,我們曾介紹過機器人學部分,曾對兩差速模型進行過介紹,所以我們還需要再創建兩個差速驅動輪和一個支撐輪。
所以接下來夢筆生花將帶你一起給機器人添加如下部件和關節:
- IMU傳感器部件與關節
- 左輪子部件與關節
- 右輪子部件與關節
- 支撐輪子部件與關節
1.添加IMU傳感器
1.1 修改顏色
透明度修改只需要在base_link中添加material
<link name="base_link">
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.12" radius="0.10"/>
</geometry>
<material name="blue">
<color rgba="0.1 0.1 1.0 0.5" />
</material>
</visual>
</link>
1.2 添加imu
<link name="imu_link">
<visual>
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<geometry>
<box size="0.02 0.02 0.02"/>
</geometry>
</visual>
</link>
<!-- imu joint -->
<joint name="imu_joint" type="fixed">
<parent link="base_link" />
<child link="imu_link" />
<origin xyz="0 0 0.02" />
</joint>
2.添加右輪
2.1 添加關節
關節名稱為right_wheel_link,我在做ros2小車的時候採用的輪子如下圖:
輪子的寬為4cm,直徑為6.4cm,幾何形狀是個圓柱體,所以geometry配置如下:
<geometry>
<cylinder length="0.04" radius="0.032"/>
</geometry>
需要注意的是,圓柱默認的朝向是向上的
我們可通過origin的rpy改變輪子的旋轉角度,讓其繞x軸旋轉pi/2,所以origin的配置為
<origin xyz="0 0 0" rpy="1.57079 0 0"/>
顏色換黑色,可以得到下面的配置:
<link name="right_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.57079 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.032"/>
</geometry>
<material name="black">
<color rgba="0.0 0.0 0.0 0.5" />
</material>
</visual>
</link>
2.2 添加joint
我們把左輪子的中心固定在機器人左後方
需要注意的是origin和axis值的設置
先看origin
因為base_link的高度是0.12,我們
- z表示child相對parent的z軸上的關係,想將輪子固定在機器人的下表面,所以
origin的z向下偏移0.12/2=0.06m(向下符號為負) - y表示child相對parent的y軸上的關係,base_link的半徑是0.10,所以我們讓輪子的y軸向負方向偏移0.10m(向左符號為負)
- x表示child相對parent的x軸上的關係,向後偏移則是x軸向後進行偏移,我們用個差不多的值0.02m(向後符號為負)
再看axis
輪子是會轉動的,那應該按照哪個軸轉動呢?從上圖可以看出是繞着y軸的逆時針方向,所以axis的設置為:
<axis xyz="0 1 0" />
<joint name="right_wheel_joint" type="continuous">
<parent link="base_link" />
<child link="right_wheel_link" />
<origin xyz="-0.02 -0.10 -0.06" />
<axis xyz="0 1 0" />
</joint>
3.添加左輪
左輪就是右輪的映射,不再贅述
<link name="left_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.57079 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.032"/>
</geometry>
<material name="black">
<color rgba="0.0 0.0 0.0 0.5" />
</material>
</visual>
</link>
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link" />
<child link="left_wheel_link" />
<origin xyz="-0.02 0.10 -0.06" />
<axis xyz="0 1 0" />
</joint>
4.添加支撐輪
支撐輪子固定在機器人的前方,用個球體,半徑用0.016m,小球的直徑為0.032m與左右輪子半徑相同,然後向下偏移0.016+0.06=0.076m,向下值為負,同時把支撐論向前移動一些,選個0.06m
最終結果如下:
<link name="caster_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.016"/>
</geometry>
<material name="black">
<color rgba="0.0 0.0 0.0 0.5" />
</material>
</visual>
</link>
<joint name="caster_joint" type="fixed">
<parent link="base_link" />
<child link="caster_link" />
<origin xyz="0.06 0.0 -0.076" />
</joint>
最終URDF文件:https://raw.githubusercontent.com/fishros/fishbot/master/src/fishbot_description/urdf/fishbot_base.urdf
5.測試運行
5.1 編譯測試
colcon build
source install/setup.bash
ros2 launch fishbot_description display_rviz2.launch.py
5.2 最終結果
rviz的配置
最終結果
jointstate多出兩個滑動條
節點關係
5.3 通過joint_state_gui改變關節tf中關節角度
在JointStatePublisher中,拖動滑動條,觀察
rviz2中tf的變換joint_states中的值的變換
可以看到隨着進度條拖動,話題中的值和rviz2中機器人關節在同步的旋轉,joint_states話題也可以手動發送。
5.4 論如何讓車輪着地
雖然顯示出了機器人模型,但有一個問題不知道你發現沒有,那就是在RVIZ中的機器人輪子是在地面之下的。
原因在於我們fixed-frame選擇的是base_link,base_link的位置本來就在left_wheel_link和right_wheel_link只上,那該怎麼辦呢?
其實很簡單,我們增加一個虛擬link和關節,這個關節與base_link相連,位置位於base_link向下剛好到車輪下表面的位置。
來,讓我們**給base_link添加一個父link-base_footprint**,新增的URDF代碼如下:
<!-- Robot Footprint -->
<link name="base_footprint"/>
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 0.076" rpy="0 0 0"/>
</joint>
因為是虛擬關節,我們不用對這個link的形狀進行描述,joint的origin設置為xyz="0.0 0.0 0.076"表示關節base_footprint向上0.076就是base_link(覺得不好理解可以看下圖)。
保存編譯再次運行測試,此時車輪就在地面只上啦~