分别创建两个功能包,分别为dual_ur_description和dual_ur_gazebo,前者存放ur5的双臂模型文件,后者存放Gazebo的相关文件。
在dual_ur_description中将官方提供的ur_description功能包中的所有文件放入,在urdf文件中新建dual_ur5_robot.urdf.xacro和dual_ur5_joint_limited_robot.urdf.xacro两个文件,前者表示关节运动不限制的ur5双臂模型,后者在前者的基础上增加了关节限制。此外还需要在launch文件夹中创建dual_ur5_upload.launch文件,用于将双臂ur5模型的xacro文件上传至参数服务器。
dual_ur5_robot.urdf.xacro代码如下:
关键部分:
首先载入ur5.urdf.xacro模型文件,这个是官方提供的单个ur5的模型文件,而后分别调用该文件创建了左右两个ur5机械臂。
而后分别给两个机械臂创建了两个与世界坐标系固连的关节,注意这两个关节的
dual_ur5_joint_limited_robot.urdf.xacro代码如下:
和前者类似,对比着看。
dual_ur5_upload.launch代码如下:
前者设置limited参数,默认为false,也可以在启动该launch文件时设置该参数,当limited为false时,解析dual_ur5_robot.urdf.xacro文件,反之解析dual_ur5_joint_limited_robot.urdf.xacro文件。
同样将官方提供的ur_gazebo文件拷贝进来,在controller文件夹中新建arm_controller_dual_ur.yaml文件,用于加载Gazebo中的控制器参数,在launch文件中新建和dual_ur5.launch用于启动双臂ur5的仿真平台。
arm_controller_dual_ur.yaml代码如下:
left_arm_controller:
type: position_controllers/JointTrajectoryController
joints:
- left_shoulder_pan_joint
- left_shoulder_lift_joint
- left_elbow_joint
- left_wrist_1_joint
- left_wrist_2_joint
- left_wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
left_shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
left_shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
left_elbow_joint: {trajectory: 0.1, goal: 0.1}
left_wrist_1_joint: {trajectory: 0.1, goal: 0.1}
left_wrist_2_joint: {trajectory: 0.1, goal: 0.1}
left_wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
joint_group_position_controller:
type: position_controllers/JointGroupPositionController
joints:
- left_shoulder_pan_joint
- left_shoulder_lift_joint
- left_elbow_joint
- left_wrist_1_joint
- left_wrist_2_joint
- left_wrist_3_joint
- right_shoulder_pan_joint
- right_shoulder_lift_joint
- right_elbow_joint
- right_wrist_1_joint
- right_wrist_2_joint
- right_wrist_3_joint
right_arm_controller:
type: position_controllers/JointTrajectoryController
joints:
- right_shoulder_pan_joint
- right_shoulder_lift_joint
- right_elbow_joint
- right_wrist_1_joint
- right_wrist_2_joint
- right_wrist_3_joint
constraints:
goal_time: 0.6
stopped_velocity_tolerance: 0.05
right_shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
right_shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
right_elbow_joint: {trajectory: 0.1, goal: 0.1}
right_wrist_1_joint: {trajectory: 0.1, goal: 0.1}
right_wrist_2_joint: {trajectory: 0.1, goal: 0.1}
right_wrist_3_joint: {trajectory: 0.1, goal: 0.1}
stop_trajectory_duration: 0.5
state_publish_rate: 25
action_monitor_rate: 10
dual_ur5.launch代码如下:
关键代码如下:
设置一些参数,limited默认为false。
加载Gazebo的仿真世界,这里的light.world是我自定义的在空世界的基础上加了一个光源的世界,也可以换成Gazebo自带的empty.world。
包含上述所写的dual_ur5_upload.launch文件,将ur5双臂模型上传至参数服务器。
Gazebo从参数服务器中载入该模型文件。
加载一些控制器,包括刚刚所写的arm_controller_dual_ur.yaml配置文件。
启动dual_ur5.launch文件即可,具体操作双臂见ur5双臂Gazebo仿真。
本文参考https://github.com/Liuyvjin/shixi_dual_ur开源项目进行改写。
本文代码连接:https://github.com/Wujinshan/dual_ur5