260404
继我们上次让我们世界中的小车动起来后,我们接下来可以继续对我们的小车进行其他的一些测试。
比如,原地转圈:
gz topic -t /model/kibot_one_base/cmd_vel \
-m gz.msgs.Twist \
-p "linear: {x: 0.0}, angular: {z: 0.8}"

再比如,转弯:
gz topic -t /model/kibot_one_base/cmd_vel \
-m gz.msgs.Twist \
-p "linear: {x: 0.3}, angular: {z: 0.5}"

可以看到我们的小车行为都基本上是正常的。
你可能会发现我们的 gif 有点...糊——
毕竟用的是我自己在腾讯云的 S3 图床...还是要考虑成本在里面的,就得压缩一下体积了。
嘛,总的来说,我们的小车已经可以正常根据我们的命令跑起来了!
以上。
接下来我们就要编写我们的 ROS2 接口来和我们的 Gazebo 进行连接了。
由于我们之前没有安装 ros_gz_bridge ,因此我们要先安装这个东西。
sudo apt update
sudo apt install ros-jazzy-ros-gz
安装好后,也不能直接就进行连接的,需要有一个桥接节点才行。
不过也不复杂,其实写一个 yaml 文件作为桥接配置就可以了。
我们可以创建 src/kibot_one_sim/config/ros_gz_bridge.yaml 并写入下面的内容:
- ros_topic_name: "/cmd_vel"
gz_topic_name: "/model/kibot_one_base/cmd_vel"
ros_type_name: "geometry_msgs/msg/Twist"
gz_type_name: "gz.msgs.Twist"
direction: ROS_TO_GZ
- ros_topic_name: "/odom"
gz_topic_name: "/model/kibot_one_base/odometry"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS
- ros_topic_name: "/tf"
gz_topic_name: "/model/kibot_one_base/tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS
这里就可以定义在 ros, gz 中的话题名称和类型名称,以及桥接的方向。
然后创建 src/kibot_one_sim/launch/sim_with_bridge.launch.py,写入下面的内容:
from pathlib import Path
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from ros_gz_bridge.actions import RosGzBridge
def generate_launch_description() -> LaunchDescription:
pkg_share = Path(get_package_share_directory('kibot_one_sim'))
default_world = pkg_share / 'worlds' / 'kibot_one.world.sdf'
gazebo_launch = pkg_share / 'launch' / 'gazebo.launch.py'
bridge_config = pkg_share / 'config' / 'ros_gz_bridge.yaml'
world_arg = DeclareLaunchArgument(
'world',
default_value=str(default_world),
description='Gazebo 世界文件的绝对路径。'
)
start_gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(str(gazebo_launch)),
launch_arguments={
'world': LaunchConfiguration('world'),
}.items()
)
start_bridge = RosGzBridge(
bridge_name='kibot_one_bridge',
config_file=str(bridge_config)
)
return LaunchDescription([
world_arg,
start_gazebo,
start_bridge,
])
你可能会注意到,我们虽然引入了我们的 gazebo.launch.py 作为 gazebo 启动的文件,但是我们依旧定义了 default_world ,这是为了我们的这个启动文件更具有灵活性来方便进行修改一些经常修改的配置系项,而gazebo.launch.py 中的start_gazebo 之类的则属于通常都不会发生变化的配置项,因此就不需要额外进行定义。
然后在我们的 CMakeLists.txt中的 install 处加入我们的 config:
install(DIRECTORY models worlds launch config
DESTINATION share/${PROJECT_NAME}
)
在完成了构建后,我们就可以通过下面的命令来拉起我们新的启动文件:
ros2 launch kibot_one_sim sim_with_bridge.launch.py
然后现在就可以通过 ros2 的 cli 来查看我们可用的话题之类的了:
(.venv) jese--ki@KiBall:~/Projects/dev/KiBots/KiBotOne$ ros2 topic list
/cmd_vel
/odom
/parameter_events
/rosout
/tf
就这样,我们就完成了 Gazebo 和 ROS2 的桥接。
我们发送命令看看我们的 Gazebo 是否会正常的遵守这些命令。
我们先将我们的视角调为垂直于地面:
gz service -s /gui/move_to/pose \
--reqtype gz.msgs.GUICamera \
--reptype gz.msgs.Boolean \
--timeout 2000 \
--req 'pose: {position: {x: 0.0, y: 0.0, z: 5.0}, orientation: {x: 0.0, y: 0.7071, z: 0.0, w: 0.7071}}'
前进:
ros2 topic pub -r 10 /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.3, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"

原地旋转:
ros2 topic pub -r 10 /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.8}}"

小车原地旋转 1min。
目前来说,我们的 Gazebo 和我们的 ROS2 就已经完成连接了。
以上。