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
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
:
:
:
...
"""
# Pose
The same position can be represented in different ways. Different description methods are uniformly expressed as the `Pose` object
同一个位置可以用不同的方式表示, 将不同的描述方式统一表述为 `Pose` 对象
## constructor 构造函数
```python
pose = Pose.Euler([x, y, z], [roll, pitch, yaw])
pose = Pose.Quat([x, y, z], [qx, qy, qz, qw])
pose = Pose.Homo(homo_array: list)
pose = Pose.AxisAngle([x, y, z], [axis_x, axis_y, axis_z], angle)
pose = Pose.Position([x, y, z])
```
## methods 方法
```python
(tran, rot) = pose.euler()
(tran, rot) = pose.quat()
(homo_array) = pose.homo()
(tran, axis, angle) = pose.axis_angle()
(tran) = pose.position()
```
"""
"""
Convert the pose into the Euler Angle expression 将位姿转化为欧拉角表述
```
([x, y, z], [roll, pitch, yaw])
```
Returns the Euler angles as a tuple of two lists: translation and rotation.
"""
...
"""
Convert the pose into the Quaternion expression 将位姿转化为四元数表述
```
([x, y, z], [qx, qy, qz, qw])
```
Returns the quaternion as a tuple of two lists: translation and rotation.
"""
...
"""
Convert the pose into the homogeneous representation 将位姿转化为齐次表示,这里并非其次变换矩阵,而是按列存储的列表
```
list[float]
```
Returns the homogeneous representation as a list.
"""
...
"""
Convert the pose into the Axis-Angle representation 将位姿转化为轴角表述
```
([x, y, z], [axis_x, axis_y, axis_z], angle)
```
Returns the axis-angle representation as a tuple of a list for translation, a list for the axis, and a float for the angle.
"""
...
"""
Convert the pose into the Position representation 将位姿转化为位置表示
```
[x, y, z]
```
Returns the position as a list.
"""
...
...
"""
# Robot
## methods(as `RobotBehavior`) 方法
"""
"""get the version of the robot 获取机器人版本号
Returns:
str: the version of the robot 机器人版本号
"""
...
"""initialize the robot 初始化机器人"""
...
"""shutdown the robot 关闭机器人"""
...
"""enable the robot 使能机器人"""
...
"""disable the robot 去使能机器人"""
...
"""reset the robot 复位机器人"""
...
"""check if robot is moving 检查机器人是否在运动中
Returns:
bool: check if robot is moving 是否在运动状态
"""
...
"""stop the current action 停止当前动作,不可恢复"""
...
"""pause the robot 运动暂停"""
...
"""resume the robot 运动恢复"""
...
"""emergency stop the robot 紧急停止机器人"""
...
"""clear emergency stop status 清除紧急停止状态"""
...
"""read the robot state 读取机器人状态
Returns:
RobotState: the robot state 机器人状态
"""
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
...
"""
Get the pose of the end effector in the base frame 获取末端执行器在基坐标系下的位姿
Returns:
Pose: the pose of the end effector in the base frame 末端执行器在基坐标系下的位姿
"""
...
"""
Get the pose of the end effector in the flange frame 获取末端执行器在法兰坐标系下的位姿
Returns:
Pose: the pose of the end effector in the flange frame 末端执行器在法兰坐标系下的位姿
"""
...
"""
Get the pose of the end effector in the kin frame 获取末端执行器在关节坐标系下的位姿
Returns:
Pose: the pose of the end effector in the kin frame 末端执行器在关节坐标系下的位姿
"""
...
"""
Get the cartesian velocity of the end effector 获取末端执行器在笛卡尔坐标系下的速度
Returns:
list[float]: the cartesian velocity of the end effector 末端执行器在笛卡尔坐标系下的速度
"""
...
"""
Get the load state of the end effector 获取末端执行器的负载状态
Returns:
LoadState: the load state of the end effector 末端执行器的负载状态
"""
...
...
# TODO rewrite the docstring with `python` style
"""
# Robot Arm
机械臂型机器人
## methods(as `ArmBehavior`) 方法
```
type State;
fn read_state(&mut self) -> RobotResult<Self::State>;
fn state(&mut self) -> RobotResult<ArmState<N>>;
fn set_load(&mut self, load: LoadState) -> RobotResult<()>;
```
## methods as `ArmPreplannedMotion`
```
fn move_to(&mut self, target: MotionType<N>, speed: f64) -> RobotResult<()>;
fn move_to_async(&mut self, target: MotionType<N>, speed: f64) -> RobotResult<()>;
fn move_rel(&mut self, rel: MotionType<N>, speed: f64) -> RobotResult<()>;
fn move_rel_async(&mut self, rel: MotionType<N>, speed: f64) -> RobotResult<()>;
fn move_path(&mut self, path: Vec<MotionType<N>>, speed: f64) -> RobotResult<()>;
fn control_with(&mut self, control: ControlType<N>) -> RobotResult<()>;
```
## methods as `ArmPreplannedMotionExt`
```
fn move_joint(&mut self, target: &[f64; N], speed: f64) -> RobotResult<()>;
fn move_joint_async(&mut self, target: &[f64; N], speed: f64) -> RobotResult<()>;
fn move_joint_rel(&mut self, target: &[f64; N], speed: f64) -> RobotResult<()>;
fn move_joint_rel_async(&mut self, target: &[f64; N], speed: f64) -> RobotResult<()>;
fn move_cartesian(&mut self, target: &Pose, speed: f64) -> RobotResult<()>;
fn move_cartesian_async(&mut self, target: &Pose, speed: f64) -> RobotResult<()>;
fn move_cartesian_rel(&mut self, target: &Pose, speed: f64) -> RobotResult<()>;
fn move_cartesian_rel_async(&mut self, target: &Pose, speed: f64) -> RobotResult<()>;
fn move_linear_with_euler(&mut self, tran: [f64; 3], rot: [f64; 3], speed: f64) -> RobotResult<()>;
fn move_linear_with_euler_async(&mut self, tran: [f64; 3], rot: [f64; 3], speed: f64) -> RobotResult<()>;
fn move_linear_with_homo(&mut self, target: &[f64; 16], speed: f64) -> RobotResult<()>;
fn move_linear_with_homo_async(&mut self, target: &[f64; 16], speed: f64) -> RobotResult<()>;
fn move_path_prepare(&mut self, _path: Vec<MotionType<N>>) -> RobotResult<()>;
fn move_path_start(&mut self) -> RobotResult<()>;
fn move_path_prepare_from_file(&mut self, path: &str) -> RobotResult<()>;
fn move_path_from_file(&mut self, path: &str, speed: f64) -> RobotResult<()>;
```
## methods as `ArmStreamingHandle`
```
type Handle: ArmStreamingHandle<N>;
fn start_streaming(&mut self) -> RobotResult<Self::Handle>;
fn end_streaming(&mut self) -> RobotResult<()>;
fn move_to_target(&mut self) -> Arc<Mutex<Option<MotionType<N>>>>;
fn control_to_target(&mut self) -> Arc<Mutex<Option<ControlType<N>>>>;
```
## methods as `ArmStreamingHandleExt`
```
fn move_joint_target(&mut self) -> Arc<Mutex<Option<[f64; N]>>>;
fn move_joint_vel_target(&mut self) -> Arc<Mutex<Option<[f64; N]>>>;
fn move_joint_acc_target(&mut self) -> Arc<Mutex<Option<[f64; N]>>>;
fn move_cartesian_target(&mut self) -> Arc<Mutex<Option<Pose>>>;
fn move_cartesian_vel_target(&mut self) -> Arc<Mutex<Option<[f64; 6]>>>;
fn move_cartesian_euler_target(&mut self) -> Arc<Mutex<Option<[f64; 6]>>>;
fn move_cartesian_quat_target(&mut self) -> Arc<Mutex<Option<na::Isometry3<f64>>>>;
fn move_cartesian_homo_target(&mut self) -> Arc<Mutex<Option<[f64; 16]>>>;
fn control_tau_target(&mut self) -> Arc<Mutex<Option<[f64; N]>>>;
```
## methods as `ArmRealtimeControl`
```
fn move_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> MotionType<N> + Send + 'static;
fn control_with_closure<FC>(&mut self, closure: FC) -> RobotResult<()>
where
FC: Fn(ArmState<N>, Duration) -> ControlType<N> + Send + 'static;
```
## methods as `ArmRealtimeControlExt`
```
fn move_joint_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> [f64; N] + Send + Sync + 'static;
fn move_joint_vel_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> [f64; N] + Send + Sync + 'static;
fn move_cartesian_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> Pose + Send + Sync + 'static;
fn move_cartesian_vel_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> [f64; 6] + Send + Sync + 'static;
fn move_cartesian_euler_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> ([f64; 3], [f64; 3]) + Send + Sync + 'static;
fn move_cartesian_quat_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> na::Isometry3<f64> + Send + Sync + 'static;
fn move_cartesian_homo_with_closure<FM>(&mut self, closure: FM) -> RobotResult<()>
where
FM: Fn(ArmState<N>, Duration) -> [f64; 16] + Send + Sync + 'static;
```
"""
...
...
...
...
...
...
...
...
...
...
"""以关节角度方式移动机器人
Args:
joint: 关节角度列表(长度必须为 HANS_DOF)
speed: 运动速度(0.0~1.0)
"""
...
"""以关节角度方式异步移动机器人
Args:
joint: 关节角度列表(长度必须为 HANS_DOF)
speed: 运动速度(0.0~1.0)
"""
...
"""以关节角度方式相对移动机器人
Args:
joint_rel: 相对关节角度列表(长度必须为 HANS_DOF)
speed: 运动速度(0.0~1.0)
"""
...
"""以关节角度方式异步相对移动机器人
Args:
joint_rel: 相对关节角度列表(长度必须为 HANS_DOF)
speed: 运动速度(0.0~1.0)
"""
...
"""以关节角度方式移动机器人
Args:
joints: 关节角度列表
speed: 运动速度(0.0~1.0)
"""
...
"""以笛卡尔坐标系移动机器人
Args:
pose: 位姿描述
speed: 运动速度(0.0~1.0)
"""
...
"""以笛卡尔坐标系异步移动机器人
Args:
pose: 位姿描述
speed: 运动速度(0.0~1.0)
"""
...
"""以笛卡尔坐标系相对移动机器人
Args:
pose_rel: 位姿描述
speed: 运动速度(0.0~1.0)
"""
...
"""以笛卡尔坐标系异步相对移动机器人
Args:
pose_rel: 位姿描述
speed: 运动速度(0.0~1.0)
"""
...
"""以笛卡尔坐标系移动机器人
Args:
poses: 位姿描述
speed: 运动速度(0.0~1.0)
"""
...
"""从文件中读取关节角度路径并执行
Args:
path: 文件路径
speed: 运动速度(0.0~1.0)
"""
...
...
...
"""
Get the last motion target 获取上一个运动目标
Returns:
MotionType: the last motion target 上一个运动目标
"""
...
"""
Set the control target 设置控制目标
Args:
control: 控制目标
"""
...
"""
Get the last control target 获取上一个控制目标
Returns:
ControlType: the last control target 上一个控制目标
"""
...
"""start streaming the robot state 开始流式运动机器人状态"""
...
"""end streaming the robot state 结束流式运动机器人状态"""
...
...
...
"""以闭包方式移动机器人
Args:
closure: 闭包函数,接受机器人状态和时间间隔,返回运动目标
"""
...
"""以闭包方式控制机器人
Args:
closure: 闭包函数,接受机器人状态和时间间隔,返回控制目标
"""
...
"""以闭包方式在位置环中移动机器人
Args:
closure: 闭包函数,接受机器人状态和时间间隔,返回关节角度列表(长度必须为 HANS_DOF)
"""
...
"""以闭包方式在速度环中移动机器人
Args:
closure: 闭包函数,接受机器人状态和时间间隔,返回关节角速度列表(长度必须为 HANS_DOF)
"""
"""以闭包方式在位置环中移动机器人
Args:
closure: 闭包函数,接受机器人状态和时间间隔,返回位姿描述
"""
...
"""以闭包方式在速度环中移动机器人
Args:
closure: 闭包函数,接受机器人状态和时间间隔,返回笛卡尔坐标系下的速度列表(长度必须为 6)
"""
...