版本信息:
ubuntu版本:Ubuntu 20.04.6 LTS
ROS版本:ROS1 noetic
gazebo版本:version 11.5.1
问题描述:两轮差速底盘使用libgazebo_ros_diff_drive.so控制插件,机械臂使用moveit助手配置,使用libgazebo_ros_control.so控制插件。发现在机器人模型描述文件中同时加载上述两种插件,底盘差速插件会失效(现象为:/cmd_vel话题正常,但机器人模型在rviz和gazebo中不运动)。
问题原因:libgazebo_ros_diff_drive.so插件和libgazebo_ros_control.so插件冲突。
解决思路:放弃libgazebo_ros_diff_drive.so插件,只使用libgazebo_ros_control.so插件。
解决方法:
1.在机器人模型文件中(.urdf.xacro文件)注释掉或直接删除掉libgazebo_ros_diff_drive.so插件的使用。(我这里选择了注释,没删)
2.在控制器配置文件中(我的文件名称是ros_controller.yaml,配置完moveit后自动生成的)添加类型为diff_drive_controller/DiffDriveController的控制器。我控制器名称设置为了chassis_controller,其他参数的含义可以看下这位大佬的文章https://blog.youkuaiyun.com/maizousidemao/article/details/140066845https://blog.youkuaiyun.com/maizousidemao/article/details/140066845
chassis_controller:
type: diff_drive_controller/DiffDriveController
left_wheel: wheel_ml_joint
right_wheel: wheel_mr_joint
publish_rate: 10
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
wheel_separation: 0.28275
wheel_radius: 0.068
wheel_separation_multiplier: 1.0
wheel_radius_multiplier: 1.0
cmd_vel_timeout: 0.5
base_frame_id: base_footprint
enable_odom_tf: true
odom_frame_id: odom
publish_cmd: true
velocity_rolling_window_size: 1
linear:
x:
has_velocity_limits : true
max_velocity : 1.0 # m/s
has_acceleration_limits: true
max_acceleration : 3.0 # m/s^2
angular:
z:
has_velocity_limits : true
max_velocity : 2.0 # rad/s
has_acceleration_limits: true
max_acceleration : 6.0 # rad/s^2
我的配置文件完整内容如下。同时需要注意,controller_list下的控制器名称,需要和后续控制器的名称完全对应,大家也可以参考一下我的配置文件的格式。
# Simulation settings for using moveit_sim_controllers
moveit_sim_hw_interface:
joint_model_group: arm_group
joint_model_group_pose: arm_home
# Settings for ros_control_boilerplate control loop
generic_hw_control_loop:
loop_hz: 300
cycle_time_error_threshold: 0.01
# Settings for ros_control hardware interface
hardware_interface:
joints:
- arm1_joint
- arm2_joint
- arm3_joint
- arm4_joint
- arm5_joint
- arm6_joint
- jaw1_joint
- jaw2_joint
- bl_yaw_joint
- wheel_bl_joint
- br_yaw_joint
- wheel_br_joint
- fl_yaw_joint
- wheel_fl_joint
- fr_yaw_joint
- wheel_fr_joint
- wheel_ml_joint
- wheel_mr_joint
sim_control_mode: 1 # 0: position, 1: velocity
# Publish all joint states
# Creates the /joint_states topic necessary in ROS
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50
controller_list:
- name: arm_controller
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
joints:
- arm1_joint
- arm2_joint
- arm3_joint
- arm4_joint
- arm5_joint
- arm6_joint
- name: jaw_controller
action_ns: follow_joint_trajectory
default: True
type: FollowJointTrajectory
joints:
- jaw1_joint
- jaw2_joint
arm_controller:
type: position_controllers/JointTrajectoryController
joints:
- arm1_joint
- arm2_joint
- arm3_joint
- arm4_joint
- arm5_joint
- arm6_joint
gains:
arm1_joint:
p: 100
d: 1
i: 1
i_clamp: 1
arm2_joint:
p: 100
d: 1
i: 1
i_clamp: 1
arm3_joint:
p: 100
d: 1
i: 1
i_clamp: 1
arm4_joint:
p: 100
d: 1
i: 1
i_clamp: 1
arm5_joint:
p: 100
d: 1
i: 1
i_clamp: 1
arm6_joint:
p: 100
d: 1
i: 1
i_clamp: 1
jaw_controller:
type: position_controllers/JointTrajectoryController
joints:
- jaw1_joint
- jaw2_joint
gains:
jaw1_joint:
p: 100
d: 1
i: 1
i_clamp: 1
jaw2_joint:
p: 100
d: 1
i: 1
i_clamp: 1
chassis_controller:
type: diff_drive_controller/DiffDriveController
left_wheel: wheel_ml_joint
right_wheel: wheel_mr_joint
publish_rate: 10
pose_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.03]
wheel_separation: 0.28275
wheel_radius: 0.068
wheel_separation_multiplier: 1.0
wheel_radius_multiplier: 1.0
cmd_vel_timeout: 0.5
base_frame_id: base_footprint
enable_odom_tf: true
odom_frame_id: odom
publish_cmd: true
velocity_rolling_window_size: 1
linear:
x:
has_velocity_limits : true
max_velocity : 1.0 # m/s
has_acceleration_limits: true
max_acceleration : 3.0 # m/s^2
angular:
z:
has_velocity_limits : true
max_velocity : 2.0 # rad/s
has_acceleration_limits: true
max_acceleration : 6.0 # rad/s^2
3.diff_drive_controller/DiffDriveController类型的控制器监听的是控制器自己命名空间下的/cmd_vel话题,对于我的文件来说,控制器监听的话题就为/chassis_controller/cmd_vel,因此需要将速度信息发布到这个话题下
4.最后,大家记得在启动文件中调用配置好的控制器,记得名字也是要一一对应