|
| 1 | +controller_manager: |
| 2 | + ros__parameters: |
| 3 | + joint_state_broadcaster: |
| 4 | + type: joint_state_broadcaster/JointStateBroadcaster |
| 5 | + |
| 6 | + alice_io_and_status_controller: |
| 7 | + type: ur_controllers/GPIOController |
| 8 | + |
| 9 | + bob_io_and_status_controller: |
| 10 | + type: ur_controllers/GPIOController |
| 11 | + |
| 12 | + alice_speed_scaling_state_broadcaster: |
| 13 | + type: ur_controllers/SpeedScalingStateBroadcaster |
| 14 | + |
| 15 | + bob_speed_scaling_state_broadcaster: |
| 16 | + type: ur_controllers/SpeedScalingStateBroadcaster |
| 17 | + |
| 18 | + alice_force_torque_sensor_broadcaster: |
| 19 | + type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster |
| 20 | + |
| 21 | + bob_force_torque_sensor_broadcaster: |
| 22 | + type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster |
| 23 | + |
| 24 | + alice_joint_trajectory_controller: |
| 25 | + type: joint_trajectory_controller/JointTrajectoryController |
| 26 | + |
| 27 | + bob_trajectory_controller: |
| 28 | + type: joint_trajectory_controller/JointTrajectoryController |
| 29 | + |
| 30 | + alice_scaled_joint_trajectory_controller: |
| 31 | + type: ur_controllers/ScaledJointTrajectoryController |
| 32 | + |
| 33 | + bob_scaled_joint_trajectory_controller: |
| 34 | + type: ur_controllers/ScaledJointTrajectoryController |
| 35 | + |
| 36 | + forward_velocity_controller: |
| 37 | + type: velocity_controllers/JointGroupVelocityController |
| 38 | + |
| 39 | + alice_forward_position_controller: |
| 40 | + type: position_controllers/JointGroupPositionController |
| 41 | + |
| 42 | + bob_forward_position_controller: |
| 43 | + type: position_controllers/JointGroupPositionController |
| 44 | + |
| 45 | + |
| 46 | +alice_speed_scaling_state_broadcaster: |
| 47 | + ros__parameters: |
| 48 | + state_publish_rate: 100.0 |
| 49 | + tf_prefix: "alice_" |
| 50 | + |
| 51 | +bob_speed_scaling_state_broadcaster: |
| 52 | + ros__parameters: |
| 53 | + state_publish_rate: 100.0 |
| 54 | + tf_prefix: "bob_" |
| 55 | + |
| 56 | +alice_io_and_status_controller: |
| 57 | + ros__parameters: |
| 58 | + tf_prefix: "alice_" |
| 59 | + |
| 60 | +bob_io_and_status_controller: |
| 61 | + ros__parameters: |
| 62 | + tf_prefix: "bob_" |
| 63 | + |
| 64 | +alice_force_torque_sensor_broadcaster: |
| 65 | + ros__parameters: |
| 66 | + sensor_name: alice_tcp_fts_sensor |
| 67 | + state_interface_names: |
| 68 | + - force.x |
| 69 | + - force.y |
| 70 | + - force.z |
| 71 | + - torque.x |
| 72 | + - torque.y |
| 73 | + - torque.z |
| 74 | + frame_id: bob_tool0 |
| 75 | + topic_name: alice_ft_data |
| 76 | + |
| 77 | +bob_force_torque_sensor_broadcaster: |
| 78 | + ros__parameters: |
| 79 | + sensor_name: bob_tcp_fts_sensor |
| 80 | + state_interface_names: |
| 81 | + - force.x |
| 82 | + - force.y |
| 83 | + - force.z |
| 84 | + - torque.x |
| 85 | + - torque.y |
| 86 | + - torque.z |
| 87 | + frame_id: bob_tool0 |
| 88 | + topic_name: bob_ft_data |
| 89 | + |
| 90 | + |
| 91 | +alice_joint_trajectory_controller: |
| 92 | + ros__parameters: |
| 93 | + joints: |
| 94 | + - alice_shoulder_pan_joint |
| 95 | + - alice_shoulder_lift_joint |
| 96 | + - alice_elbow_joint |
| 97 | + - alice_wrist_1_joint |
| 98 | + - alice_wrist_2_joint |
| 99 | + - alice_wrist_3_joint |
| 100 | + command_interfaces: |
| 101 | + - position |
| 102 | + state_interfaces: |
| 103 | + - position |
| 104 | + - velocity |
| 105 | + state_publish_rate: 100.0 |
| 106 | + action_monitor_rate: 20.0 |
| 107 | + allow_partial_joints_goal: false |
| 108 | + constraints: |
| 109 | + stopped_velocity_tolerance: 0.2 |
| 110 | + goal_time: 0.0 |
| 111 | + alice_shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 } |
| 112 | + alice_shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 } |
| 113 | + alice_elbow_joint: { trajectory: 0.2, goal: 0.1 } |
| 114 | + alice_wrist_1_joint: { trajectory: 0.2, goal: 0.1 } |
| 115 | + alice_wrist_2_joint: { trajectory: 0.2, goal: 0.1 } |
| 116 | + alice_wrist_3_joint: { trajectory: 0.2, goal: 0.1 } |
| 117 | + |
| 118 | +bob_joint_trajectory_controller: |
| 119 | + ros__parameters: |
| 120 | + joints: |
| 121 | + - bob_shoulder_pan_joint |
| 122 | + - bob_shoulder_lift_joint |
| 123 | + - bob_elbow_joint |
| 124 | + - bob_wrist_1_joint |
| 125 | + - bob_wrist_2_joint |
| 126 | + - bob_wrist_3_joint |
| 127 | + command_interfaces: |
| 128 | + - position |
| 129 | + state_interfaces: |
| 130 | + - position |
| 131 | + - velocity |
| 132 | + state_publish_rate: 100.0 |
| 133 | + action_monitor_rate: 20.0 |
| 134 | + allow_partial_joints_goal: false |
| 135 | + constraints: |
| 136 | + stopped_velocity_tolerance: 0.2 |
| 137 | + goal_time: 0.0 |
| 138 | + bob_shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 } |
| 139 | + bob_shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 } |
| 140 | + bob_elbow_joint: { trajectory: 0.2, goal: 0.1 } |
| 141 | + bob_wrist_1_joint: { trajectory: 0.2, goal: 0.1 } |
| 142 | + bob_wrist_2_joint: { trajectory: 0.2, goal: 0.1 } |
| 143 | + bob_wrist_3_joint: { trajectory: 0.2, goal: 0.1 } |
| 144 | + |
| 145 | +alice_scaled_joint_trajectory_controller: |
| 146 | + ros__parameters: |
| 147 | + joints: |
| 148 | + - alice_shoulder_pan_joint |
| 149 | + - alice_shoulder_lift_joint |
| 150 | + - alice_elbow_joint |
| 151 | + - alice_wrist_1_joint |
| 152 | + - alice_wrist_2_joint |
| 153 | + - alice_wrist_3_joint |
| 154 | + command_interfaces: |
| 155 | + - position |
| 156 | + state_interfaces: |
| 157 | + - position |
| 158 | + - velocity |
| 159 | + state_publish_rate: 100.0 |
| 160 | + action_monitor_rate: 20.0 |
| 161 | + allow_partial_joints_goal: false |
| 162 | + constraints: |
| 163 | + stopped_velocity_tolerance: 0.2 |
| 164 | + goal_time: 0.0 |
| 165 | + alice_shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 } |
| 166 | + alice_shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 } |
| 167 | + alice_elbow_joint: { trajectory: 0.2, goal: 0.1 } |
| 168 | + alice_wrist_1_joint: { trajectory: 0.2, goal: 0.1 } |
| 169 | + alice_wrist_2_joint: { trajectory: 0.2, goal: 0.1 } |
| 170 | + alice_wrist_3_joint: { trajectory: 0.2, goal: 0.1 } |
| 171 | + speed_scaling_interface_name: alice_speed_scaling/speed_scaling_factor |
| 172 | + |
| 173 | +bob_scaled_joint_trajectory_controller: |
| 174 | + ros__parameters: |
| 175 | + joints: |
| 176 | + - bob_shoulder_pan_joint |
| 177 | + - bob_shoulder_lift_joint |
| 178 | + - bob_elbow_joint |
| 179 | + - bob_wrist_1_joint |
| 180 | + - bob_wrist_2_joint |
| 181 | + - bob_wrist_3_joint |
| 182 | + command_interfaces: |
| 183 | + - position |
| 184 | + state_interfaces: |
| 185 | + - position |
| 186 | + - velocity |
| 187 | + state_publish_rate: 100.0 |
| 188 | + action_monitor_rate: 20.0 |
| 189 | + allow_partial_joints_goal: false |
| 190 | + constraints: |
| 191 | + stopped_velocity_tolerance: 0.2 |
| 192 | + goal_time: 0.0 |
| 193 | + bob_shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 } |
| 194 | + bob_shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 } |
| 195 | + bob_elbow_joint: { trajectory: 0.2, goal: 0.1 } |
| 196 | + bob_wrist_1_joint: { trajectory: 0.2, goal: 0.1 } |
| 197 | + bob_wrist_2_joint: { trajectory: 0.2, goal: 0.1 } |
| 198 | + bob_wrist_3_joint: { trajectory: 0.2, goal: 0.1 } |
| 199 | + speed_scaling_interface_name: bob_speed_scaling/speed_scaling_factor |
| 200 | + |
| 201 | +alice_forward_velocity_controller: |
| 202 | + ros__parameters: |
| 203 | + joints: |
| 204 | + - alice_shoulder_pan_joint |
| 205 | + - alice_shoulder_lift_joint |
| 206 | + - alice_elbow_joint |
| 207 | + - alice_wrist_1_joint |
| 208 | + - alice_wrist_2_joint |
| 209 | + - alice_wrist_3_joint |
| 210 | + interface_name: velocity |
| 211 | + |
| 212 | +bob_forward_velocity_controller: |
| 213 | + ros__parameters: |
| 214 | + joints: |
| 215 | + - bob_shoulder_pan_joint |
| 216 | + - bob_shoulder_lift_joint |
| 217 | + - bob_elbow_joint |
| 218 | + - bob_wrist_1_joint |
| 219 | + - bob_wrist_2_joint |
| 220 | + - bob_wrist_3_joint |
| 221 | + interface_name: velocity |
| 222 | + |
| 223 | +alice_forward_position_controller: |
| 224 | + ros__parameters: |
| 225 | + joints: |
| 226 | + - alice_shoulder_pan_joint |
| 227 | + - alice_shoulder_lift_joint |
| 228 | + - alice_elbow_joint |
| 229 | + - alice_wrist_1_joint |
| 230 | + - alice_wrist_2_joint |
| 231 | + - alice_wrist_3_joint |
| 232 | + |
| 233 | +bob_forward_position_controller: |
| 234 | + ros__parameters: |
| 235 | + joints: |
| 236 | + - bob_shoulder_pan_joint |
| 237 | + - bob_shoulder_lift_joint |
| 238 | + - bob_elbow_joint |
| 239 | + - bob_wrist_1_joint |
| 240 | + - bob_wrist_2_joint |
| 241 | + - bob_wrist_3_joint |
0 commit comments