修改ros中的控制器,便于仿真和驱动真实UR
UR机械臂学习(5-3):驱动ur机械臂实物——问题及解决_error: 鈥榰r_msgs::setpayloadrequest {aka struct ur__冰激凌啊的博客-程序员宝宝 - 程序员宝宝 (cxybb.com)
问题5 Action client not connected: scaled_pos_traj_controller/follow_joint_trajectory
[ WARN] [1624863539.203489625, 57.864000000]: Waiting for scaled_pos_joint_traj_controller/follow_joint_trajectory to come up
[ WARN] [1624863545.212986404, 63.864000000]: Waiting for scaled_pos_joint_traj_controller/follow_joint_trajectory to come up
[ERROR] [1624863551.221038108, 69.865000000]: Action client not connected: scaled_pos_joint_traj_controller/follow_joint_trajectory
解决:
这个是个很大的坑。
首先要确定的是在/home/guyue/ur_ws/src/fmauch_universal_robot/ur3_moveit_config/config
下的ros_controllers.yaml
里
name需要为scaled_pos_traj_controller
,因为如果不是这个名字,是无法驱动实物机械臂的。
下面说原因:
看下面这张图,bringup启动的时候,他启动的是scaled_pos_traj_controller
控制器
然后再回来说为什么启动gazebo,然后再启动moveit的时候会报这个错
看下面这张图
/home/guyue/ur_ws/src/fmauch_universal_robot/ur3_moveit_config/config
下的ros_controllers.yaml
和/home/guyue/ur_ws/src/fmauch_universal_robot/ur_gazebo/config
下的ur3_controllers.yaml
这两个文件夹对这个控制器的名字不一样
现在有两种思路
- 一种是把这两个文件里关于控制器的名称改为一样的
- 另一种是在某个文件里把这两个控制器连接在一起
先说第一种思路:
如果把moveit下面的ros_controllers.yaml
里的scaled_pos_traj_controller
改为pos_traj_controller
gazebo和所有仿真都正常,但在驱动实物时又会出现问题,因为ur_ros_driver
驱动里面所有控制器的名字都是scaled_pos_traj_controller
而如果把gazebo下面的ur3_controllers.yaml
里的pos_traj_controller
改为scaled_pos_traj_controller
在启动gazebo时就会报错,因为/home/guyue/ur_ws/src/fmauch_universal_robot/ur_gazebo/launch
文件夹下的ur3_bringup.launch
也同样将这个控制器的名字命名为pos_traj_controller
如果说ur3_controllers.yaml
和ur3_bringup.launch
里的名字都修改,启动gazebo是不报错了,但启动moveit时还是会报最开始的那个错误。
所以,我们因当采取的是第二种思路:
也就是修改两者的连接文件
我们在moveit中启动的是ur3_moveit_planning_execution.launchl
文件,所以从这个文件开始看起。
在这个里面就提到了如果sim
参数为true
,就连接两个控制器,但是这里面对于gazebo的名字为arm_controller
,而不是现在所使用的pos_traj_controller
,所以问题应该就出现在这里了。
所以,最后应该是修改/home/guyue/ur_ws/src/fmauch_universal_robot/ur3_moveit_config/launch
下的ur3_moveit_planning_execution.launchl
修改后应该如下图所示
因为gazebo和moveit里的分别是
# moveit
controller_list:
- name: "scaled_pos_joint_traj_controller"action_ns: follow_joint_trajectorytype: FollowJointTrajectoryjoints:- shoulder_pan_joint- shoulder_lift_joint- elbow_joint- wrist_1_joint- wrist_2_joint- wrist_3_joint# gazebo
pos_joint_traj_controller:type: position_controllers/JointTrajectoryControllerjoints: &robot_joints- shoulder_pan_joint- shoulder_lift_joint- elbow_joint- wrist_1_joint- wrist_2_joint- wrist_3_joint
所以修改ur3_moveit_planning_execution.launchl
为
<remap if="$(arg sim)" from="/scaled_pos_joint_traj_controller/follow_joint_trajectory" to="/pos_joint_traj_controller/follow_joint_trajectory"/>
最后,因为ur的安装包和驱动一直在更新,所以如果这种方法也没用了,可以注意下面几个文件里控制器的名称是否一致
-
gazebo里的文件
/home/guyue/ur_ws/src/fmauch_universal_robot/ur_gazebo/config
文件夹下的ur3_controllers.yaml
/home/guyue/ur_ws/src/fmauch_universal_robot/ur_gazebo/launch
文件夹下的ur3_bringup.launch
-
moveit的文件
/home/guyue/ur_ws/src/fmauch_universal_robot/ur3_moveit_config/config
文件夹下的ros_controllers.yaml
/home/guyue/ur_ws/src/fmauch_universal_robot/ur3_moveit_config/launch
文件夹下的ur3_moveit_planning_execution.launch
最后的最后,2021年6月下载的fmauch版,moveit的部分不需要修改,只需要修改gazebo部分
也就是说,只驱动真实机械臂,不仿真,是没有任何问题的,不需要任何修改