-
Notifications
You must be signed in to change notification settings - Fork 26
/
robot.yaml
218 lines (188 loc) · 4.84 KB
/
robot.yaml
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
controller_manager:
ros__parameters:
update_rate: 20 # Hz
head_controller:
type: joint_trajectory_controller/JointTrajectoryController
eyes_controller:
type: joint_trajectory_controller/JointTrajectoryController
forward_head_controller:
type: forward_command_controller/ForwardCommandController
jaw_controller:
type: joint_trajectory_controller/JointTrajectoryController
r_shoulder_controller:
type: joint_trajectory_controller/JointTrajectoryController
r_hand_controller:
type: joint_trajectory_controller/JointTrajectoryController
l_hand_controller:
type: joint_trajectory_controller/JointTrajectoryController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
# Set joint state broadcaster to push zero joint states to all other than movable joints
joint_state_broadcaster:
ros__parameters:
extra_joints:
- head_roll_joint
- head_tilt_joint
- waist_pan_joint
- waist_roll_joint
#- r_shoulder_lift_joint
- r_upper_arm_roll_joint
- r_elbow_flex_joint
#- r_shoulder_out_joint
- r_thumb1_joint
#- r_thumb_joint
- r_thumb3_joint
#- r_index1_joint
- r_index_joint
- r_index3_joint
#- r_middle1_joint
- r_middle_joint
- r_middle3_joint
- r_ring1_joint
#- r_ring_joint
- r_ring3_joint
- r_ring4_joint
- r_pinky1_joint
#- r_pinky_joint
- r_pinky3_joint
- r_pinky4_joint
- r_wrist_roll_joint
- l_shoulder_lift_joint
- l_upper_arm_roll_joint
- l_elbow_flex_joint
- l_shoulder_out_joint
- l_thumb1_joint
#- l_thumb_joint
- l_thumb3_joint
#- l_index1_joint
- l_index_joint
- l_index3_joint
#- l_middle1_joint
- l_middle_joint
- l_middle3_joint
- l_ring1_joint
#- l_ring_joint
- l_ring3_joint
- l_ring4_joint
- l_pinky1_joint
#- l_pinky_joint
- l_pinky3_joint
- l_pinky4_joint
- l_wrist_roll_joint
r_hand_controller:
ros__parameters:
joints:
- r_thumb_joint
- r_index1_joint
- r_middle1_joint
- r_ring_joint
- r_pinky_joint
write_op_modes:
- r_thumb_joint
- r_index_joint
- r_middle_joint
- r_ring_joint
- r_pinky_joint
allow_partial_joints_goal: true
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 20.0 # Defaults to 50
action_monitor_rate: 20.0 # Defaults to 20
l_hand_controller:
ros__parameters:
joints:
- l_thumb_joint
- l_index1_joint
- l_middle1_joint
- l_ring_joint
- l_pinky_joint
write_op_modes:
- l_thumb_joint
- l_index_joint
- l_middle_joint
- l_ring_joint
- l_pinky_joint
allow_partial_joints_goal: true
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 20.0 # Defaults to 50
action_monitor_rate: 20.0 # Defaults to 20
head_controller:
ros__parameters:
joints:
- head_pan_joint
- head_tilt_right_joint
- head_tilt_left_joint
- head_tilt_vertical_joint
write_op_modes:
- head_pan_joint
- head_tilt_right_joint
- head_tilt_left_joint
- head_tilt_vertical_joint
allow_partial_joints_goal: true
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 20.0 # Defaults to 50
action_monitor_rate: 5.0 # Defaults to 20
eyes_controller:
ros__parameters:
joints:
- eyes_shift_horizontal_joint
- eyes_shift_vertical_joint
write_op_modes:
- eyes_shift_horizontal_joint
- eyes_shift_vertical_joint
allow_partial_joints_goal: true
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 20.0 # Defaults to 50
action_monitor_rate: 20.0 # Defaults to 20
#forward_head_controller:
# ros__parameters:
# joints:
# - head_pan_joint
# - head_tilt_right_joint
# - head_tilt_left_joint
# - head_tilt_vertical_joint
# interface_name: position
jaw_controller:
ros__parameters:
joints:
- head_jaw_joint
write_op_modes:
- head_jaw_joint
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 5.0 # Defaults to 50
action_monitor_rate: 20.0 # Defaults to 20
r_shoulder_controller:
ros__parameters:
joints:
- r_shoulder_lift_joint
- r_shoulder_out_joint
write_op_modes:
- r_shoulder_lift_joint
- r_shoulder_out
allow_partial_joints_goal: true
interface_name: position
command_interfaces:
- position
state_interfaces:
- position
state_publish_rate: 20.0 # Defaults to 50
action_monitor_rate: 20.0 # Defaults to 20