最近在研究ROS的机械臂,但是在RViz与gazebo联合仿真时出现如下错误,,找了好几个博主的都没能解决,最终修改一处代码就解决了,解决方法提供给大家,希望对大家有帮助。
其他博主的解决办法:
moveIt之Unable to identify any set of controllers that can actuate the specified joints问题解决 - 知乎
Unable to identify any set of controllers that can actuate the specified joints:_we-ai的博客-CSDN博客
我的环境如下:
Ubuntu版本:20.04 LTS
ROS版本: noetic
moveit!版本:1.1.13
出现的问题如下:
[ERROR] [1701506431.253044843, 25.636000000]: Unable to identify any set of controllers that can actuate the specified joints: [ joint1 joint2 joint3 joint4 joint5 joint6 ]
[ERROR] [1701506431.253073031, 25.636000000]: Known controllers and their joints:
[ERROR] [1701506431.253102750, 25.636000000]: Apparently trajectory initialization failed
解决办法:
找到arm_gazebo文件下的trajectory_control.yaml文件,修改前内容如下:
arm:
arm_joint_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
gains:
joint1: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint2: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint3: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint4: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint5: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
joint6: {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}
gripper_controller:
type: "position_controllers/JointTrajectoryController"
joints:
- finger_joint1
gains:
finger_joint1: {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}
将机械臂模型的控制器“arm_joint_controller”修改为“arm_controller”,这里不一定是和我的一样,要和使用Moveit Setup Assistant生成的文件里中controller_gazebo.yaml文件里的控制器名一样,我这里的controller_gazebo.yaml文件内容如下:
controller_manager_ns: controller_manager
controller_list:
- name: arm/arm_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: True
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
- name: arm/gripper_controller
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: True
joints:
- finger_joint1
同时找到ma_arm_moveit_config/simple_moveit_controller_manager.launch.xml文件,老版本的moveit生成的可能是arm_moveit_controller_manager.launch.xml这个文件,但是都是一样的,在这个文件中进行如下修改:
<launch>
<!-- Define the MoveIt controller manager plugin to use for trajectory execution -->
<param name="moveit_controller_manager" value="moveit_simple_controller_manager/MoveItSimpleControllerManager" />
<!-- Load controller list to the parameter server -->
<!--不进行rviz和gazebo联合仿真时,使用下面的命令-->
<!--<rosparam file="$(find hqyj_arm_moveit_config)/config/simple_moveit_controllers.yaml" />-->
<!--在进行rviz和gazebo联合仿真时,使用下面的命令-->
<rosparam file="$(find hqyj_arm_moveit_config)/config/controller_gazebo.yaml" />
<rosparam file="$(find hqyj_arm_moveit_config)/config/ros_controllers.yaml" />
</launch>
之后再去执行仿真命令就完美解决了,也不会出现任何报错。
运行效果如下: