-
Notifications
You must be signed in to change notification settings - Fork 324
Expand file tree
/
Copy pathur_controllers.yaml
More file actions
224 lines (188 loc) · 6.95 KB
/
ur_controllers.yaml
File metadata and controls
224 lines (188 loc) · 6.95 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
controller_manager:
ros__parameters:
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
io_and_status_controller:
type: ur_controllers/GPIOController
speed_scaling_state_broadcaster:
type: ur_controllers/SpeedScalingStateBroadcaster
force_torque_sensor_broadcaster:
type: force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster
joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
scaled_joint_trajectory_controller:
type: ur_controllers/ScaledJointTrajectoryController
forward_velocity_controller:
type: forward_command_controller/ForwardCommandController
forward_effort_controller:
type: forward_command_controller/ForwardCommandController
forward_position_controller:
type: forward_command_controller/ForwardCommandController
force_mode_controller:
type: ur_controllers/ForceModeController
freedrive_mode_controller:
type: ur_controllers/FreedriveModeController
passthrough_trajectory_controller:
type: ur_controllers/PassthroughTrajectoryController
tcp_pose_broadcaster:
type: pose_broadcaster/PoseBroadcaster
ur_configuration_controller:
type: ur_controllers/URConfigurationController
tool_contact_controller:
type: ur_controllers/ToolContactController
gravity_update_controller:
type: ur_controllers/GravityUpdateController
# The way this is currently implemented upstream doesn't really work for us. When using
# position control, the robot will have a tracking error. However, limits will be enforced
# from the currently reported position, effectively limiting the possible step size using the
# joints' velocity limits. Until this is resolved, we will keep command limits non-enforced.
# Note: On Jazzy this is the default behavior, anyway. For Rolling / Kilted this defaults to
# true.
enforce_command_limits: false
motion_primitive_forward_controller:
type: motion_primitives_controllers/MotionPrimitivesForwardController
speed_scaling_state_broadcaster:
ros__parameters:
state_publish_rate: 100.0
tf_prefix: "$(var tf_prefix)"
io_and_status_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
ur_configuration_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
force_torque_sensor_broadcaster:
ros__parameters:
sensor_name: $(var tf_prefix)tcp_fts_sensor
state_interface_names:
- force.x
- force.y
- force.z
- torque.x
- torque.y
- torque.z
frame_id: $(var tf_prefix)tool0_controller
topic_name: ft_data
joint_trajectory_controller:
ros__parameters:
joints:
- $(var tf_prefix)shoulder_pan_joint
- $(var tf_prefix)shoulder_lift_joint
- $(var tf_prefix)elbow_joint
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.2
goal_time: 0.0
$(var tf_prefix)shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
$(var tf_prefix)shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
$(var tf_prefix)elbow_joint: {trajectory: 0.2, goal: 0.1}
$(var tf_prefix)wrist_1_joint: {trajectory: 0.2, goal: 0.1}
$(var tf_prefix)wrist_2_joint: {trajectory: 0.2, goal: 0.1}
$(var tf_prefix)wrist_3_joint: {trajectory: 0.2, goal: 0.1}
speed_scaling:
state_interface: $(var tf_prefix)speed_scaling/speed_scaling_factor
# Setting the command interface currently would clash with the io_and_status_controller
# This will probably be changed in the future.
# command_interface: $(var tf_prefix)speed_scaling/target_speed_fraction_cmd
scaled_joint_trajectory_controller:
ros__parameters:
joints:
- $(var tf_prefix)shoulder_pan_joint
- $(var tf_prefix)shoulder_lift_joint
- $(var tf_prefix)elbow_joint
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint
command_interfaces:
- position
state_interfaces:
- position
- velocity
state_publish_rate: 100.0
action_monitor_rate: 20.0
allow_partial_joints_goal: false
constraints:
stopped_velocity_tolerance: 0.2
goal_time: 0.0
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
passthrough_trajectory_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
joints:
- $(var tf_prefix)shoulder_pan_joint
- $(var tf_prefix)shoulder_lift_joint
- $(var tf_prefix)elbow_joint
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint
state_interfaces:
- position
- velocity
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
forward_velocity_controller:
ros__parameters:
joints:
- $(var tf_prefix)shoulder_pan_joint
- $(var tf_prefix)shoulder_lift_joint
- $(var tf_prefix)elbow_joint
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint
interface_name: velocity
forward_effort_controller:
ros__parameters:
joints:
- $(var tf_prefix)shoulder_pan_joint
- $(var tf_prefix)shoulder_lift_joint
- $(var tf_prefix)elbow_joint
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint
interface_name: effort
forward_position_controller:
ros__parameters:
joints:
- $(var tf_prefix)shoulder_pan_joint
- $(var tf_prefix)shoulder_lift_joint
- $(var tf_prefix)elbow_joint
- $(var tf_prefix)wrist_1_joint
- $(var tf_prefix)wrist_2_joint
- $(var tf_prefix)wrist_3_joint
interface_name: position
force_mode_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
freedrive_mode_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
tcp_pose_broadcaster:
ros__parameters:
frame_id: $(var tf_prefix)base
pose_name: $(var tf_prefix)tcp_pose
tf:
child_frame_id: $(var tf_prefix)tool0_controller
tool_contact_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
motion_primitive_forward_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"
gravity_update_controller:
ros__parameters:
tf_prefix: "$(var tf_prefix)"