< >
Home » ROS2与Ignition入门教程 » Ignition入门教程-利用SDF构建机器人

Ignition入门教程-利用SDF构建机器人

Ignition入门教程-利用SDF构建机器人

说明:

  • 我们将学习如何在 SDFormat 中构建我们自己的机器人。
  • 我们将构建一个简单的两轮机器人。

SDFormat

  • http://sdformat.org/

  • SDFormat(Simulation Description Format),有时缩写为 SDF,是一种 XML 格式,用于描述机器人模拟器、可视化和控制的对象和环境。 SDFormat 最初是作为 Gazebo 机器人模拟器的一部分开发的,其设计时考虑了科学机器人应用。 多年来,SDFormat 已经成为一种稳定、健壮和可扩展的格式,能够描述机器人、静态和动态对象、光照、地形甚至物理的各个方面。

  • 您可以使用 SDFormat 准确地描述机器人的各个方面,无论机器人是带轮子的简单底盘还是人形机器人。 除了运动学和动态属性之外,还可以为机器人定义传感器、表面属性、纹理、关节摩擦以及更多属性。 这些功能允许您使用 SDFormat 进行仿真、可视化、运动规划和机器人控制。

  • 仿真需要模型存在和交互的丰富而复杂的环境。 SDFormat 提供了定义各种环境的方法。 环境、地形(虚构或基于 DEM)、OpenStreetMaps 中的街道以及 The Prop Shop 提供的任何模型(在 3D 模型的在线存储库上)中可能包含多个灯光。

构建世界

  • 我们将从构建一个简单的世界开始,然后在其中构建我们的机器人。
  • 打开一个新文件,命名为building_robot.sdf,并将以下代码复制到其中。
<?xml version="1.0" ?>
<sdf version="1.7">
    <world name="car_world">
        <physics name="1ms" type="ignored">
            <max_step_size>0.001</max_step_size>
            <real_time_factor>1.0</real_time_factor>
        </physics>
        <plugin
            filename="libignition-gazebo-physics-system.so"
            name="ignition::gazebo::systems::Physics">
        </plugin>
        <plugin
            filename="libignition-gazebo-user-commands-system.so"
            name="ignition::gazebo::systems::UserCommands">
        </plugin>
        <plugin
            filename="libignition-gazebo-scene-broadcaster-system.so"
            name="ignition::gazebo::systems::SceneBroadcaster">
        </plugin>

        <gui fullscreen="0">

            <!-- 3D scene -->
            <plugin filename="GzScene3D" name="3D View">
                <ignition-gui>
                <title>3D View</title>
                <property type="bool" key="showTitleBar">false</property>
                <property type="string" key="state">docked</property>
                </ignition-gui>

                <engine>ogre2</engine>
                <scene>scene</scene>
                <ambient_light>0.4 0.4 0.4</ambient_light>
                <background_color>0.8 0.8 0.8</background_color>
            </plugin>

            <!-- World control -->
            <plugin filename="WorldControl" name="World control">
                <ignition-gui>
                <title>World control</title>
                <property type="bool" key="showTitleBar">false</property>
                <property type="bool" key="resizable">false</property>
                <property type="double" key="height">72</property>
                <property type="double" key="width">121</property>
                <property type="double" key="z">1</property>

                <property type="string" key="state">floating</property>
                <anchors target="3D View">
                    <line own="left" target="left"/>
                    <line own="bottom" target="bottom"/>
                </anchors>
                </ignition-gui>

                <play_pause>true</play_pause>
                <step>true</step>
                <start_paused>true</start_paused>
                <service>/world/car_world/control</service>
                <stats_topic>/world/car_world/stats</stats_topic>
            </plugin>

            <!-- World statistics -->
            <plugin filename="WorldStats" name="World stats">
                <ignition-gui>
                <title>World stats</title>
                <property type="bool" key="showTitleBar">false</property>
                <property type="bool" key="resizable">false</property>
                <property type="double" key="height">110</property>
                <property type="double" key="width">290</property>
                <property type="double" key="z">1</property>

                <property type="string" key="state">floating</property>
                <anchors target="3D View">
                    <line own="right" target="right"/>
                    <line own="bottom" target="bottom"/>
                </anchors>
                </ignition-gui>

                <sim_time>true</sim_time>
                <real_time>true</real_time>
                <real_time_factor>true</real_time_factor>
                <iterations>true</iterations>
                <topic>/world/car_world/stats</topic>

            </plugin>

            <!-- Entity tree -->
            <plugin filename="EntityTree" name="Entity tree">
            </plugin>

        </gui>

        <light type="directional" name="sun">
            <cast_shadows>true</cast_shadows>
            <pose>0 0 10 0 0 0</pose>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
            <attenuation>
                <range>1000</range>
                <constant>0.9</constant>
                <linear>0.01</linear>
                <quadratic>0.001</quadratic>
            </attenuation>
            <direction>-0.5 0.1 -0.9</direction>
        </light>

        <model name="ground_plane">
            <static>true</static>
            <link name="link">
                <collision name="collision">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    </plane>
                </geometry>
                </collision>
                <visual name="visual">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    <size>100 100</size>
                    </plane>
                </geometry>
                <material>
                    <ambient>0.8 0.8 0.8 1</ambient>
                    <diffuse>0.8 0.8 0.8 1</diffuse>
                    <specular>0.8 0.8 0.8 1</specular>
                </material>
                </visual>
            </link>
        </model>
    </world>
