diff --git a/sr_multi_description/urdf/right_srhand_ur10e.urdf.xacro b/sr_multi_description/urdf/right_srhand_ur10e.urdf.xacro index 82fa8bd48..3286679fc 100644 --- a/sr_multi_description/urdf/right_srhand_ur10e.urdf.xacro +++ b/sr_multi_description/urdf/right_srhand_ur10e.urdf.xacro @@ -23,9 +23,35 @@ + - + - + + + + true + + true + true + + sensor + child_to_parent + + + + true + + + + + 125.0 + ra_wrench + ra_arm_to_hand + + diff --git a/sr_multi_moveit/sr_multi_moveit_config/config/robot_configs/right_sh_ur10.yaml b/sr_multi_moveit/sr_multi_moveit_config/config/robot_configs/right_sh_ur10.yaml index c3c1a58a7..052ea3d2e 100644 --- a/sr_multi_moveit/sr_multi_moveit_config/config/robot_configs/right_sh_ur10.yaml +++ b/sr_multi_moveit/sr_multi_moveit_config/config/robot_configs/right_sh_ur10.yaml @@ -6,7 +6,7 @@ robot: arm: name: ur10 main_group: manipulator - moveit_path: + moveit_path: package: sr_multi_moveit_config relative_path: /config/ur extra_groups_config_path: /config diff --git a/sr_robot_launch/config/gazebo/controller/ra_trajectory_controller_no_wrist.yaml b/sr_robot_launch/config/gazebo/controller/ra_trajectory_controller_no_wrist.yaml new file mode 100644 index 000000000..ee760ec23 --- /dev/null +++ b/sr_robot_launch/config/gazebo/controller/ra_trajectory_controller_no_wrist.yaml @@ -0,0 +1,50 @@ +# gazebo_ros_control: +# pid_gains: +# ra_shoulder_pan_joint: {p: 500, i: 1000, d: 0.1, i_clamp_max: 1000, i_clamp_min: -1000, antiwindup: true} +# ra_shoulder_lift_joint: {p: 500, i: 1000, d: 0.1, i_clamp_max: 1000, i_clamp_min: -1000, antiwindup: true} +# ra_elbow_joint: {p: 500, i: 1000, d: 0.1, i_clamp_max: 1000, i_clamp_min: -1000, antiwindup: true} +# ra_wrist_1_joint: {p: 500, i: 1000, d: 0.1, i_clamp_max: 1000, i_clamp_min: -1000, antiwindup: true} +# ra_wrist_2_joint: {p: 500, i: 1000, d: 0.1, i_clamp_max: 1000, i_clamp_min: -1000, antiwindup: true} +# ra_wrist_3_joint: {p: 500, i: 1000, d: 0.1, i_clamp_max: 1000, i_clamp_min: -1000, antiwindup: true} + + +ra_trajectory_controller: + type: "velocity_controllers/ComplianceController" + joints: + - ra_shoulder_pan_joint + - ra_shoulder_lift_joint + - ra_elbow_joint + - ra_wrist_1_joint + - ra_wrist_2_joint + - ra_wrist_3_joint + compliance_command_timeout: 1.5 + constraints: + goal_time: 0.6 + stopped_velocity_tolerance: 1.0 + ra_shoulder_pan_joint: {trajectory: 0.3, goal: 0.1} + ra_shoulder_lift_joint: {trajectory: 0.3, goal: 0.1} + ra_elbow_joint: {trajectory: 0.3, goal: 0.1} + ra_wrist_1_joint: {trajectory: 0.3, goal: 0.1} + ra_wrist_2_joint: {trajectory: 0.3, goal: 0.1} + ra_wrist_3_joint: {trajectory: 0.3, goal: 0.1} + stop_trajectory_duration: 0.5 + state_publish_rate: 25 + action_monitor_rate: 10 + allow_partial_joints_goal: true + #!!These values have not been optimized!! + gains: + ra_shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + ra_shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + ra_elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + ra_wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + ra_wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + ra_wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} + + # Use a feedforward term to reduce the size of PID gains + velocity_ff: + ra_shoulder_pan_joint: 1.0 + ra_shoulder_lift_joint: 1.0 + ra_elbow_joint: 1.0 + ra_wrist_1_joint: 1.0 + ra_wrist_2_joint: 1.0 + ra_wrist_3_joint: 1.0 diff --git a/sr_robot_launch/config/ra_compliant_trajectory_controller.yaml b/sr_robot_launch/config/ra_compliant_trajectory_controller.yaml new file mode 100644 index 000000000..741acc6b9 --- /dev/null +++ b/sr_robot_launch/config/ra_compliant_trajectory_controller.yaml @@ -0,0 +1,49 @@ + +joints: &robot_joints + - ra_shoulder_pan_joint + - ra_shoulder_lift_joint + - ra_elbow_joint + - ra_wrist_1_joint + - ra_wrist_2_joint + - ra_wrist_3_joint + +ra_trajectory_controller: + type: "velocity_controllers/ComplianceController" + joints: *robot_joints + compliance_command_timeout: 1.5 + constraints: + goal_time: 6.0 + stopped_velocity_tolerance: 0.05 + ra_shoulder_pan_joint: {trajectory: 0.3, goal: 0.1} + ra_shoulder_lift_joint: {trajectory: 0.3, goal: 0.1} + ra_elbow_joint: {trajectory: 0.3, goal: 0.1} + ra_wrist_1_joint: {trajectory: 0.3, goal: 0.1} + ra_wrist_2_joint: {trajectory: 0.3, goal: 0.1} + ra_wrist_3_joint: {trajectory: 0.3, goal: 0.1} + stop_trajectory_duration: 0.5 + state_publish_rate: 250 + action_monitor_rate: 10 + allow_partial_joints_goal: true + #!!These values have not been optimized!! + gains: + p: &p_gain 20.0 + i: &i_gain 0.0 + d: &d_gain 0.0 + clamp: &i_clamp 1.0 + ra_shoulder_pan_joint: {p: *p_gain, i: *i_gain, d: *d_gain, i_clamp: *i_clamp} + ra_shoulder_lift_joint: {p: *p_gain, i: *i_gain, d: *d_gain, i_clamp: *i_clamp} + ra_elbow_joint: {p: *p_gain, i: *i_gain, d: *d_gain, i_clamp: *i_clamp} + ra_wrist_1_joint: {p: *p_gain, i: *i_gain, d: *d_gain, i_clamp: *i_clamp} + ra_wrist_2_joint: {p: *p_gain, i: *i_gain, d: *d_gain, i_clamp: *i_clamp} + ra_wrist_3_joint: {p: *p_gain, i: *i_gain, d: *d_gain, i_clamp: *i_clamp} + + # Use a feedforward term to reduce the size of PID gains + velocity_ff: + var: &v_ff 0.0 + ra_shoulder_pan_joint: *v_ff + ra_shoulder_lift_joint: *v_ff + ra_elbow_joint: *v_ff + ra_wrist_1_joint: *v_ff + ra_wrist_2_joint: *v_ff + ra_wrist_3_joint: *v_ff + diff --git a/sr_robot_launch/config/ra_trajectory_controller.yaml b/sr_robot_launch/config/ra_trajectory_controller.yaml index 8160c541b..3ea63e484 100644 --- a/sr_robot_launch/config/ra_trajectory_controller.yaml +++ b/sr_robot_launch/config/ra_trajectory_controller.yaml @@ -1,13 +1,16 @@ + +joints: &robot_joints + - ra_shoulder_pan_joint + - ra_shoulder_lift_joint + - ra_elbow_joint + - ra_wrist_1_joint + - ra_wrist_2_joint + - ra_wrist_3_joint + ra_trajectory_controller: type: "position_controllers/JointTrajectoryController" hardware_interface: - joints: &robot_joints - - ra_shoulder_pan_joint - - ra_shoulder_lift_joint - - ra_elbow_joint - - ra_wrist_1_joint - - ra_wrist_2_joint - - ra_wrist_3_joint + joints: *robot_joints joints: *robot_joints constraints: goal_time: 0.6 diff --git a/sr_robot_launch/launch/sr_bimanual_hardware_control_loop.launch b/sr_robot_launch/launch/sr_bimanual_hardware_control_loop.launch index b071c3482..ddd5bcd96 100644 --- a/sr_robot_launch/launch/sr_bimanual_hardware_control_loop.launch +++ b/sr_robot_launch/launch/sr_bimanual_hardware_control_loop.launch @@ -44,6 +44,9 @@ + + + @@ -56,8 +59,8 @@ + - diff --git a/sr_robot_launch/launch/sr_hardware_control_loop.launch b/sr_robot_launch/launch/sr_hardware_control_loop.launch index ecca5de1d..4aff21aff 100644 --- a/sr_robot_launch/launch/sr_hardware_control_loop.launch +++ b/sr_robot_launch/launch/sr_hardware_control_loop.launch @@ -46,6 +46,7 @@ + @@ -61,10 +62,14 @@ + + - + + + @@ -156,6 +161,13 @@ - unique_robot_hw + + + + [/robot_description, /robot_description_semantic] + + + @@ -163,16 +175,14 @@ + - - - - - +