Gazebo 仿真环境系列教程(三):让机器人动起来

发布于:2025-06-23 ⋅ 阅读:(15) ⋅ 点赞:(0)


在之前的教程中,我们已经学习了如何在 Gazebo 仿真环境中创建自己的机器人模型。然而,一个静止的机器人并不能满足我们的需求。本篇教程将详细介绍如何让机器人在 Gazebo 仿真环境中动起来,包括使用插件、话题和消息,以及通过键盘控制机器人移动。

一、插件的概念与使用

1. 什么是插件

在 Gazebo 仿真环境中,插件(Plugin)是一段编译为共享库的代码,它可以插入到仿真中,用于控制仿真世界的各个方面,如世界、模型等。插件是 Gazebo 中非常重要的组成部分,通过插件,我们可以实现对机器人模型的控制。

2. Diff_drive 插件

为了让我们的机器人能够移动,我们将使用 diff_drive 插件。该插件主要用于控制差动驱动的机器人。下面我们将详细介绍如何在机器人模型中设置该插件。

首先,打开我们之前创建的机器人模型文件 building_robot.sdf,在 <vehicle_blue> 模型标签内添加以下代码:

<plugin
    filename="gz-sim-diff-drive-system"
    name="gz::sim::systems::DiffDrive">
    <left_joint>left_wheel_joint</left_joint>
    <right_joint>right_wheel_joint</right_joint>
    <wheel_separation>1.2</wheel_separation>
    <wheel_radius>0.4</wheel_radius>
    <odom_publish_frequency>1</odom_publish_frequency>
    <topic>cmd_vel</topic>
</plugin>

3. 插件参数解释

  • <plugin> 标签:包含两个属性,filename 指定插件的库文件名,name 指定插件的名称。
  • <left_joint><right_joint>:定义连接左轮和右轮与机器人主体的关节名称,分别为 left_wheel_jointright_wheel_joint
  • <wheel_separation>:定义两个轮子之间的距离,本例中为 1.2 米。
  • <wheel_radius>:定义轮子的半径,本例中为 0.4 米。
  • <odom_publish_frequency>:设置 odometry(里程计)数据的发布频率,本例中为 1 Hz。
  • <topic>:定义输入话题名称,本例中为 cmd_vel

二、话题和消息

1. 什么是话题和消息

在 Gazebo 中,话题(Topic)是用于对一组特定的消息或服务进行命名的。我们的机器人模型将订阅(监听)在 cmd_vel 话题上发送的消息。

2. 发送消息控制机器人移动

现在,我们的机器人模型已经准备好接收控制命令。我们可以通过在终端中发送消息来控制机器人移动。

首先,启动机器人世界:

gz sim building_robot.sdf

在另一个终端中,发送消息给机器人:

gz topic -t "/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 0.5}, angular: {z: 0.05}"

该命令的含义如下:

  • -t 指定要发布到的话题名称 /cmd_vel
  • -m 指定消息类型 gz.msgs.Twist,该类型包含两个部分:linear(线速度)和 angular(角速度)。
  • -p 指定消息的内容,本例中线速度 x: 0.5,角速度 z: 0.05

发送上述命令后,你应该可以看到机器人在仿真环境中移动。

三、通过键盘控制机器人移动

1. KeyPublisher 插件

除了通过终端发送消息,我们还可以使用键盘来控制机器人移动。为此,我们需要使用 KeyPublisher 插件。该插件是 gz-gui 的一部分,它可以读取键盘按键并将其发送到默认话题 /keyboard/keypress 上。

操作步骤如下:

  1. 在一个终端中启动机器人世界:

    gz sim building_robot.sdf
    
  2. 在 Gazebo 界面的右上角,点击插件下拉列表(垂直省略号),选择 Key Publisher

  3. 在另一个终端中运行以下命令,以查看 /keyboard/keypress 话题上的消息:

    gz topic -e -t /keyboard/keypress
    
  4. 在 Gazebo 窗口中按下不同的键,你应该可以在终端中看到相应的数据(数字)。

2. TriggeredPublisher 插件

接下来,我们需要将键盘按键映射为 Twist 类型的消息,并将其发布到 /cmd_vel 话题上。这可以通过 TriggeredPublisher 插件实现。

<world> 标签下添加以下代码:

<!-- 前进 -->
<plugin filename="gz-sim-triggered-publisher-system"
        name="gz::sim::systems::TriggeredPublisher">
    <input type="gz.msgs.Int32" topic="/keyboard/keypress">
        <match field="data">16777235</match>
    </input>
    <output type="gz.msgs.Twist" topic="/cmd_vel">
        linear: {x: 0.5}, angular: {z: 0.0}
    </output>
</plugin>