</sdf>
  • 启动Ignition并指定文件
ign gazebo building_robot.sdf
  • 效果图 

请输入图片描述

创建模型

  • 在 标签下,我们将添加我们的机器人模型,如下所示:

定义模型

<model name='vehicle_blue' canonical_link='chassis'>
    <pose relative_to='world'>0 0 0 0 0 0</pose>
  • 这里我们定义了我们的模型vehicle_blue的名称,同级别的其他标签或模型中唯一的名称。 每个模型可能有一个指定为 canonical_link 的链接,模型的隐式框架附加到此链接。 如果未定义,第一个 将被选为规范链接。

  • 标签用于定义模型的位置和方向,relative_to 属性用于定义模型相对于任何其他帧的位姿。 如果未定义 relative_to,则模型的 将相对于世界。

  • 让我们的姿势相对于世界。 位姿标签内的值如下:X Y Z R P Y,其中X Y Z代表帧的位置,R P Y代表roll pitch yaw的方向。 我们将它们设置为零,这使得两个框架(模型和世界)相同。

链接形成我们的机器人

  • 每个模型都是通过joints连接在一起的一组links (可以只是一个links )。

主体

  • 底盘结构/chassis
<link name='chassis'>
        <pose relative_to='__model__'>0.5 0 0.4 0 0 0</pose>
  • 我们定义了第一个link ,我们的底盘和它相对于模型的姿势

  • 惯性特性/Inertial properties

 <inertial> <!--inertial properties of the link mass, inertia matix-->
        <mass>1.14395</mass>
        <inertia>
            <ixx>0.095329</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.381317</iyy>
            <iyz>0</iyz>
            <izz>0.476646</izz>
        </inertia>
    </inertial>
  • 在这里,我们定义了底盘的惯性属性,例如mass 和 矩阵。
  • 可以使用质量惯性计算器计算原始形状的惯性矩阵值。
  • 视觉/Visual
  <visual name='visual'>
        <geometry>
            <box>
                <size>2.0 1.0 0.5</size>
            </box>
        </geometry>
        <!--let's add color to our link-->
        <material>
            <ambient>0.0 0.0 1.0 1</ambient>
            <diffuse>0.0 0.0 1.0 1</diffuse>
            <specular>0.0 0.0 1.0 1</specular>
        </material>
    </visual>  
  • 顾名思义, 标签负责我们的链接的外观。

  • 我们将 标签内的链接形状定义为 (长方体),然后在 标签内指定此框的三个维度(以米为单位)。

  • 然后,在 标签内,我们定义了链接的材质。 在这里,我们将 颜色定义为一组 red/green/blue/alpha 四个数字,每个数字都在 [0, 1] 范围内。

  • 碰撞/collision

        <collision name='collision'>
            <geometry>
                <box>
                    <size>2.0 1.0 0.5</size>
                </box>
            </geometry>
        </collision>
    </link>
