|
| 1 | +# Settings for ros_control control loop |
| 2 | +hardware_control_loop: |
| 3 | + loop_hz: &loop_hz 500 |
| 4 | + |
| 5 | +# Settings for ros_control hardware interface |
| 6 | +ur_hardware_interface: |
| 7 | + joints: &robot_joints |
| 8 | + - shoulder_pan_joint |
| 9 | + - shoulder_lift_joint |
| 10 | + - elbow_joint |
| 11 | + - wrist_1_joint |
| 12 | + - wrist_2_joint |
| 13 | + - wrist_3_joint |
| 14 | + |
| 15 | +# Publish all joint states ---------------------------------- |
| 16 | +joint_state_controller: |
| 17 | + type: joint_state_controller/JointStateController |
| 18 | + publish_rate: *loop_hz |
| 19 | + |
| 20 | +# Publish wrench ---------------------------------- |
| 21 | +force_torque_sensor_controller: |
| 22 | + type: force_torque_sensor_controller/ForceTorqueSensorController |
| 23 | + publish_rate: *loop_hz |
| 24 | + |
| 25 | +# Publish speed_scaling factor |
| 26 | +speed_scaling_state_controller: |
| 27 | + type: ur_controllers/SpeedScalingStateController |
| 28 | + publish_rate: *loop_hz |
| 29 | + |
| 30 | +# Joint Trajectory Controller - position based ------------------------------- |
| 31 | +# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller |
| 32 | +scaled_pos_joint_traj_controller: |
| 33 | + type: position_controllers/ScaledJointTrajectoryController |
| 34 | + joints: *robot_joints |
| 35 | + constraints: |
| 36 | + goal_time: 0.6 |
| 37 | + stopped_velocity_tolerance: 0.05 |
| 38 | + shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} |
| 39 | + shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} |
| 40 | + elbow_joint: {trajectory: 0.2, goal: 0.1} |
| 41 | + wrist_1_joint: {trajectory: 0.2, goal: 0.1} |
| 42 | + wrist_2_joint: {trajectory: 0.2, goal: 0.1} |
| 43 | + wrist_3_joint: {trajectory: 0.2, goal: 0.1} |
| 44 | + stop_trajectory_duration: 0.5 |
| 45 | + state_publish_rate: *loop_hz |
| 46 | + action_monitor_rate: 20 |
| 47 | + |
| 48 | +pos_joint_traj_controller: |
| 49 | + type: position_controllers/JointTrajectoryController |
| 50 | + joints: *robot_joints |
| 51 | + constraints: |
| 52 | + goal_time: 0.6 |
| 53 | + stopped_velocity_tolerance: 0.05 |
| 54 | + shoulder_pan_joint: {trajectory: 0.2, goal: 0.1} |
| 55 | + shoulder_lift_joint: {trajectory: 0.2, goal: 0.1} |
| 56 | + elbow_joint: {trajectory: 0.2, goal: 0.1} |
| 57 | + wrist_1_joint: {trajectory: 0.2, goal: 0.1} |
| 58 | + wrist_2_joint: {trajectory: 0.2, goal: 0.1} |
| 59 | + wrist_3_joint: {trajectory: 0.2, goal: 0.1} |
| 60 | + stop_trajectory_duration: 0.5 |
| 61 | + state_publish_rate: *loop_hz |
| 62 | + action_monitor_rate: 20 |
| 63 | + |
| 64 | +scaled_vel_joint_traj_controller: |
| 65 | + type: velocity_controllers/ScaledJointTrajectoryController |
| 66 | + joints: *robot_joints |
| 67 | + constraints: |
| 68 | + goal_time: 0.6 |
| 69 | + stopped_velocity_tolerance: 0.05 |
| 70 | + shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} |
| 71 | + shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} |
| 72 | + elbow_joint: {trajectory: 0.1, goal: 0.1} |
| 73 | + wrist_1_joint: {trajectory: 0.1, goal: 0.1} |
| 74 | + wrist_2_joint: {trajectory: 0.1, goal: 0.1} |
| 75 | + wrist_3_joint: {trajectory: 0.1, goal: 0.1} |
| 76 | + gains: |
| 77 | + #!!These values have not been optimized!! |
| 78 | + shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 79 | + shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 80 | + elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 81 | + wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 82 | + wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 83 | + wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 84 | + # Use a feedforward term to reduce the size of PID gains |
| 85 | + velocity_ff: |
| 86 | + shoulder_pan_joint: 1.0 |
| 87 | + shoulder_lift_joint: 1.0 |
| 88 | + elbow_joint: 1.0 |
| 89 | + wrist_1_joint: 1.0 |
| 90 | + wrist_2_joint: 1.0 |
| 91 | + wrist_3_joint: 1.0 |
| 92 | + stop_trajectory_duration: 0.5 |
| 93 | + state_publish_rate: *loop_hz |
| 94 | + action_monitor_rate: 20 |
| 95 | + |
| 96 | +vel_joint_traj_controller: |
| 97 | + type: velocity_controllers/JointTrajectoryController |
| 98 | + joints: *robot_joints |
| 99 | + constraints: |
| 100 | + goal_time: 0.6 |
| 101 | + stopped_velocity_tolerance: 0.05 |
| 102 | + shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} |
| 103 | + shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} |
| 104 | + elbow_joint: {trajectory: 0.1, goal: 0.1} |
| 105 | + wrist_1_joint: {trajectory: 0.1, goal: 0.1} |
| 106 | + wrist_2_joint: {trajectory: 0.1, goal: 0.1} |
| 107 | + wrist_3_joint: {trajectory: 0.1, goal: 0.1} |
| 108 | + gains: |
| 109 | + #!!These values have not been optimized!! |
| 110 | + shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 111 | + shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 112 | + elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 113 | + wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 114 | + wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 115 | + wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1} |
| 116 | + # Use a feedforward term to reduce the size of PID gains |
| 117 | + velocity_ff: |
| 118 | + shoulder_pan_joint: 1.0 |
| 119 | + shoulder_lift_joint: 1.0 |
| 120 | + elbow_joint: 1.0 |
| 121 | + wrist_1_joint: 1.0 |
| 122 | + wrist_2_joint: 1.0 |
| 123 | + wrist_3_joint: 1.0 |
| 124 | + stop_trajectory_duration: 0.5 |
| 125 | + state_publish_rate: *loop_hz |
| 126 | + action_monitor_rate: 20 |
| 127 | + |
| 128 | +# Pass an array of joint velocities directly to the joints |
| 129 | +joint_group_vel_controller: |
| 130 | + type: velocity_controllers/JointGroupVelocityController |
| 131 | + joints: *robot_joints |
| 132 | + |
| 133 | +robot_status_controller: |
| 134 | + type: industrial_robot_status_controller/IndustrialRobotStatusController |
| 135 | + handle_name: industrial_robot_status_handle |
| 136 | + publish_rate: 10 |
0 commit comments