通过ros2_control控制机器人
1. Hardware Components(硬件组件)
实现了与物理硬件的通信,并在ros2_control框架中表示其抽象。需要使用pluginlib
库将组件导出为插件。Resource Manager(资源管理器)动态加载这些插件并管理它们的生命周期。
Hardware Components有三种基本类型:
System
复杂(多自由度)机器人,如工业机器人。执行器组件之间可以使用复杂的传动装置。该组件具有读写功能。
Sensor
用于感知其环境。传感器组件与关节或连杆相连。此组件类型仅具有读取功能。
Actuator
简单(1自由度)机器人,如电机、阀门等。执行机构的运动仅与一个关节有关。此组件类型具有读和写功能。
2. Hardware Description(硬件描述)的URDF
ros2_control使用机器人URDF文件中的<ros2_control>
标记来描述其组件。所选的结构可以在不做任何更改的情况下将多个xacro宏跟踪到一个宏中。以下示例为了一个位置控制机器人,其具有2自由度(RRBot)、外部1自由度力扭矩传感器和外部控制的1自由度平行夹具作为其末端执行器。
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rrbot_ros2_control" params="name prefix">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>ros2_control_demo_example_1/RRBotSystemPositionOnlyHardware</plugin>
<param name="example_param_hw_start_duration_sec">0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">100</param>
</hardware>
<joint name="${prefix}joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<joint name="${prefix}joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>
3. 通过ros2_control运行机器人
要运行ros2_control框架,请执行以下操作。
- 使用脚本创建robot bringup
ros2_control_setup-hardware-interface-package FILE_NAME [CLASS_NAME]
ros2_control_setup-hardware-interface-package
脚本接受robot硬件接口的文件名,也可以接受类名。文件名应使用标准ROS格式<my_cool_robot_hardware>
。将使用此名称添加.cpp和.hpp文件。如果没有设置类名,则通过文件名的大小写来自动生成。包名称从“package.xml”文件中获得。
- 创建YAML配置文件,用以配置控制器管理器和控制器的。(RRBot的配置示例)
controller_manager:
# 控制器管理器的参数
ros__parameters:
update_rate: 10 # 控制更新周期 Hz
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
forward_position_controller:
type: forward_command_controller/ForwardCommandController
joint_trajectory_position_controller:
type: joint_trajectory_controller/JointTrajectoryController
forward_position_controller:
ros__parameters:
joints:
- joint1 # 该控制器控制的关节列表
- joint2
interface_name: position # 控制接口名称
joint_trajectory_position_controller:
ros__parameters:
joints:
- joint1
- joint2
command_interfaces:
- position
state_interfaces:
- position # 控制器发布的状态接口
action_monitor_rate: 20.0 # 控制器监视动作状态的频率,单位为Hz
allow_partial_joints_goal: false # Defaults to false
open_loop_control: true
allow_integration_in_goal_trajectories: true
constraints:
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
goal_time: 0.0 # 目标达成时间,0表示立即开始,默认为0.0
- 使用
<ros2_control>
标签扩展机器人的URDF描述。建议使用宏文件(xacro),而不是纯URDF。(RRBot的URDF示例)
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rrbot_ros2_control" params="name prefix">
<!-- 创建一个ros2_control节点,指定控制系统名称, 类型为"system" -->
<ros2_control name="${name}" type="system">
<hardware>
<!-- 指定硬件接口插件,这里是"ros2_control_demo_example_1/RRBotSystemPositionOnlyHardware" -->
<plugin>ros2_control_demo_example_1/RRBotSystemPositionOnlyHardware</plugin>
<!-- 配置硬件接口的参数,这些参数将传递给硬件接口插件 -->
<param name="example_param_hw_start_duration_sec">0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">100</param>
</hardware>
<!-- 定义第一个关节 -->
<joint name="${prefix}joint1">
<!-- 定义命令接口,这里使用"position"命令接口 -->
<command_interface name="position">
<!-- 配置命令接口的参数,包括关节位置的最小和最大值 -->
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<!-- 定义状态接口,这里使用"position"状态接口 -->
<state_interface name="position"/>
</joint>
<!-- 定义第二个关节 -->
<joint name="${prefix}joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>
- 创建launch file以使用控制器管理器启动节点。可以使用默认的ros2_control节点(推荐),也可以在软件堆栈中集成控制器管理器。(RRBot的启动文件示例)
def generate_launch_description():
# 声明要使用的参数
declared_arguments = []
declared_arguments.append(
DeclareLaunchArgument(
"gui",
default_value="true",
description="Start RViz2 automatically with this launch file.",
)
)
# 初始化启动参数
gui = LaunchConfiguration("gui")
# 获取机器人的 URDF 描述,通过 xacro 处理
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[
FindPackageShare("ros2_control_demo_example_1"),
"urdf",
"rrbot.urdf.xacro",
]
),
]
)
robot_description = {"robot_description": robot_description_content}
# 设置机器人控制器的配置文件路径
robot_controllers = PathJoinSubstitution(
[
FindPackageShare("ros2_control_demo_example_1"),
"config",
"rrbot_controllers.yaml",
]
)
# 设置 RViz 的配置文件路径
rviz_config_file = PathJoinSubstitution(
[FindPackageShare("ros2_control_demo_description"), "rrbot/rviz", "rrbot.rviz"]
)
# 定义要启动的节点
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
output="both",
)
robot_state_pub_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
)
rviz_node = Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="log",
arguments=["-d", rviz_config_file],
condition=IfCondition(gui),
)
joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster", "--controller-manager", "/controller_manager"],
)
robot_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["forward_position_controller", "--controller-manager", "/controller_manager"],
)
# 延迟 RViz 启动,等待 'joint_state_broadcaster_spawner' 完成
delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[rviz_node],
)
)
# 延迟机器人控制器的启动,等待 'joint_state_broadcaster_spawner' 完成
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
)
# 将所有节点组合成一个列表
nodes = [
control_node,
robot_state_pub_node,
joint_state_broadcaster_spawner,
delay_rviz_after_joint_state_broadcaster_spawner,
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
]
# 返回 LaunchDescription,包括声明的参数和节点列表
return LaunchDescription(declared_arguments + nodes)