</model>
  • 标签定义了链接的碰撞属性,我们的链接将如何与其他对象反应以及物理引擎对其的影响。

  • 注意: 可以与视觉属性不同,例如,通常使用更简单的碰撞模型来减少计算时间。

  • 将上述所有部分按顺序复制到世界文件中后,再次运行世界:

ign gazebo building_robot.sdf
  • 效果图

请输入图片描述

  • 在右上角单击插件下拉列表(垂直省略号),选择变换控件,选择您的模型,然后单击Transform control。
  • 您应该看到三个轴,如下所示:

请输入图片描述

  • 这些是我们模型的轴,其中红色是 x 轴,绿色是 y 轴,蓝色是 z 轴。

左轮

 - 让我们为我们的机器人添加轮子。

  • 以下代码位于 标记之后和 标记之前。
  • 属于同一模型的所有链接和关节应在之前定义。
<link name='left_wheel'>
    <pose relative_to="chassis">-0.5 0.6 0 -1.5707 0 0</pose>
    <inertial>
        <mass>1</mass>
        <inertia>
            <ixx>0.043333</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.043333</iyy>
            <iyz>0</iyz>
            <izz>0.08</izz>
        </inertia>
    </inertial>
  • 我们定义了链接 left_wheel 的名称,然后定义了它的 relative_to 底盘链接。
  • 车轮需要放置在底盘背面的左侧,因此我们将pose 的值选择为-0.5 0.6 0。
  • 此外,我们的车轮是一个圆柱体,但在其侧面。
  • 这就是我们将方向值定义为 -1.5707 0 0 的原因,即绕 x 轴旋转 -90 度(角度以弧度为单位)。
  • 然后我们定义了车轮的惯性特性、质量和惯性矩阵。
  • 视觉与碰撞
 <visual name='visual'>
        <geometry>
            <cylinder>
                <radius>0.4</radius>
                <length>0.2</length>
            </cylinder>
        </geometry>
        <material>
            <ambient>1.0 0.0 0.0 1</ambient>
            <diffuse>1.0 0.0 0.0 1</diffuse>
            <specular>1.0 0.0 0.0 1</specular>
        </material>
    </visual>
    <collision name='collision'>
        <geometry>
            <cylinder>
                <radius>0.4</radius>
                <length>0.2</length>
            </cylinder>
        </geometry>
    </collision>
</link>
  • 属性与前面的链接类似,不同之处在于我们链接的形状具有 <圆柱体> 的形状,需要两个属性:圆柱体的
  • 保存文件并再次运行世界,我们的模型应该如下所示:

请输入图片描述

右轮:

 - 右轮与左轮相似,只是其位置不同。

<!--The same as left wheel but with different position-->
<link name='right_wheel'>
    <pose relative_to="chassis">-0.5 -0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
    <inertial>
        <mass>1</mass>
        <inertia>
            <ixx>0.043333</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.043333</iyy>
            <iyz>0</iyz>
            <izz>0.08</izz>
        </inertia>
    </inertial>
    <visual name='visual'>
        <geometry>
            <cylinder>
                <radius>0.4</radius>
                <length>0.2</length>
            </cylinder>
        </geometry>
        <material>
            <ambient>1.0 0.0 0.0 1</ambient>
            <diffuse>1.0 0.0 0.0 1</diffuse>
            <specular>1.0 0.0 0.0 1</specular>
        </material>
    </visual>
    <collision name='collision'>
        <geometry>
            <cylinder>
                <radius>0.4</radius>
                <length>0.2</length>
            </cylinder>
        </geometry>
    </collision>
</link>

增加脚轮框架

 - SDF 1.7 的新特性之一是我们可以定义任意帧。 它需要两个属性:

name:框架的名称
attach_to:框架的名称或该框架所附加到的链接。
  • 让我们为我们的脚轮添加一个框架,如下所示:
<frame name="caster_frame" attached_to='chassis'>
    <pose>0.8 0 -0.2 0 0 0</pose>
