noetic版本/ubuntu20 通过moveit控制真实机械臂
noetic版本/ubuntu20 通过moveit控制真实机械臂
- config包代码浏览
- demo.launch
- move_group.launch
- trajectory_execution.launch.xml
- fake_moveit_controller_manager.launch.xml
- ros_control_moveit_controller_manager.launch.xml
- simple_moveit_controller_manager.launch.xml
- 修改方法
- demo.launch
- ros_controllers.yaml
前几年做过melodic版本的控制真实机械臂的笔记。
https://blog.csdn.net/ze3000/article/details/121473979
今天新项目是 ubuntu20+ros1 noetic 的环境,用 moveit 配置助手生成配置包后发现内容不一样了。因此重新写一篇作记录。
config包代码浏览
demo.launch
生成的demo.launch 文件,从上往下看。
<!-- Choose controller manager: fake, simple, or ros_control --><arg name="moveit_controller_manager" default="fake" />
controller manager 有三种选择类型:fake, simple, or ros_control。当前默认选择是 fake。
检查生成的文件,后缀是 moveit_controller_manager.launch.xml的。一共有三种:fake、simple、ros_control。
fake_moveit_controller_manager.launch.xml
simple_moveit_controller_manager.launch.xml
ros_control_moveit_controller_manager.launch.xml
<!-- Set execution mode for fake execution controllers --><arg name="fake_execution_type" default="interpolate" />
设置虚拟执行控制器的执行模式,这里是 interpolate。点开 fake_moveit_controller_manager.launch.xml 文件,看到:
<!-- execute the trajectory in 'interpolate' mode or jump to goal position in 'last point' mode --><arg name="fake_execution_type" default="interpolate" />
虚拟执行器有两种模式,一种 interpolate 模式,执行器会对目标位置进行插值,有运动过去的动画效果。另一种模式是 last point,即直接跳到目标点。
<!-- By default, hide joint_state_publisher's GUI in 'fake' controller_manager mode --><arg name="use_gui" default="false" /><arg name="use_rviz" default="true" />
在 fake controller_manager 模式下,隐藏 joint_state_publishe 的GUI:use_gui 默认为 false。默认开启 rviz。
<group if="$(eval arg('moveit_controller_manager') == 'fake')"><!-- We do not have a real robot connected, so publish fake joint states via a joint_state_publisherMoveIt's fake controller's joint states are considered via the 'source_list' parameter --><node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" unless="$(arg use_gui)"><rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam></node><!-- If desired, a GUI version is available allowing to move the simulated robot around manuallyThis corresponds to moving around the real robot without the use of MoveIt. --><node name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" if="$(arg use_gui)"><rosparam param="source_list">[move_group/fake_controller_joint_states]</rosparam></node><!-- Given the published joint states, publish tf for the robot links --><node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen" /></group>
如果使用 fake_moveit_controller_manager:
- use_gui == false: 订阅move_group/fake_controller_joint_states作为源列表
- use_gui == true: 订阅相同的源列表,但状态发布器带图形界面。
- robot_state_publisher节点:根据发布的关节状态,发布机器人的tf(变换)信息。这个节点会持续运行(respawn=“true”)并将输出显示在屏幕上(output=“screen”)。
节点 joint_state_publisher 是虚拟的,我们使用真实机械臂应该用实际获取的状态再发布到对应的话题, 默认是 /joint_states。
<!-- Run the main MoveIt executable without trajectory execution (we do not have controllers configured by default) --><include file="$(dirname)/move_group.launch"><arg name="allow_trajectory_execution" value="true"/><arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" /><arg name="fake_execution_type" value="$(arg fake_execution_type)"/><arg name="info" value="true"/><arg name="debug" value="$(arg debug)"/><arg name="pipeline" value="$(arg pipeline)"/><arg name="load_robot_description" value="$(arg load_robot_description)"/></include>
调用 move_group.launch 文件。并传入参数:
- allow_trajectory_execution:设为true表示允许进行轨迹规划
- moveit_controller_manager:前面设置的 fake 值
- fake_execution_type:当使用虚拟控制器时,指定执行方式为前面设置 interpolate
- info:启用信息输出,显示运动规划的相关信息
- pipeline:指定运动规划器。
move_group.launch
<!-- move_group settings --><arg name="pipeline" default="ompl" /><arg name="allow_trajectory_execution" default="true"/><arg name="moveit_controller_manager" default="simple" /><arg name="fake_execution_type" default="interpolate"/><arg name="max_safe_path_cost" default="1"/><arg name="publish_monitored_planning_scene" default="true"/><arg name="capabilities" default=""/><arg name="disable_capabilities" default=""/>
- pipeline:默认运动规划器设置为 ompl。
- allow_trajectory_execution:是否允许轨迹执行(默认允许)。
- moveit_controller_manager:控制器管理器类型设置为 simple。
- fake_execution_type:虚拟执行方式为interpolate。
- max_safe_path_cost:路径成本的安全阈值。
- publish_monitored_planning_scene:发布规划场景到RViz。
- capabilities:加载非默认功能(如自定义规划算法)
<include ns="move_group" file="$(dirname)/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)"><arg name="moveit_manage_controllers" value="true" /><arg name="moveit_controller_manager" value="$(arg moveit_controller_manager)" /><arg name="fake_execution_type" value="$(arg fake_execution_type)" /></include>
使用 moveit_controller_manager 为前面设置的 simple。
trajectory_execution.launch.xml
<include file="$(dirname)/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" pass_all_args="true" />
传参最后传到这里,终于确定了是启动哪个 _moveit_controller_manager.launch.xml 文件
fake_moveit_controller_manager.launch.xml
<param name="moveit_controller_manager" value="moveit_fake_controller_manager/MoveItFakeControllerManager"/><rosparam subst_value="true" file="$(find ti5_arm3_moveit_config)/config/fake_controllers.yaml"/>
会默认加载 fake_controllers.yaml 控制器参数文件。
controller_list:- name: fake_arm3_controllertype: $(arg fake_execution_type)joints:- A- B- C- D- E- F
ros_control_moveit_controller_manager.launch.xml
<param name="moveit_controller_manager" value="moveit_ros_control_interface::MoveItControllerManager" />
simple_moveit_controller_manager.launch.xml
<rosparam file="$(find ti5_arm3_moveit_config)/config/simple_moveit_controllers.yaml" /><rosparam file="$(find ti5_arm3_moveit_config)/config/ros_controllers.yaml" />
查找文件目录,发现 ros_controllers.yaml 这个文件为空,simple_moveit_controllers.yaml 里的controller_list 为空。
修改方法
demo.launch
将开头的 moveit_controller_manager 设置为 simple
<arg name="moveit_controller_manager" default="simple" />
ros_controllers.yaml
在自己编写的 hardware_interface 里,会启动
<rosparam file="$(find ti5_arm3_hardware_interface)/config/controllers.yaml" command="load"/>
ti5_arm3:controllers:state:type: joint_state_controller/JointStateControllerpublish_rate: 100position:type: position_controllers/JointTrajectoryControllerjoints:- A- B- C- D- E- Fconstraints:goal_time: 0.5A:trajectory: 0.5goal: 0.02B:trajectory: 0.5goal: 0.02C:trajectory: 0.5goal: 0.02D:trajectory: 0.5goal: 0.02E:trajectory: 0.5goal: 0.02F:trajectory: 0.5goal: 0.02
启动 hardware_interface 的节点,用 rostopic list 的值令查看话题的名字
/joint_states
/rosout
/rosout_agg
/ti5_arm3/controllers/position/command
/ti5_arm3/controllers/position/follow_joint_trajectory/cancel
/ti5_arm3/controllers/position/follow_joint_trajectory/feedback
/ti5_arm3/controllers/position/follow_joint_trajectory/goal
/ti5_arm3/controllers/position/follow_joint_trajectory/result
/ti5_arm3/controllers/position/follow_joint_trajectory/status
/ti5_arm3/controllers/position/state
前面的名字是 /ti5_arm3/controllers/position
修改moveit_config 功能包里面的 ros_controllers.yaml 文件
controller_list:- name: "/ti5_arm3/controllers/position"action_ns: follow_joint_trajectorytype: FollowJointTrajectorydefaunlt: truejoints:- A- B- C- D- E- F
至此,启动 hardware_interface 机械臂驱动,再启动 moveit_config 功能包里的 demo.launch 文件,拖动末端小球,规划执行,就能看到 rviz 里的仿真机械臂和真实机械臂的同步了。