序言
這個(gè)教程演示了gazebo的基本操作,并且對(duì)模型數(shù)據(jù)庫內(nèi)的各個(gè)基本參數(shù)進(jìn)行了基本講解,你可以通過下面的過程創(chuàng)造一個(gè)兩輪小車,進(jìn)行基本的移動(dòng)。
建立模型文件夾
建立模型的第一步是要建立一個(gè)符合模型數(shù)據(jù)庫規(guī)則的文件系統(tǒng),關(guān)于模型的細(xì)節(jié)描述可以看SDF。
1.創(chuàng)建模型文件夾
mkdir -p ~/.gazebo/models/my_robot
2.創(chuàng)建模型config文件(配置)
gedit ~/.gazebo/models/my_robot/model.config
3.在config文件當(dāng)中貼入下列程序
<?xml version="1.0"?>
<model>
<name>My Robot</name>
<version>1.0</version>
<sdf version='1.4'>model.sdf</sdf>
<author>
<name>My Name</name>
<email>me@my.email</email>
</author>
<description>
My awesome robot.
</description>
</model>
4.創(chuàng)建一個(gè)~/.gazebo/models/my_robot/model.sdf
文件
gedit ~/.gazebo/models/my_robot/model.sdf
5.把下面內(nèi)容貼進(jìn)去
<sdf version='1.4'>
<model name="my_robot">
</model>
</sdf>
現(xiàn)在我們有了一個(gè)模型基本的內(nèi)容,這個(gè)model.config
文件通過一些額外的數(shù)據(jù)描述了這個(gè)機(jī)器人。這個(gè)機(jī)器人的名字叫做my_robot,機(jī)器人使用的sdf文件版本為1.4。
建立模型框架
這一步會(huì)建立一個(gè)長(zhǎng)方形底座和兩個(gè)輪子
從一個(gè)基本的模型開始,慢慢建立一個(gè)機(jī)器人是很重要的,第一步是把基本形狀布置在模型中,做這一步會(huì)使我們的模型進(jìn)入static
狀態(tài),意味著它將不使用物理引擎。它會(huì)一直呆在一個(gè)地方,讓我們可以裝配所有組件。
1.讓模型變?yōu)殪o態(tài)是通過加入<static>true</static>
元素進(jìn)入~/.gazebo/models/my_robot/model.sdf
當(dāng)中實(shí)現(xiàn)的。
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="my_robot">
<static>true</static>
</model>
</sdf>
2.然后通過編輯~/.gazebo/models/my_robot/model.sdf
加入基本長(zhǎng)方體。
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="my_robot">
<static>true</static>
<link name='chassis'>
<pose>0 0 .1 0 0 0</pose>
<collision name='collision'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</visual>
</link>
</model>
</sdf>
在這里我們建立了一個(gè)形狀為0.40.20.1的盒子,這里的碰撞引擎通過碰撞元素(collision)定義的形狀進(jìn)行檢測(cè)。渲染引擎通過可視化元素(visual)進(jìn)行渲染,對(duì)于大部分情況來說,碰撞以及渲染元素是一樣的。當(dāng)visual的網(wǎng)格很復(fù)雜時(shí),可以通過簡(jiǎn)化碰撞元素來提高運(yùn)行效果。
3.嘗試在gazebo里插入這個(gè)模型
gazebo
你可以看到一個(gè)白色的盒子飄在地面上1m處。
點(diǎn)一下他就會(huì)落下來
4.現(xiàn)在我們可以在機(jī)器人上加入輪子了,輪子是一個(gè)沒有摩擦的球體,這種形狀的輪子會(huì)比加一個(gè)有關(guān)節(jié)的輪子更好,因?yàn)樗鼫p少了約束,使物理引擎運(yùn)算更加簡(jiǎn)單。(想看完整robot代碼的可以直接往下拉)
<collision name='caster_collision'>
<pose>-0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='caster_visual'>
<pose>-0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
</visual>
5.加入一個(gè)左輪
<link name="left_wheel">
<pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</visual>
</link>
6.然后插入一個(gè)右輪,跟左輪差不多,只不過pose當(dāng)中的位置發(fā)生了改變。
<link name="right_wheel">
<pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</visual>
</link>
7.把<static>設(shè)置為false然后在左輪和右輪上加入兩個(gè)關(guān)節(jié)。
<static>false</static>
<joint type="revolute" name="left_wheel_hinge">
<pose>0 0 -0.03 0 0 0</pose>
<child>left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint type="revolute" name="right_wheel_hinge">
<pose>0 0 0.03 0 0 0</pose>
<child>right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
兩個(gè)關(guān)節(jié)繞y軸旋轉(zhuǎn)<xyz>0 1 0 </xyz>,把輪子和底座連接起來。
sdf文件完整代碼
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="my_robot">
<static>false</static>
<link name='chassis'>
<pose>0 0 .1 0 0 0</pose>
<collision name='collision'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</visual>
<collision name='caster_collision'>
<pose>-0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='caster_visual'>
<pose>-0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
</visual>
</link>
<link name="left_wheel">
<pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</visual>
</link>
<link name="right_wheel">
<pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</visual>
</link>
<joint type="revolute" name="left_wheel_hinge">
<pose>0 0 -0.03 0 0 0</pose>
<child>left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint type="revolute" name="right_wheel_hinge">
<pose>0 0 0.03 0 0 0</pose>
<child>right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
</model>
</sdf>
8.打開gazebo,點(diǎn)擊insert,把模型從左邊來勁來,然后放進(jìn)去。
9.可以在gazebo打開后把右邊中間的點(diǎn)點(diǎn)拉開
點(diǎn)擊小車調(diào)整force的數(shù)值,或者之間點(diǎn)擊要改變的那個(gè)物理,選擇force然后在y軸加上一定的力,小車就會(huì)開始移動(dòng)了(注意力不要太大不然會(huì)跑得很快,推薦小于1。