</frame>
  • 我们给框架命名为 caster_frame 并将其附加到底盘链接,然后使用 标签来定义框架的位置和方向。
  • 我们没有使用 relative_to 属性,所以姿势是相对于 attach_to 属性中命名的框架,在我们的例子中是底盘。
  • 脚轮
<!--caster wheel-->
<link name='caster'>
    <pose relative_to='caster_frame'/>
    <inertial>
        <mass>1</mass>
        <inertia>
            <ixx>0.016</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>0.016</iyy>
            <iyz>0</iyz>
            <izz>0.016</izz>
        </inertia>
    </inertial>
    <visual name='visual'>
        <geometry>
            <sphere>
                <radius>0.2</radius>
            </sphere>
        </geometry>
        <material>
            <ambient>0.0 1 0.0 1</ambient>
            <diffuse>0.0 1 0.0 1</diffuse>
            <specular>0.0 1 0.0 1</specular>
        </material>
    </visual>
    <collision name='collision'>
        <geometry>
            <sphere>
                <radius>0.2</radius>
            </sphere>
        </geometry>
    </collision>
</link>
  • 我们的最后一个链接是caster,它的姿势是关于我们上面定义的框架 caster_frame 的。
  • 正如你可能注意到的,我们关闭了姿势标签而没有定义位置或方向;
  • 在这种情况下,链接的位姿与 relative_to 中的(身份)帧相同。
  • 标签中,我们定义了一个不同的形状 ,它需要球体的

joint/关节

  • 我们需要将这些链接连接在一起; 标签的作用就在这里。
  • 联合标签将两个链接连接在一起并定义它们将如何相对于彼此移动。
  • 标记内,我们需要定义要连接的两个链接及其关系(移动方式)。
  • 左轮关节
<joint name='left_wheel_joint' type='revolute'>
    <pose relative_to='left_wheel'/>

 - 我们的第一个关节是 left_wheel_joint。 它有两个属性:名称 name='left_wheel_joint' 和类型 type='revolute'。

  • revolute 类型提供 1 个带有关节限制的旋转自由度。
  • 关节的位姿与子链接框架相同,即left_wheel框架。
  • 父子关系
 <parent>chassis</parent>
    <child>left_wheel</child>
  • 每个关节将两个链接(主体)连接在一起。
  • 在这里,我们将chassis与 left_wheel 连接起来。
  • chassis 是父链接,left_wheel 是子链接。
  • 旋转轴
  <axis>
        <xyz expressed_in='__model__'>0 1 0</xyz> <!--can be defined as any frame or even arbitrary frames-->
        <limit>
            <lower>-1.79769e+308</lower>    <!--negative infinity-->
            <upper>1.79769e+308</upper>     <!--positive infinity-->
        </limit>
    </axis>
</joint>
  • 这里我们定义旋转轴。 旋转轴可以是任何框架,而不仅仅是父链接或子链接。
  • 我们选择了相对于模型框架的 y 轴,因此我们将 1 放在 y 元素中,将零放在其他元素中。
  • 对于旋转关节,我们需要在 标签中定义旋转角度的
  • 注意:角度以弧度为单位。
  • 右轮关节
<joint name='right_wheel_joint' type='revolute'>
    <pose relative_to='right_wheel'/>
    <parent>chassis</parent>
    <child>right_wheel</child>
    <axis>
        <xyz expressed_in='__model__'>0 1 0</xyz>
        <limit>
            <lower>-1.79769e+308</lower>    <!--negative infinity-->
            <upper>1.79769e+308</upper>     <!--positive infinity-->
        </limit>
    </axis>
</joint>
  • 除了关节的位姿外,right_wheel_joint 非常相似。 该接头将 right_wheel 与底盘连接起来。

  • 脚轮关节

 <joint name='caster_wheel' type='ball'>
    <parent>chassis</parent>
    <child>caster</child>
  </joint>
  • 对于脚轮,我们需要不同类型的接头(连接)。
  • 我们使用了 type='ball' ,它给出了 3 个旋转自由度。

测试:

  • 上面的完整版本: 
