接上文在ROS2使用Gazebo控制小车,上文控制小车使用的是libgazebo_ros_diff_drive.so这个插件,输入模型的数据就可以对小车进行差速控制。
本文介绍另外一种控制方式ros2_control
1. ros2_control的配置
当我们想要再Gazebo使用ros2_control 来控制关节运动时,需要配置三个地方:
-
写关于控制器的yaml:
1.1 配置Controller manager
controller_manager: ros__parameters: update_rate: 10 # Hz ### Controllers available joint_state_broadcaster: type: joint_state_broadcaster/JointStateBroadcaster forward_position_controller: type: forward_command_controller/ForwardCommandController position_trajectory_controller: type: joint_trajectory_controller/JointTrajectoryController
1.2. 对我们将要使用的控制器的属性和关节进行定义
forward_position_controller: ros__parameters: joints: - joint1 interface_name: position position_trajectory_controller: ros__parameters: joints: - joint1 command_interfaces: - position state_interfaces: - position state_publish_rate: 200.0 # Hz, Defaults to 50 action_monitor_rate: 20.0 # Hz, Defaults to 20 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 # Defaults to 0.0 (start immediately)
-
为了启用ros2_control,我们还必须向描述机器人的XACRO文件中添加一些新的tag. 包括ros2_control 和gazebo的tag
<ros2_control name="MyRobotSystem" type="system"> <hardware> <plugin>gazebo_ros2_control/GazeboSystem</plugin> </hardware> <joint name="joint1"> <command_interface name="position"> <param name="min">-6.28</param> <param name="max">6.28</param> </command_interface> <state_interface name="position"/> <state_interface name="velocity"/> <state_interface name="effort"/> </joint> </ros2_control> <!-- Gazebo's ros2_control plugin --> <gazebo> <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control"> <robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type> <parameters>$(find my_robot_bringup)/config/controller_configuration.yaml</parameters> </plugin> </gazebo>
-
最后是在launch文件中添加启动项
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", "-c", "/controller_manager"], ) return LaunchDescription([ RegisterEventHandler( event_handler=OnProcessExit( target_action=spawn_entity, on_exit=[joint_state_broadcaster_spawner], ) ), RegisterEventHandler( event_handler=OnProcessExit( target_action=joint_state_broadcaster_spawner, on_exit=[robot_controller_spawner], ) ), spawn_entity, node_robot_state_publisher, ])
值得一提的是
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[robot_controller_spawner],
)
意思是等启动完joint_state_broadcaster_spawner,再启动 robot_controller_spawner。
之后会介绍一下 controller_manager 以及 如何在真实机器人上使用ros2_control