260403
目前我们完成了小车和世界的 sdf 文件,不过如果每次我们都要通过 CLI 命令来拉起这两个文件就显得有点过于麻烦了,因此我们可以选择编写一个启动文件来通过下面的命令一件拉起:
ros2 launch kibot_one_sim gazebo.launch.py
我们可以看看我们编写的启动文件:
from pathlib import Path
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, SetEnvironmentVariable
from launch.substitutions import LaunchConfiguration
def generate_launch_description():
pkg_share = Path(get_package_share_directory('kibot_one_sim'))
default_world = pkg_share / 'worlds' / 'kibot_one.world.sdf'
models_path = pkg_share / 'models'
existing_resource_path = os.environ.get('GZ_SIM_RESOURCE_PATH', '')
resource_path = (
f'{existing_resource_path}:{models_path}' if existing_resource_path else str(models_path)
)
world_arg = DeclareLaunchArgument(
'world',
default_value=str(default_world),
description='Absolute path to the Gazebo world file',
)
gz_resource_path = SetEnvironmentVariable(
name='GZ_SIM_RESOURCE_PATH',
value=resource_path,
)
start_gazebo = ExecuteProcess(
cmd=['gz', 'sim', '-v', '4', LaunchConfiguration('world')],
output='screen',
)
return LaunchDescription([
world_arg,
gz_resource_path,
start_gazebo,
])
我们可以解析一下我们的这个文件代码。
我们直接讲解我们编写的这个 generate_launch_description 函数,这个函数名称是固定为 generate_launch_description 的,即——ROS 2 launch Python 文件里的标准入口函数。
ROS 2 的 launch 系统在加载这个文件时,会去找这个函数,并调用它。
然后我们往下,可以看到我们调用了 get_package_share_directory 这个方法,由于我们需要找到这个模块的 share 目录,而手动拼接目录又往往很麻烦,因此我们可以直接使用这个 get_package_share_directory 函数来获取到对应的 share 目录,当然,这个得我们构建后使用 source install/setup.sh 后才行。
后面我们就可以使用相对路径来找到 kibot_one.world.sdf 和 models 文件了。
resource_path 除了拼接以外,我们的 GZ_SIM_RESOURCE_PATH 往往也代表着可能有环境变量级别的资源路径,我们可以以该环境变量为更高的优先级。
下面就是实际启动时候的参数了,分别是:
- world_arg
- 即 world 参数,用于指定启动 Gazebo 时候使用什么世界文件。
- gz_resource_path
- GZ_SIM_RESOURCE_PATH 环境变量,这里我们手动进行设置。
- start_gazebo
- 正式启动 Gazebo 进程,开始模拟。
在 CMakeLists.txt中 install 目录添加下面的内容:
install(DIRECTORY models worlds launch
DESTINATION share/${PROJECT_NAME}
)
除此之外,我们还需要在 package.xml 中添加下面两个 exec_depend :
- ament_index_python
- launch
最后,我们进行构建后,就可以使用下面的命令来拉起我们的世界了:
ros2 launch kibot_one_sim gazebo.launch.py

以上。
接下来就是给我们的小车增加动力了。
由于我们最终的目的是履带小车,因此最后还是选择四轮差速这个方案。
即,我们左侧的两个轮子作为左侧驱动组,右侧的两个轮子作为右侧驱动组。
这样我们未来切换到履带的时候,也可以保留为——左履带/右履带。
在控制的接口侧面也几乎不需要什么改变了。
Gazebo 内部自带这样的插件,名叫 DiffDrive ,因此我们直接将该插件放入到我们的模型内就可以了:
<plugin
filename="gz-sim-diff-drive-system"
name="gz::sim::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<wheel_separation>0.48</wheel_separation>
<wheel_radius>0.08</wheel_radius>
<topic>/model/kibot_one_base/cmd_vel</topic>
<odom_topic>/model/kibot_one_base/odometry</odom_topic>
<tf_topic>/model/kibot_one_base/tf</tf_topic>
<frame_id>odom</frame_id>
<child_frame_id>chassis</child_frame_id>
<odom_publish_frequency>50</odom_publish_frequency>
<max_linear_velocity>0.8</max_linear_velocity>
<max_angular_velocity>1.5</max_angular_velocity>
<max_linear_acceleration>0.8</max_linear_acceleration>
<max_angular_acceleration>1.5</max_angular_acceleration>
</plugin>
- <left_joint> / <right_joint> 作用是把左右两侧的轮子告诉差速插件。
- wheel_separation:是左右的轮的中心距,我们当前模型的左右轮在 y = +0.24 和 y = -0.24,所以先取 0.48。
- wheel_radius:轮子的半径,相当于是圆柱的厚度,我们模型中是 0.08,因此这里也是 0.08。
- topic:订阅话题的名称,用于我们控制小车。
- odom_topic:Gazebo 发布里程的话题。
- tf_topic:Gazebo 发布位姿变化的话题。
- <frame_id> / <child_frame_id> 先这样用就够了,这两个是计算我们相对里程的参数,设置为 odom相当于是绑定在坐标原点。
- odom_publish_frequency:我们发布里程变化话题的频率。
- 下面的一系列 max_*都是限制速度之类的,避免一开始就跑的太猛。
重新构建并使用我们上面的启动脚本进行启动后,便可以开始调用我们的话题了。
我们先看看我们可用的 topic:
(.venv) jese--ki@KiBall:~/Projects/dev/KiBots/KiBotOne$ gz topic -l
/clock
/gazebo/resource_paths
/gui/camera/pose
/gui/currently_tracked
/gui/track
/model/kibot_one_base/odometry
/model/kibot_one_base/tf
/stats
/world/kibot_one_world/clock
/world/kibot_one_world/dynamic_pose/info
/world/kibot_one_world/pose/info
/world/kibot_one_world/scene/deletion
/world/kibot_one_world/scene/info
/world/kibot_one_world/state
/world/kibot_one_world/stats
/model/kibot_one_base/cmd_vel
/model/kibot_one_base/enable
/world/kibot_one_world/light_config
/world/kibot_one_world/material_color
可以看到这里面已经有了我们的 cmd_vel, odometry, tf 等话题。
我们测试一下直行看看:
gz topic -t /model/kibot_one_base/cmd_vel \
-m gz.msgs.Twist \
-p "linear: {x: 0.4}, angular: {z: 0.0}"

嗯...好吧...动得十分的诡异...
发现是向左下移动,而且轮子的圆柱是绕 z 轴旋转的,而非绕 y 轴旋转。
我们排查了一下,可能是 joint 的方向的问题。
因为我们的轮子都在 pose 处通过调整 roll 为 1.5708 来调整了 90 度,因此 joint 的相对坐标也调整了 90 度,这就导致实际旋转了 180 度,即最终像是以 z 轴进行旋转的。
我们通过调整
我们重新构建后重新运行看看:

可以看到已经可以正常运行了。