<?xml version="1.0" ?>
<sdf version="1.7">
    <world name="car_world">
        <physics name="1ms" type="ignored">
            <max_step_size>0.001</max_step_size>
            <real_time_factor>1.0</real_time_factor>
        </physics>
        <plugin
            filename="libignition-gazebo-physics-system.so"
            name="ignition::gazebo::systems::Physics">
        </plugin>
        <plugin
            filename="libignition-gazebo-user-commands-system.so"
            name="ignition::gazebo::systems::UserCommands">
        </plugin>
        <plugin
            filename="libignition-gazebo-scene-broadcaster-system.so"
            name="ignition::gazebo::systems::SceneBroadcaster">
        </plugin>

        <gui fullscreen="0">

            <!-- 3D scene -->
            <plugin filename="GzScene3D" name="3D View">
                <ignition-gui>
                <title>3D View</title>
                <property type="bool" key="showTitleBar">false</property>
                <property type="string" key="state">docked</property>
                </ignition-gui>

                <engine>ogre2</engine>
                <scene>scene</scene>
                <ambient_light>0.4 0.4 0.4</ambient_light>
                <background_color>0.8 0.8 0.8</background_color>
            </plugin>

            <!-- World control -->
            <plugin filename="WorldControl" name="World control">
                <ignition-gui>
                <title>World control</title>
                <property type="bool" key="showTitleBar">false</property>
                <property type="bool" key="resizable">false</property>
                <property type="double" key="height">72</property>
                <property type="double" key="width">121</property>
                <property type="double" key="z">1</property>

                <property type="string" key="state">floating</property>
                <anchors target="3D View">
                    <line own="left" target="left"/>
                    <line own="bottom" target="bottom"/>
                </anchors>
                </ignition-gui>

                <play_pause>true</play_pause>
                <step>true</step>
                <start_paused>true</start_paused>
                <service>/world/car_world/control</service>
                <stats_topic>/world/car_world/stats</stats_topic>
            </plugin>

            <!-- World statistics -->
            <plugin filename="WorldStats" name="World stats">
                <ignition-gui>
                <title>World stats</title>
                <property type="bool" key="showTitleBar">false</property>
                <property type="bool" key="resizable">false</property>
                <property type="double" key="height">110</property>
                <property type="double" key="width">290</property>
                <property type="double" key="z">1</property>

                <property type="string" key="state">floating</property>
                <anchors target="3D View">
                    <line own="right" target="right"/>
                    <line own="bottom" target="bottom"/>
                </anchors>
                </ignition-gui>

                <sim_time>true</sim_time>
                <real_time>true</real_time>
                <real_time_factor>true</real_time_factor>
                <iterations>true</iterations>
                <topic>/world/car_world/stats</topic>

            </plugin>

            <!-- Entity tree -->
            <plugin filename="EntityTree" name="Entity tree">
            </plugin>

        </gui>

        <light type="directional" name="sun">
            <cast_shadows>true</cast_shadows>
            <pose>0 0 10 0 0 0</pose>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
            <attenuation>
                <range>1000</range>
                <constant>0.9</constant>
                <linear>0.01</linear>
                <quadratic>0.001</quadratic>
            </attenuation>
            <direction>-0.5 0.1 -0.9</direction>
        </light>

        <model name="ground_plane">
            <static>true</static>
            <link name="link">
                <collision name="collision">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    </plane>
                </geometry>
                </collision>
                <visual name="visual">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    <size>100 100</size>
                    </plane>
                </geometry>
                <material>
                    <ambient>0.8 0.8 0.8 1</ambient>
                    <diffuse>0.8 0.8 0.8 1</diffuse>
                    <specular>0.8 0.8 0.8 1</specular>
                </material>
                </visual>
            </link>
        </model>
        <model name='vehicle_blue' canonical_link='chassis'>
            <pose relative_to='world'>0 0 0 0 0 0</pose>
        
            <link name='chassis'>
                <pose relative_to='__model__'>0.5 0 0.4 0 0 0</pose>
                <inertial> <!--inertial properties of the link mass, inertia matix-->
                    <mass>1.14395</mass>
                    <inertia>
                        <ixx>0.095329</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.381317</iyy>
                        <iyz>0</iyz>
                        <izz>0.476646</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <box>
                            <size>2.0 1.0 0.5</size>
                        </box>
                    </geometry>
                    <!--let's add color to our link-->
                    <material>
                        <ambient>0.0 0.0 1.0 1</ambient>
                        <diffuse>0.0 0.0 1.0 1</diffuse>
                        <specular>0.0 0.0 1.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <box>
                            <size>2.0 1.0 0.5</size>
                        </box>
                    </geometry>
                </collision>
            </link>

            <link name='left_wheel'>
                <pose relative_to="chassis">-0.5 0.6 0 -1.5707 0 0</pose>
                <inertial>
                    <mass>1</mass>
                    <inertia>
                        <ixx>0.043333</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.043333</iyy>
                        <iyz>0</iyz>
                        <izz>0.08</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                    <material>
                        <ambient>1.0 0.0 0.0 1</ambient>
                        <diffuse>1.0 0.0 0.0 1</diffuse>
                        <specular>1.0 0.0 0.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                </collision>
            </link> 

            <link name='right_wheel'>
                <pose relative_to="chassis">-0.5 -0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
                <inertial>
                    <mass>1</mass>
                    <inertia>
                        <ixx>0.043333</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.043333</iyy>
                        <iyz>0</iyz>
                        <izz>0.08</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                    <material>
                        <ambient>1.0 0.0 0.0 1</ambient>
                        <diffuse>1.0 0.0 0.0 1</diffuse>
                        <specular>1.0 0.0 0.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <cylinder>
                            <radius>0.4</radius>
                            <length>0.2</length>
                        </cylinder>
                    </geometry>
                </collision>
            </link> 
            <frame name="caster_frame" attached_to='chassis'>
                <pose>0.8 0 -0.2 0 0 0</pose>
            </frame>
            <link name='caster'>
                <pose relative_to='caster_frame'/>
                <inertial>
                    <mass>1</mass>
                    <inertia>
                        <ixx>0.016</ixx>
                        <ixy>0</ixy>
                        <ixz>0</ixz>
                        <iyy>0.016</iyy>
                        <iyz>0</iyz>
                        <izz>0.016</izz>
                    </inertia>
                </inertial>
                <visual name='visual'>
                    <geometry>
                        <sphere>
                            <radius>0.2</radius>
                        </sphere>
                    </geometry>
                    <material>
                        <ambient>0.0 1 0.0 1</ambient>
                        <diffuse>0.0 1 0.0 1</diffuse>
                        <specular>0.0 1 0.0 1</specular>
                    </material>
                </visual>
                <collision name='collision'>
                    <geometry>
                        <sphere>
                            <radius>0.2</radius>
                        </sphere>
                    </geometry>
                </collision>
            </link>
            <joint name='left_wheel_joint' type='revolute'>
                <pose relative_to='left_wheel'/>
                <parent>chassis</parent>
                <child>left_wheel</child>   
                    <axis>
                    <xyz expressed_in='__model__'>0 1 0</xyz> <!--can be defined as any frame or even arbitrary frames-->
                    <limit>
                        <lower>-1.79769e+308</lower>    <!--negative infinity-->
                        <upper>1.79769e+308</upper>     <!--positive infinity-->
                    </limit>
                </axis>
            </joint>
            <joint name='right_wheel_joint' type='revolute'>
                <pose relative_to='right_wheel'/>
                <parent>chassis</parent>
                <child>right_wheel</child>
                <axis>
                    <xyz expressed_in='__model__'>0 1 0</xyz>
                    <limit>
                        <lower>-1.79769e+308</lower>    <!--negative infinity-->
                        <upper>1.79769e+308</upper>     <!--positive infinity-->
                    </limit>
                </axis>
            </joint>
            <joint name='caster_wheel' type='ball'>
                <parent>chassis</parent>
                <child>caster</child>
            </joint>
        </model>
    </world>
</sdf>

 - 全部都放在一个文件里后运行测试: 

ign gazebo building_robot.sdf

 - 效果: 

请输入图片描述

  • 我们建造了我们的第一个机器人。
  • 您可以在此处了解有关 SDFormat 标签的更多详细信息。

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ignition入门教程