该代码的含义如下:

  • 该插件接受类型为 gz.msgs.Int32 的消息,话题为 /keyboard/keypress
  • 如果消息中的 data 字段值为 16777235(上箭头键),则在 /cmd_vel 话题上发布一个 Twist 消息,内容为 linear: {x: 0.5}, angular: {z: 0.0}

3. 使用箭头键控制机器人移动

我们可以通过类似的方式,为其他箭头键添加相应的 TriggeredPublisher 插件,以实现不同的移动控制。

例如,添加以下代码以实现后退功能:

 <!-- 后退 -->
<plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
    <input type="gz.msgs.Int32" topic="/keyboard/keypress">
        <match field="data">16777237</match>
    </input>
    <output type="gz.msgs.Twist" topic="/cmd_vel">
        linear: {x: -0.5}, angular: {z: 0.0}
    </output>
</plugin>
<!-- 左转 -->
<plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
    <input type="gz.msgs.Int32" topic="/keyboard/keypress">
        <match field="data">16777234</match>
    </input>
    <output type="gz.msgs.Twist" topic="/cmd_vel">
        linear: {x: 0.0}, angular: {z: 0.5}
    </output>
</plugin>
<!-- 右转 -->
<plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
    <input type="gz.msgs.Int32" topic="/keyboard/keypress">
        <match field="data">16777236</match>
    </input>
    <output type="gz.msgs.Twist" topic="/cmd_vel">
        linear: {x: 0.0}, angular: {z: -0.5}
    </output>
</plugin>

通过为每个箭头键添加相应的插件,我们可以实现对机器人的全面控制:

  • 左箭头键(16777234):linear: {x: 0.0}, angular: {z: 0.5}
  • 上箭头键(16777235):linear: {x: 0.5}, angular: {z: 0.0}
  • 右箭头键(16777236):linear: {x: 0.0}, angular: {z: -0.5}
  • 下箭头键(16777237):linear: {x: -0.5}, angular: {z: 0.0}

四、完整代码

building_robot.sdf

<?xml version="1.0" ?>
<sdf version="1.10">
    <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="gz-sim-physics-system" name="gz::sim::systems::Physics">
        </plugin>
        <plugin filename="gz-sim-user-commands-system" name="gz::sim::systems::UserCommands">
        </plugin>
        <plugin filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster">
        </plugin>

        <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>
                    <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>
                    <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>
                <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>
                    <limit>
                        <lower>-1.79769e+308</lower>
                        <upper>1.79769e+308</upper>
                    </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>
                        <upper>1.79769e+308</upper>
                    </limit>
                </axis>
            </joint>

            <joint name='caster_wheel' type='ball'>
                <parent>chassis</parent>
                <child>caster</child>
            </joint>
            <plugin filename="gz-sim-diff-drive-system" name="gz::sim::systems::DiffDrive">
                <left_joint>left_wheel_joint</left_joint>
                <right_joint>right_wheel_joint</right_joint>
                <wheel_separation>1.2</wheel_separation>
                <wheel_radius>0.4</wheel_radius>
                <odom_publish_frequency>1</odom_publish_frequency>
                <topic>cmd_vel</topic>
            </plugin>
        </model>
        <!-- TriggeredPublisher 插件 -->
        <!-- 前进 -->
        <plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
            <input type="gz.msgs.Int32" topic="/keyboard/keypress">
                <match field="data">16777235</match>
            </input>
            <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.5}, angular: {z: 0.0}
            </output>
        </plugin>
        <!-- 后退 -->
        <plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
            <input type="gz.msgs.Int32" topic="/keyboard/keypress">
                <match field="data">16777237</match>
            </input>
            <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: -0.5}, angular: {z: 0.0}
            </output>
        </plugin>
        <!-- 左转 -->
        <plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
            <input type="gz.msgs.Int32" topic="/keyboard/keypress">
                <match field="data">16777234</match>
            </input>
            <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.0}, angular: {z: 0.5}
            </output>
        </plugin>
        <!-- 右转 -->
        <plugin filename="gz-sim-triggered-publisher-system" name="gz::sim::systems::TriggeredPublisher">
            <input type="gz.msgs.Int32" topic="/keyboard/keypress">
                <match field="data">16777236</match>
            </input>
            <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.0}, angular: {z: -0.5}
            </output>
        </plugin>
    </world>
</sdf>

运行效果如下:

在这里插入图片描述

五、总结

通过本篇教程,我们学习了如何在 Gazebo 仿真环境中使用插件、话题和消息来控制机器人移动。我们使用了 diff_drive 插件来实现差动驱动控制,并通过 KeyPublisherTriggeredPublisher 插件实现了键盘控制。这些技能将为我们后续的机器人仿真开发提供坚实的基础。

参考文献

Gazebo Tutorials


网站公告

今日签到

点亮在社区的每一天
去签到