不同于 RVIZ 只需要向对应的话题接口发送数据就可以让智能机器人运动。在 Gazebo 中由于是模拟真实的机器人运动,因此需要在智能机器人中配置完善的硬件控制系统,并且该硬件控制系统是高度抽象的,可以为不同的具体硬件提供统一的应用接口,从而使在 Gazebo 中模拟的硬件数据与使用真实硬件获取的硬件数据完全相同,然后再通过控制系统向 ROS 系统反馈这些数据,该工作由ROS 系统的控制中间件 ros_control18来完成,而 gazebo_ros_control 则是该中间件在适配 Gazebo 系统后的派生组件。
————————
ros_control 的主要工作就是将智能机器人执行机构中采集的真实数值与一组特定的目标输入数值合并为一个输入数据,然后把该数据通过如 PID 等通用循环反馈算法来得到最终输出到执行机构
上的力、速度、位置等。然而,对于智能机器人中关节位置和力矩无法进行一对一的映射的物理机制,ros_control 使用传动系统来对这些复杂场景进行解算。ros_control 中主要包含了三个组件,分别是控制器(Controller)、硬件抽象接口(Hardware Interfaces)和传动系统(Transmissions)。
————————
1、控制器:控制器主要是对关节进行控制,并从硬件接口中读取关节的状态数据,如编码器值等,然后把关节状态数据和目标数据输入至如 PID 控制算法中,从而得到相应的控制指令。
目前常用的控制器主要有五种,分别是:
(1)关节状态控制器(joint_state_controller):用于发布所有使用 JointStateInterface 硬件接口的关节数据。
(2)位置控制器(position_controllers):用于接收位置数据的输入,然后通过 PID 控制算法转化为输出的位置数据,该输出数据再通过相应的硬件接口向真实的硬件发送,从而
达到控制硬件位置的目的。位置控制器中主要有两个子控制器,分别是关节位置控制器(joint_position_controller)和关节组位置控制器(joint_group_position_controller)。
(3)速度控制器(velocity_controllers):用于接收速度数据的输入,然后通过 PID 控制算法
转化为输出的速度数据,该输出数据再通过相应的硬件接口向真实的硬件发送,从而
达到控制硬件速度的目的。速度控制器中主要有三个子控制器,分别是关节速度控制器(joint_velocity_controller)、关节组速度控制器(joint_group_velocity_controller)和关节位置控制器(joint_position_controller)。
(4)力控制器(effort_controllers):用于接收力控数据的输入,然后通过 PID 控制算法转化为输出的力控数据,该输出数据再通过相应的硬件接口向真实的硬件发送,从而达到控制
硬件力矩的目的。速度控制器中主要有五个子控制器,分别是关节力量控制器(joint_-effort_controller)、关节组力量控制器(joint_group_effort_controller)、关节位置控制器
(joint_position_controller)、关节组位置控制器(joint_group_position_controller)和关节速度控制器(joint_velocity_controller)。
(5)轨迹控制器(joint_trajectory_controllers):用于在一组关节上执行关节空间轨迹的控制
器。轨迹控制器中主要有五个子控制器,分别是关节力量控制器(joint_effort_controller)、
关节位置控制器(joint_position_controller)、关节速度控制器(joint_velocity_controller)、
关节位置速度控制器(position_velocity_controller)和关节位置速度加速度控制器(position_velocity_acceleration_controller)。
2、硬件抽象接口:硬件接口主要是对执行机构的软件抽象,通过与控制器联合使用来实现对
硬件系统的指令发送和数据采集。目前常用的硬件抽象接口主要有三种,分别是关节力量接
口(EffortJointInterface)、关节速度接口(VelocityJointInterface)和关节位置接口(PositionJointInterface)。
3、传动系统:传动系统主要用于实现执行机构与关节之间的双向映射,如力、速度和位置等。
在 Gazebo 中每个可运动的关节都需要配置相应的传送系统,目前常用的传动系统主要有三种,分别是轴传动系统(SimpleTransmission)、差速传动系统(DifferentialTransmission)和四连杆传动系统(FourBarLinkageTransmission),如图7-33所示。
虽然目前的 URDF 文件已经具备在 G添加如传动系统、通信控制插件等,因此目前的 URDF 模型还无法在 Gazebo 仿真环境中运动。从总体上来说,URDF 在 Gazebo 中仿真可以分为两个步骤,分别是添加传动系统和添加功能插件。
第一步:添加传动系统。
在 Gazebo 仿真系统中,机器人中的每个可运动的关节都需要在 URDF 模型文件中配置相应的传动系统,并且该系统是执行机构和运动关节之间的纽带。在代码7.18所示的模型中有两个控制轮需要进行关节控制,因此就需要添加两个与之对应的传动系统,如代码7.26所示。
代码7.18
sample_sai_robot.urdf
<?xml version="1.0"?>
<robot name="sai_robot">
<link name="base_link" />
<link name="robot_body_layer">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<cylinder radius="0.25" length="0.01"/>
</geometry >
<material name="yellow">
<color rgba="1 0.4 0.0 1.0"/>
</material >
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<cylinder radius="0.25" length="0.01"/>
</geometry >
</collision >
<inertial >
<mass value="0.5"/>
<inertia ixx="0.00782" ixy="0" ixz="0"
iyy="0.00782" iyz="0" izz="0.01563"/>
</inertial >
</link >
<gazebo reference ="robot_body_layer">
<material >Gazebo/Orange </material >
</gazebo >
<joint name="dummy_joint" type="fixed">
<origin xyz="0.0 0.0 0.095" rpy="0.0 0.0 0.0"/>
<parent link="base_link"/>
<child link="robot_body_layer"/>
</joint >
<link name="left_motor_link">
<visual >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.02" length="0.08"/>
</geometry >
<material name="gray">
<color rgba="0.75 0.75 0.75 1.0"/>
</material >
</visual >
<collision>
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.02" length="0.08"/>
</geometry >
</collision >
<inertial >
<mass value="0.1"/>
<inertia ixx="0.00006" ixy="0" ixz="0"
iyy="0.00006" iyz="0" izz="0.00002"/>
</inertial >
</link >
<gazebo reference ="left_motor_link">
<material >Gazebo/Grey</material >
</gazebo >
<link name="right_motor_link">
<visual >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.02" length="0.08"/>
</geometry >
<material name="gray" />
</visual >
<collision >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.02" length="0.08"/>
</geometry >
</collision >
<inertial >
<mass value="0.1"/>
<inertia ixx="0.00006" ixy="0" ixz="0"
iyy="0.00006" iyz="0" izz="0.00002"/>
</inertial >
</link >
<gazebo reference ="right_motor_link">
<material >Gazebo/Grey </material >
</gazebo >
<joint name="left_motor_join" type="fixed">
<origin xyz="0.125 0.22 -0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="left_motor_link"/>
</joint >
<joint name="right_motor_join" type="fixed">
<origin xyz="0.125 -0.22 -0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="right_motor_link"/>
</joint >
<link name="left_wheel_link">
<visual >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.07" length="0.04"/>
</geometry >
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material >
</visual >
<collision >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.07" length="0.04"/>
</geometry >
</collision >
<inertial >
<mass value="0.1"/>
<inertia ixx="0.00014" ixy="0" ixz="0"
iyy="0.00014" iyz="0" izz="0.00025"/>
</inertial >
</link >
<gazebo reference ="left_wheel_link">
<material >Gazebo/Black</material >
</gazebo >
<link name="right_wheel_link">
<visual >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.07" length="0.04"/>
</geometry >
<material name="black" />
</visual >
<collision >
<origin xyz="0.0 0 0" rpy="1.57 0.0 0.0"/>
<geometry >
<cylinder radius="0.07" length="0.04"/>
</geometry >
</collision >
<inertial >
<mass value="0.1"/>
<inertia ixx="0.00014" ixy="0" ixz="0"
iyy="0.00014" iyz="0" izz="0.00025"/>
</inertial >
</link >
<gazebo reference ="right_wheel_link">
<material >Gazebo/Black </material >
</gazebo >
<joint name="left_wheel_joint" type="continuous">
<origin xyz="0.0 0.06 0.0" rpy="0.0 0.0 0.0"/>
<parent link="left_motor_link"/>
<child link="left_wheel_link"/>
<axis xyz="0.0 1.0 0.0"/>
</joint >
<joint name="right_wheel_joint" type="continuous">
<origin xyz="0.0 -0.06 0.0" rpy="0.0 0.0 0.0"/>
<parent link="right_motor_link"/>
<child link="right_wheel_link"/>
<axis xyz="0.0 1.0 0.0"/>
</joint >
<link name="caster_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<sphere radius="0.045"/>
</geometry >
<material name="black" />
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<sphere radius="0.045"/>
</geometry >
</collision >
<inertial >
<mass value="0.1"/>
<inertia ixx="0.00008" ixy="0" ixz="0"
iyy="0.00008" iyz="0" izz="0.00008"/>
</inertial >
</link >
<gazebo reference ="caster_link">
<material >Gazebo/Black </material >
<mu1 value="0.0"/>
<mu2 value="0.0"/>
<kp value="1000000.0" />
<kd value="10.0" />
</gazebo >
<joint name="caster_joint" type="fixed">
<origin xyz=" -0.125 0.0 -0.05" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="caster_link"/>
</joint >
<link name="imu_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.1 0.1 0.01"/>
</geometry >
<material name="green">
<color rgba="0.42 0.54 0.45 1.0"/>
</material >
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.1 0.1 0.01"/>
</geometry >
</collision >
<inertial >
<mass value="0.05"/>
<inertia ixx="0.00004" ixy="0" ixz="0"
iyy="0.00008" iyz="0" izz="0.00004"/>
</inertial >
</link >
<gazebo reference ="imu_link">
<material >Gazebo/Green </material >
</gazebo >
<joint name="imu_joint" type="fixed">
<origin xyz=" -0.125 0.0 0.01" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="imu_link"/>
</joint >
<link name="laser_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<cylinder radius="0.05" length="0.05"/>
</geometry >
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material >
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<cylinder radius="0.05" length="0.05"/>
</geometry >
</collision >
<inertial >
<mass value="0.2"/>
<inertia ixx="0.00017" ixy="0" ixz="0"
iyy="0.00017" iyz="0" izz="0.00025"/>
</inertial >
</link >
<gazebo reference ="laser_link">
<material >Gazebo/SkyBlue </material >
</gazebo >
<joint name="laser_joint" type="fixed">
<origin xyz="0.0 0.0 0.03" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="laser_link"/>
</joint >
<link name="camera_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.03 0.15 0.02"/>
</geometry >
<material name="gold">
<color rgba="0.9 0.9 0.1 1.0"/>
</material >
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.03 0.15 0.02"/>
</geometry >
</collision >
<inertial >
<mass value="0.2"/>
<inertia ixx="0.00002" ixy="0" ixz="0"
iyy="0.00039" iyz="0" izz="0.00038"/>
</inertial >
</link >
<gazebo reference ="camera_link">
<material >Gazebo/Gold </material >
</gazebo >
<joint name="camera_joint" type="fixed">
<origin xyz="0.18 0.0 0.015" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="camera_link"/>
</joint >
<link name="us_back_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.01 0.02 0.04"/>
</geometry >
<material name="red">
<color rgba="0.71 0.54 0.75 1.0"/>
</material >
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.01 0.02 0.04"/>
</geometry >
</collision >
<inertial >
<mass value="0.05"/>
<inertia ixx="0.000007" ixy="0" ixz="0"
iyy="0.000002" iyz="0" izz="0.000008"/>
</inertial >
</link >
<gazebo reference ="us_back_link">
<material >Gazebo/Turquoise </material >
</gazebo >
<link name="us_front_left_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.01 0.02 0.04"/>
</geometry >
<material name="red" />
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.01 0.02 0.04"/>
</geometry >
<material name="red" />
</collision >
<inertial >
<mass value="0.05"/>
<inertia ixx="0.000007" ixy="0" ixz="0"
iyy="0.000002" iyz="0" izz="0.000008"/>
</inertial >
</link >
<gazebo reference ="us_front_left_link">
<material >Gazebo/ Turquoise </material >
</gazebo >
<link name="us_front_right_link">
<visual >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.01 0.02 0.04"/>
</geometry >
<material name="red" />
</visual >
<collision >
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<geometry >
<box size="0.01 0.02 0.04"/>
</geometry >
<material name="red" />
</collision >
<inertial >
<mass value="0.05"/>
<inertia ixx="0.000007" ixy="0" ixz="0"
iyy="0.000002" iyz="0" izz="0.000008"/>
</inertial >
</link >
<gazebo reference ="us_front_right_link">
<material >Gazebo/Turquoise </material >
</gazebo >
<joint name="us_back_joint" type="fixed">
<origin xyz=" -0.2 0.0 0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="us_back_link"/>
</joint >
<joint name="us_front_left_joint" type="fixed">
<origin xyz="0.18 0.12 0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="us_front_left_link"/>
</joint >
<joint name="us_front_right_joint" type="fixed">
<origin xyz="0.18 -0.12 0.025" rpy="0.0 0.0 0.0"/>
<parent link="robot_body_layer"/>
<child link="us_front_right_link"/>
</joint >
</robot >
Code 7.26: URDF 传动系统配置
<transmission name="base_l_wheel_trans">
<type>transmission_interface/SimpleTransmission</type >
<joint name="base_l_wheel_joint">
<hardwareInterface>VelocityJointInterface</hardwareInterface >
</joint>
<actuator name="left_motor_link">
<mechanicalReduction >1</mechanicalReduction>
<hardwareInterface>VelocityJointInterface</hardwareInterface >
</actuator>
</transmission>
<transmission name="base_r_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_r_wheel_joint">
<hardwareInterface>VelocityJointInterface</hardwareInterface >
</joint>
<actuator name="right_motor_link">
<mechanicalReduction >1</mechanicalReduction >
<hardwareInterface>VelocityJointInterface</hardwareInterface >
</actuator>
</transmission>
第 1 行:设置传统系统的名称,在整个 URDF 文件中具有唯一性。
第 2 行:设置传统系统的类型,由于本书中的模型是一个双轮差速驱动的机器人,因此只需要使用简单的轴传动系统就可以完成。
第 3 行:用于把传统系统与特定关节进行绑定,该关节名称需与 URDF 中定义的关节名称一致。
第 4 行:用于定义特定关节的硬件接口,由于是控制轮子速度,因此只需要使用 VelocityJointInterface 即可。
第 6 行:用于绑定特定关节对应的执行机构,在本例中为左右电机组件。
第 7 行:用于设置执行机构和关节之间的减速比。
第 8 行:用于定义该执行机构的硬件接口,由于是控制电机转速速度,因此也只需要使用 VelocityJointInterface 即可。
第二步:添加功能插件
在 URDF 文件中添加传动系统后,智能机器人依然无法运动,此时传动系统只是与 ros_control进行关联,并没有与 Gazebo 进行数据的通信,因此还需要在 URDF 中添加 Gazebo 插件来解决 ROS与 Gazebo 之间消息通信、电机控制等。在 URDF 文件中添加 Gazebo 插件的格式如代码7.27所示。
Code 7.27: Gazebo 插件添加的格式
<gazebo reference ="对 应 的Link或Joint名 称">
<plugin name="唯 一 的 插 件 名 称" filename="libgazebo_ros_XXX.so">
插 件 参 数 列 表...
</plugin >
</gazebo>
在上述代码中,如果 标签中添加了 reference 属性,那么就表示该插件只作用于某个Link 或者 Joint,如果没有添加 reference 属性,那么就表示该插件作用于整个 URDF 文件。而 < plugin>
标签中的 name 属性和 filename 属性分别表示该插件的别名和插件文件名,这里有四点需要特别说明。
1、插件的别名必须在整个 URDF 文件中具有唯一性。
2、插件的文件名需要在/opt/ros/melodic/lib 目录下存在,否则会导入仿真失败。
3、在 ROS 的 Wiki 中并没有提供不同插件的使用说明,但是开放了插件源代码,因此对于插件
的学习和使用主要以阅读源代码的方式进行19。
4、一个 URDF 文件可以有多个 < gazebo> 标签,表示载入多个 Gazebo 插件。
在本节中,使用差速控制的插件 libgazebo_ros_diff_drive.so20来实现 ROS 与 Gazebo 模型之间的
数据交换。该插件的功能与 Arbotix 类似,区别在于可以通过 ROS 系统的方式在 Gazebo 中进行差速运动控制的仿真,并且把在 Gazebo 中机器人真实的位置和速度信息转化为 ROS 系统能够识别数据进行反馈,根据这些反馈信息再结合运动学模型就可计算出当前机器人的位姿(里程计),如图7-34所示。这里需要注意的是,轮子的目标速度在大多情况下并不等于实际速度,例如当轮子卡住时,轮子的速度为 0,但目标速度不为 0,因此运动学模型和动力学模型的目的就是使机器人的运动能够尽量与所设置的目标值相同。
Code 7.28: Gazebo 差速控制插件的使用
<gazebo >
<plugin name="differential_drive_controller"
filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel >Debug</rosDebugLevel >
# 机 器 人 的 命 名 空 间, 插 件 所 有 数 据 的 发 布、 订 阅 都 在 该 命 名 空 间 下6 <robotNamespace >/</ robotNamespace >
<alwaysOn >true </alwaysOn >
# 里 程 计 的 父 坐 标 系
<odometrySource >world </odometrySource >
#是 否 广 播TF树
<broadcastTF >1</broadcastTF >
#是 否 发 布TF树
<publishTf >1</publishTf >
# 是 否 发 布 轮 子 的TF树
<publishWheelTF >true </publishWheelTF >
# 是 否 发 布 里 程 计 的TF树
<publishOdomTF >true </publishOdomTF >
# 是 否 发 布 轮 子 的 关 节 状 态
<publishWheelJointState >true </publishWheelJointState >
<updateRate >100.0 </updateRate >
<legacyMode >true </legacyMode >
# 左 轮 转 动 的Joint关 节
<leftJoint >base_l_wheel_joint </leftJoint >
# 右 轮 转 动 的Joint关 节
<rightJoint >base_r_wheel_joint </rightJoint >
# 计 算 差 速 时 需 要 用 到 的 轮 距
<wheelSeparation >0.52 </wheelSeparation >
# 计 算 差 速 时 需 要 用 到 的 轮 子 直 径
<wheelDiameter >0.14 </wheelDiameter >
# 轮 子 的 扭 矩
<wheelTorque >30</wheelTorque >
# 轮 子 的 加 速 度
<wheelAcceleration >1.8 </wheelAcceleration >
# 控 制 器 订 阅 的 速 度 控 制 指 令 话 题
<commandTopic >cmd_vel </commandTopic >
# 里 程 计 数 据 的 参 考 坐 标 系
<odometryFrame >odom </odometryFrame >
# 里 程 计 数 据 的 话 题
<odometryTopic >odom </odometryTopic >
# 机 器 人 根 坐 标 系
<robotBaseFrame >base_footprint </robotBaseFrame >
</plugin >
</gazebo >
修改完成 URDF 后,重新执行如代码7.20所示的 Launch 文件,这时再执行如代码7.29所示的运动指令,就可以在 Gazebo 中看到智能机器人呈现圆周运动,如图7-35所示。
代码7.20 simple_model_gazebo.launch
<launch >
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- 指 定 模 型 的URDF文 件 地 址 -->
<arg name="model"
default="$(find begin1)/urdf/simple_sai_robot.urdf"/>
<!-- RVIZ配 置 文 件 的 存 放 地 址 -->
<arg name="rvizconfig"
default="$(find begin1)/rviz/simple_model.rviz" />
<!-- 模 型 描 述 的 参 数 -->
<param name="robot_description"
command="$(find xacro)/xacro $(arg model)" />
<!-- 载 入 空 的 物 理 世 界 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include >
<node if="$(arg gui)" name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node unless="$(arg gui)" name="joint_state_publisher"
pkg="joint_state_publisher"
type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher"
type="robot_state_publisher" />
<!-- 创 建 一 个 模 型 对 象 -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"
args="-x 0.0 -y 0.0 -z 0.0 -unpause -urdf
-model sai_robot -param robot_description"
respawn="false" output="screen" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)"
required="true" />
</launch >
Code 7.29: Gazebo 的运动指令
rostopic pub /cmd_vel geometry_msgs /Twist -r 10 -- '[0.4 , 0.0, 0.0]' '[0.0 , 0.0,
-1]'