参考链接:
通过ROS控制真实机械臂(5)—Moveit!真实机械臂(move_group界面)
使用moveit控制真实机械臂
<include file="$(find ur5_robotiq140_real_moveit_config)/launch/move_group.launch">
<arg name="allow_trajectory_execution" value="true"/>
<arg name="fake_execution" value="false"/>
<arg name="info" value="true"/>
<arg name="debug" value="$(arg debug)"/>
include>
解决真实机械臂与 joint_states_publisher
消息冲突的问题。
当控制真实机械臂时,moveit 的配置文件中,demo.launch
文件中关于 joint_states_publisher
的一段代码需要注释掉,因为该程序也在发布机械臂关节状态,而且是一个模拟的状态,与真实机械臂状态是不相符的,若不注释掉该代码,rviz 下显示的机械臂状态总是在不停的跳变,将原本的注释,使用真实的传感器发布的 /joint_states
来控制。
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="use_gui" value="$(arg use_gui)"/>
<rosparam param="/source_list">[/joint_states]rosparam>
node>
move_group.launch
文件中,moveit_controller_manager
在选择参数值时,unless
前面那个 velue
值要修改,写一个自己机器人名称作为前缀。
<include ns="move_group" file="$(find ur5_robotiq140_real_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="ur5" unless="$(arg fake_execution)"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
include>
moveit_controller_manager
的参数是有选择的,要么等于“ur5”,要么等于“fake”,这要取决于后面的参数fake_execution
, 而这个参数我们上一步已经改为了false,即当前moveit_controller_manager
应该等于“ur5”接下来,这个参数会传递给trajectory_execution.launch.xml
文件,该文件中有下面这句话,按照原先的设置,本应该启动fake_moveit_controller_manager.launch.xml
,而现在ur5_moveit_controller_manager.launch.xml
将会被启动。
<include file="$(find moveit)/launch/$(arg moveit_controller_manager)_moveit_controller_manager.launch.xml" />
......
......
......
<node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
<env name="DISPLAY" value="$(optenv DISPLAY :0)" />
<param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
<param name="capabilities" value="move_group/MoveGroupCartesianPathService
move_group/MoveGroupExecuteTrajectoryAction
move_group/MoveGroupKinematicsService
move_group/MoveGroupMoveAction
move_group/MoveGroupPickPlaceAction
move_group/MoveGroupPlanService
move_group/MoveGroupQueryPlannersService
move_group/MoveGroupStateValidationService
move_group/MoveGroupGetPlanningSceneService
move_group/ClearOctomapService
" />
<param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
node>
moveit 配置文件中有几个参数还需要添加上,否则后续真实机械臂执行轨迹时会报超时的错误。需要在 move_group.launch
文件中增加几个参数,来延长允许执行轨迹的时间。 找到
所对应的标签组,在其中加入以下参数:
<include ns="move_group" file="$(find ur5_robotiq140_real_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="ompl" />
<param name="trajectory_execution/execution_duration_monitoring" value="false"/>
include>
这个文件用于配置 MoveIt 的控制器,我们需要将MoveIt 的控制器指向我们上一步创建的控制器。
<launch>
<arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/>
<arg name="use_controller_manager" default="true" />
<param name="use_controller_manager" value="$(arg use_controller_manager)" />
<rosparam file="$(find ur5_robotiq140_real_moveit_config)/config/controllers.yaml"/>
launch>
将
ur5_robotiq140_real_moveit_config
修改为你自己的moveit配置文件目录名称
上一步的代码最后一句指向了config
目录下一个叫做controller.yaml
的文件,决定了你所使用的moveit控制器的基本参数。我们打开配置文件夹中的config
目录,发现只有fake_controllers.yaml
,所以,现在要做的就是复制一份这个文件,然后将名字改为controllers.yaml
,打开这个新文件,将文件修改成如下形式:
controller_list:
- name: ""
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- shoulder_pan_joint
- shoulder_lift_joint
- elbow_joint
- wrist_1_joint
- wrist_2_joint
- wrist_3_joint
- name: gripper
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
joints:
- finger_joint
参数含义:
name: 这里你可以写一个与你机器人相关的名称,方便你使用。
action_ns: follow_joint_trajectory
,follow_joint_trajectory
是后续 action
的名称的一部分,将来你需要填一个 action
的名称,这个名称就在这个配置文件里确定了,就是 name/action_ns
所代表的对应字符串的组合。
type: FollowJointTrajectory
,这个类型是 ros 下的自带 action
类型,是一种控制机械臂运动轨迹的数据结构,请原样填写,将来你可能还想控制手抓之类的结构,所填写的类型都是不一样的。
joints: 这里是你机器人(机械臂)的关节名称,这些名称源自你的机器人模型文件,我们的 controllers.yaml
文件复制于 fake_controllers.yaml
文件,这部分应该是自动生成的。
至此,moveit!已经修改完成,先启动试试看!!!