ARCS SDK API  0.25.0
载入中...
搜索中...
未找到
motion_control.h
浏览该文件的文档.
1/** @file motion_control.h
2 * @brief 运动控制接口
3 *
4 * The robot movements are programmed as pose-to-pose movements, that is move
5 * from the current position to a new position. The path between these two
6 * positions is then automatically calculated by the robot.
7 */
8#ifndef AUBO_SDK_MOTION_CONTROL_INTERFACE_H
9#define AUBO_SDK_MOTION_CONTROL_INTERFACE_H
10
11#include <vector>
12#include <functional>
13#include <thread>
14
15#include <aubo/global_config.h>
16#include <aubo/type_def.h>
17
18namespace arcs {
19namespace common_interface {
20
21/**
22 * pathBuffer类型
23 */
25{
26 PathBuffer_TOPPRA = 1, ///< 1: toppra 时间最优路径规划
27 PathBuffer_CubicSpline = 2, ///< 2: cubic_spline(录制的轨迹)
28
29 /// 3: 关节B样条插值,最少三个点
30 /// 废弃,建议用5替代,现在实际是关节空间 CUBIC_SPLINE
32
33 /// 4:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
34 /// 废弃,建议用6替代,现在实际是关节空间 CUBIC_SPLINE
36
37 ///< 5: 关节B样条插值,最少三个点
39
40 /// 6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
42};
43
44/**
45 * MotionControl类
46 */
47class ARCS_ABI_EXPORT MotionControl
48{
49public:
51 virtual ~MotionControl();
52
53 /**
54 * 获取等效半径,单位 m
55 * moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动
56 * 可以通过 setEqradius 设置,默认为1
57 *
58 * @return 返回等效半径
59 *
60 * @throws arcs::common_interface::AuboException
61 *
62 * @par Python函数原型
63 * getEqradius(self: pyaubo_sdk.MotionControl) -> float
64 *
65 * @par Lua函数原型
66 * getEqradius() -> number
67 *
68 * @par JSON-RPC请求示例
69 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getEqradius","params":[],"id":1}
70 *
71 * @par JSON-RPC响应示例
72 * {"id":1,"jsonrpc":"2.0","result":1.0}
73 *
74 */
75 double getEqradius();
76
77 /**
78 * 设置等效半径,单位 m
79 * moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
80 *
81 * @param eqradius 0表示只规划移动,姿态旋转跟随移动
82 *
83 * @return 成功返回0; 失败返回错误码
84 * AUBO_BAD_STATE
85 * AUBO_BUSY
86 * -AUBO_INVL_ARGUMENT
87 * -AUBO_BAD_STATE
88 *
89 * @throws arcs::common_interface::AuboException
90 *
91 * @par JSON-RPC请求示例
92 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setEqradius","params":[0.8],"id":1}
93 *
94 * @par JSON-RPC响应示例
95 * {"id":1,"jsonrpc":"2.0","result":0}
96 *
97 * @par Python函数原型
98 * setEqradius(self: pyaubo_sdk.MotionControl, arg0: float) -> int
99 *
100 * @par Lua函数原型
101 * setEqradius(eqradius: number) -> number
102 */
103 int setEqradius(double eqradius);
104
105 /**
106 * 动态调整机器人运行速度和加速度比例 (0., 1.]
107 *
108 * @param fraction 机器人运行速度和加速度比例
109 * @return 成功返回0; 失败返回错误码
110 * AUBO_INVL_ARGUMENT
111 * AUBO_BUSY
112 * AUBO_BAD_STATE
113 * -AUBO_INVL_ARGUMENT
114 * -AUBO_BAD_STATE
115 *
116 * @throws arcs::common_interface::AuboException
117 *
118 * @par Python函数原型
119 * setSpeedFraction(self: pyaubo_sdk.MotionControl, arg0: float) -> int
120 *
121 * @par Lua函数原型
122 * setSpeedFraction(fraction: number) -> nil
123 *
124 * @par JSON-RPC请求示例
125 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setSpeedFraction","params":[0.8],"id":1}
126 *
127 * @par JSON-RPC响应示例
128 * {"id":1,"jsonrpc":"2.0","result":0}
129 *
130 */
131 int setSpeedFraction(double fraction);
132
133 /**
134 * 获取速度和加速度比例,默认为 1
135 * 可以通过 setSpeedFraction 接口设置
136 *
137 * @return 返回速度和加速度比例
138 *
139 * @throws arcs::common_interface::AuboException
140 *
141 * @par Python函数原型
142 * getSpeedFraction(self: pyaubo_sdk.MotionControl) -> float
143 *
144 * @par Lua函数原型
145 * getSpeedFraction() -> number
146 *
147 * @par JSON-RPC请求示例
148 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getSpeedFraction","params":[],"id":1}
149 *
150 * @par JSON-RPC响应示例
151 * {"id":1,"jsonrpc":"2.0","result":1.0}
152 *
153 */
155
156 /**
157 * 速度比例设置临界区,使能之后速度比例被强制设定为1. ,
158 * 失能之后恢复之前的速度比例
159 *
160 * @param enable
161 * @return 成功返回0; 失败返回错误码
162 * AUBO_BAD_STATE
163 * AUBO_BUSY
164 * -AUBO_BAD_STATE
165 *
166 * @throws arcs::common_interface::AuboException
167 *
168 * @par JSON-RPC请求示例
169 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical","params":[true],"id":1}
170 *
171 * @par JSON-RPC响应示例
172 * {"id":1,"jsonrpc":"2.0","result":0}
173 *
174 */
175 int speedFractionCritical(bool enable);
176
177 /**
178 * 是否处于速度比例设置临界区
179 *
180 * @return 处于速度比例设置临界区返回 true; 反之返回 false
181 *
182 * @throws arcs::common_interface::AuboException
183 *
184 * @par JSON-RPC请求示例
185 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isSpeedFractionCritical","params":[],"id":1}
186 *
187 * @par JSON-RPC响应示例
188 * {"id":1,"jsonrpc":"2.0","result":true}
189 *
190 */
192
193 /**
194 * 是否处交融区
195 *
196 * @return 处交融区返回 true; 反之返回 false
197 *
198 * @throws arcs::common_interface::AuboException
199 *
200 * @par JSON-RPC请求示例
201 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isBlending","params":[],"id":1}
202 *
203 * @par JSON-RPC响应示例
204 * {"id":1,"jsonrpc":"2.0","result":false}
205 *
206 */
208
209 /**
210 * 设置偏移的最大速度和最大加速度
211 * 仅对pathOffsetSet中 type=1 有效
212 * @param v 最大速度
213 * @param a 最大加速度
214 * @return 成功返回0;失败返回错误码
215 * AUBO_BUSY
216 * AUBO_BAD_STATE
217 * -AUBO_INVL_ARGUMENT
218 * -AUBO_BAD_STATE
219 *
220 * @throws arcs::common_interface::AuboException
221 *
222 * @par Python函数原型
223 * pathOffsetLimits(self: pyaubo_sdk.MotionControl, arg0: float, arg1:
224 * float)
225 * -> int
226 *
227 * @par Lua函数原型
228 * pathOffsetLimits(v: number, a: number) -> nil
229 *
230 */
231 int pathOffsetLimits(double v, double a);
232
233 /**
234 * 设置偏移的参考坐标系
235 * 仅对pathOffsetSet中 type=1 有效
236 * @param ref_coord 参考坐标系 0-基坐标系 1-TCP
237 *
238 * @throws arcs::common_interface::AuboException
239 *
240 * @par Python函数原型
241 * pathOffsetCoordinate(self: pyaubo_sdk.MotionControl, arg0: int) -> float
242 *
243 * @par Lua函数原型
244 * pathOffsetCoordinate(ref_coord: number) -> number
245 *
246 * @par JSON-RPC请求示例
247 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetCoordinate","params":[0],"id":1}
248 *
249 * @par JSON-RPC响应示例
250 * {"id":1,"jsonrpc":"2.0","result":0}
251 *
252 */
253 int pathOffsetCoordinate(int ref_coord);
254
255 /**
256 * 路径偏移使能
257 *
258 * @return 成功返回0; 失败返回错误码
259 * AUBO_BUSY
260 * AUBO_BAD_STATE
261 * -AUBO_BAD_STATE
262 *
263 * @throws arcs::common_interface::AuboException
264 *
265 * @par Python函数原型
266 * pathOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
267 *
268 * @par Lua函数原型
269 * pathOffsetEnable() -> number
270 *
271 * @par JSON-RPC请求示例
272 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetEnable","params":[],"id":1}
273 *
274 * @par JSON-RPC响应示例
275 * {"id":1,"jsonrpc":"2.0","result":0}
276 *
277 */
279
280 /**
281 * 设置路径偏移
282 *
283 * @param offset 在各方向的位姿偏移
284 * @param type 运动类型 0-位置规划 1-速度规划
285 * @return 成功返回0; 失败返回错误码
286 * AUBO_BAD_STATE
287 * AUBO_BUSY
288 * -AUBO_INVL_ARGUMENT
289 * -AUBO_BAD_STATE
290 *
291 * @throws arcs::common_interface::AuboException
292 *
293 * @par Python函数原型
294 * pathOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
295 * int) -> int
296 *
297 * @par Lua函数原型
298 * pathOffsetSet(offset: table, type: number) -> nil
299 *
300 * @par JSON-RPC请求示例
301 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetSet","params":[[0,0,0.01,0,0,0],0],"id":1}
302 *
303 * @par JSON-RPC响应示例
304 * {"id":1,"jsonrpc":"2.0","result":0}
305 *
306 */
307 int pathOffsetSet(const std::vector<double> &offset, int type = 0);
308
309 /**
310 * 路径偏移失能
311 *
312 * @return 成功返回0; 失败返回错误码
313 * AUBO_BAD_STATE
314 * AUBO_BUSY
315 * -AUBO_BAD_STATE
316 *
317 * @throws arcs::common_interface::AuboException
318 *
319 * @par Python函数原型
320 * pathOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
321 *
322 * @par Lua函数原型
323 * pathOffsetDisable() -> nil
324 *
325 * @par JSON-RPC请求示例
326 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetDisable","params":[],"id":1}
327 *
328 * @par JSON-RPC响应示例
329 * {"id":1,"jsonrpc":"2.0","result":0}
330 *
331 */
333
334 /**
335 * @brief 监控轨迹偏移范围
336 * @param min: 沿坐标轴负方向最大偏移量
337 * @param max: 沿坐标轴负正方向最大偏移量
338 * @param strategy: 达到最大偏移量后监控策略
339 *     0-禁用监控
340 *     1-饱和限制,即维持最大姿态
341 *     2-保护停止
342 * @return
343 *
344 * @throws arcs::common_interface::AuboException
345 *
346 * @par Python函数原型
347 * pathOffsetSupv(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
348 * List[float], arg2: int) -> int
349 *
350 * @par Lua函数原型
351 * pathOffsetSupv(min: table, max: table, strategy: number) -> number
352 */
353 int pathOffsetSupv(const std::vector<double> &min,
354 const std::vector<double> &max, int strategy);
355
356 /**
357 * 关节偏移使能
358 *
359 * @return 成功返回0; 失败返回错误码
360 * AUBO_BAD_STATE
361 * AUBO_BUSY
362 * -AUBO_BAD_STATE
363 *
364 * @throws arcs::common_interface::AuboException
365 *
366 * @par Python函数原型
367 * jointOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
368 *
369 * @par Lua函数原型
370 * jointOffsetEnable() -> nil
371 *
372 * @par JSON-RPC请求示例
373 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetEnable","params":[],"id":1}
374 *
375 * @par JSON-RPC响应示例
376 * {"id":1,"jsonrpc":"2.0","result":0}
377 *
378 */
380
381 /**
382 * 设置关节偏移
383 *
384 * @param offset 在各关节的位姿偏移
385 * @param type
386 * @return 成功返回0; 失败返回错误码
387 * AUBO_BAD_STATE
388 * AUBO_BUSY
389 * -AUBO_INVL_ARGUMENT
390 * -AUBO_BAD_STATE
391 *
392 * @throws arcs::common_interface::AuboException
393 *
394 * @par Python函数原型
395 * jointOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
396 * int) -> int
397 *
398 * @par Lua函数原型
399 * jointOffsetSet(offset: table, type: number) -> nil
400 *
401 * @par JSON-RPC请求示例
402 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetSet","params":[[0.1,0,0,0,0],1],"id":1}
403 *
404 * @par JSON-RPC响应示例
405 * {"id":1,"jsonrpc":"2.0","result":0}
406 *
407 */
408 int jointOffsetSet(const std::vector<double> &offset, int type = 1);
409
410 /**
411 * 关节偏移失能
412 *
413 * @return 成功返回0; 失败返回错误码
414 * AUBO_BAD_STATE
415 * AUBO_BUSY
416 * -AUBO_BAD_STATE
417 *
418 * @throws arcs::common_interface::AuboException
419 *
420 * @par Python函数原型
421 * jointOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
422 *
423 * @par Lua函数原型
424 * jointOffsetDisable() -> nil
425 *
426 * @par JSON-RPC请求示例
427 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetDisable","params":[],"id":1}
428 *
429 * @par JSON-RPC响应示例
430 * {"id":1,"jsonrpc":"2.0","result":0}
431 *
432 */
434
435 /**
436 * 获取已经入队的指令段(INST)数量,运动指令包括
437 * moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令
438 *
439 * 指令一般会在接口宏定义里面用 _INST 指示, 比如 moveJoint
440 * _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration)
441 *
442 * @return 已经入队的指令段数量
443 *
444 * @throws arcs::common_interface::AuboException
445 *
446 * @par Python函数原型
447 * getQueueSize(self: pyaubo_sdk.MotionControl) -> int
448 *
449 * @par Lua函数原型
450 * getQueueSize() -> number
451 *
452 * @par JSON-RPC请求示例
453 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getQueueSize","params":[],"id":1}
454 *
455 * @par JSON-RPC响应示例
456 * {"id":1,"jsonrpc":"2.0","result":0}
457 *
458 */
460
461 /**
462 * 获取已经入队的运动规划插补点数量
463 *
464 * @return 已经入队的运动规划插补点数量
465 *
466 * @throws arcs::common_interface::AuboException
467 *
468 * @par Python函数原型
469 * getTrajectoryQueueSize(self: pyaubo_sdk.MotionControl) -> int
470 *
471 * @par Lua函数原型
472 * getTrajectoryQueueSize() -> number
473 *
474 * @par JSON-RPC请求示例
475 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getTrajectoryQueueSize","params":[],"id":1}
476 *
477 * @par JSON-RPC响应示例
478 * {"id":1,"jsonrpc":"2.0","result":0}
479 *
480 */
482
483 /**
484 * 获取当前正在插补的运动指令段的ID
485 *
486 * @return 当前正在插补的运动指令段的ID
487 * @retval -1 表示轨迹队列为空 \n
488 * 像movePathBuffer运动中的buffer或者规划器(moveJoint和moveLine等)里的队列都属于轨迹队列
489 *
490 * @throws arcs::common_interface::AuboException
491 *
492 * @par Python函数原型
493 * getExecId(self: pyaubo_sdk.MotionControl) -> int
494 *
495 * @par Lua函数原型
496 * getExecId() -> number
497 *
498 * @par JSON-RPC请求示例
499 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getExecId","params":[],"id":1}
500 *
501 * @par JSON-RPC响应示例
502 * {"id":1,"jsonrpc":"2.0","result":-1}
503 *
504 */
506
507 /**
508 * 获取指定ID的运动指令段的预期执行时间
509 *
510 * @param id 运动指令段ID
511 * @return 返回预期执行时间
512 *
513 * @throws arcs::common_interface::AuboException
514 *
515 * @par Python函数原型
516 * getDuration(self: pyaubo_sdk.MotionControl, arg0: int) -> float
517 *
518 * @par Lua函数原型
519 * getDuration(id: number) -> number
520 *
521 * @par JSON-RPC请求示例
522 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getDuration","params":[16],"id":1}
523 *
524 * @par JSON-RPC响应示例
525 * {"id":1,"jsonrpc":"2.0","result":0.0}
526 *
527 */
528 double getDuration(int id);
529
530 /**
531 * 获取指定ID的运动指令段的剩余执行时间
532 *
533 * @param id 运动指令段ID
534 * @return 返回剩余执行时间
535 *
536 * @throws arcs::common_interface::AuboException
537 *
538 * @par Python函数原型
539 * getMotionLeftTime(self: pyaubo_sdk.MotionControl, arg0: int) -> float
540 *
541 * @par Lua函数原型
542 * getMotionLeftTime(id: number) -> number
543 *
544 * @par JSON-RPC请求示例
545 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getMotionLeftTime","params":[16],"id":1}
546 *
547 * @par JSON-RPC响应示例
548 * {"id":1,"jsonrpc":"2.0","result":0.0}
549 *
550 */
551 double getMotionLeftTime(int id);
552
553 /**
554 * StopMove is used to stop robot and external axes movements and any
555 * belonging process temporarily. If the instruction StartMove is given then
556 * the movement and process resumes.
557 *
558 * This instruction can, for example, be used in a trap routine to stop the
559 * robot temporarily when an interrupt occurs.
560 *
561 * @param quick true: Stops the robot on the path as fast as possible.
562 * Without the optional parameter \Quick, the robot stops on the path, but
563 * the braking distance is longer (same as for normal Program Stop).
564 *
565 * @return 成功返回0; 失败返回错误码
566 * AUBO_BAD_STATE
567 * AUBO_BUSY
568 * -AUBO_BAD_STATE
569 *
570 * @throws arcs::common_interface::AuboException
571 *
572 */
573 int stopMove(bool quick, bool all_tasks);
574
575 /**
576 * StartMove is used to resume robot, external axes movement and belonging
577 * process after the movement has been stopped
578 *
579 * • by the instruction StopMove.
580 * • after execution of StorePath ... RestoPath sequence.
581 * • after asynchronously raised movements errors, such as ERR_PATH_STOP or
582 * specific process error after handling in the ERROR handler.
583 *
584 * @return 成功返回0; 失败返回错误码
585 * AUBO_BAD_STATE
586 * AUBO_BUSY
587 * -AUBO_BAD_STATE
588 *
589 * @throws arcs::common_interface::AuboException
590 *
591 * @par JSON-RPC请求示例
592 * {"jsonrpc":"2.0","method":"rob1.MotionControl.startMove","params":[],"id":1}
593 *
594 * @par JSON-RPC响应示例
595 * {"id":1,"jsonrpc":"2.0","result":0}
596 *
597 */
599
600 /**
601 * storePath
602 *
603 * @param keep_sync
604 * @return 成功返回0; 失败返回错误码
605 * AUBO_BAD_STATE
606 * AUBO_BUSY
607 * -AUBO_BAD_STATE
608 *
609 * @throws arcs::common_interface::AuboException
610 *
611 */
612 int storePath(bool keep_sync);
613
614 /**
615 * ClearPath (Clear Path) clears the whole motion path on the current motion
616 * path level (base level or StorePath level).
617 *
618 * @return 成功返回0; 失败返回错误码
619 * AUBO_BAD_STATE
620 * AUBO_BUSY
621 * -AUBO_BAD_STATE
622 *
623 * @throws arcs::common_interface::AuboException
624 *
625 * @par JSON-RPC请求示例
626 * {"jsonrpc":"2.0","method":"rob1.MotionControl.clearPath","params":[],"id":1}
627 *
628 * @par JSON-RPC响应示例
629 * {"id":1,"jsonrpc":"2.0","result":0}
630 *
631 */
633
634 /**
635 * restoPath
636 *
637 * @return 成功返回0; 失败返回错误码
638 * AUBO_BAD_STATE
639 * AUBO_BUSY
640 * -AUBO_BAD_STATE
641 *
642 * @throws arcs::common_interface::AuboException
643 *
644 * @par JSON-RPC请求示例
645 * {"jsonrpc":"2.0","method":"rob1.MotionControl.restoPath","params":[],"id":1}
646 *
647 * @par JSON-RPC响应示例
648 * {"id":1,"jsonrpc":"2.0","result":0}
649 *
650 */
652
653 /**
654 * 获取当前运动指令段的执行进度
655 *
656 * @return 返回执行进度
657 *
658 * @throws arcs::common_interface::AuboException
659 *
660 * @par Python函数原型
661 * getProgress(self: pyaubo_sdk.MotionControl) -> float
662 *
663 * @par Lua函数原型
664 * getProgress() -> number
665 *
666 * @par JSON-RPC请求示例
667 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getProgress","params":[],"id":1}
668 *
669 * @par JSON-RPC响应示例
670 * {"id":1,"jsonrpc":"2.0","result":0.0}
671 *
672 */
673 double getProgress();
674
675 /**
676 * 当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
677 *
678 * @note 暂未实现
679 *
680 * @param module_name 控制模块名字
681 * @param mounting_pose 抓取的相对位置,
682 * 如果是机器人,则相对于机器人末端中心点(非TCP点)
683 * @return 成功返回0; 失败返回错误码
684 * AUBO_BAD_STATE
685 * AUBO_BUSY
686 * -AUBO_INVL_ARGUMENT
687 * -AUBO_BAD_STATE
688 *
689 * @throws arcs::common_interface::AuboException
690 *
691 * @par Python函数原型
692 * setWorkObjectHold(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
693 * List[float]) -> int
694 *
695 * @par Lua函数原型
696 * setWorkObjectHold(module_name: string, mounting_pose: table) -> nil
697 *
698 */
699 int setWorkObjectHold(const std::string &module_name,
700 const std::vector<double> &mounting_pose);
701
702 /**
703 * getWorkObjectHold
704 *
705 * @note 暂未实现
706 *
707 * @return
708 *
709 * @throws arcs::common_interface::AuboException
710 *
711 * @par Python函数原型
712 * getWorkObjectHold(self: pyaubo_sdk.MotionControl) -> Tuple[str,
713 * List[float]]
714 *
715 * @par Lua函数原型
716 * getWorkObjectHold() -> table
717 *
718 * @par JSON-RPC请求示例
719 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getWorkObjectHold","params":[],"id":1}
720 *
721 * @par JSON-RPC响应示例
722 * {"id":1,"jsonrpc":"2.0","result":["",[]]}
723 *
724 */
725 std::tuple<std::string, std::vector<double>> getWorkObjectHold();
726
727 /**
728 * getPauseJointPositions
729 *
730 * @note 获取暂停点关节位置
731 * 常用于运行工程时发生碰撞后继续运动过程中(先通过resumeMoveJoint或resumeMoveLine运动到暂停位置,再恢复工程)
732 *
733 * @return 暂停关节位置
734 *
735 * @throws arcs::common_interface::AuboException
736 *
737 * @par Python函数原型
738 * getPauseJointPositions(self: pyaubo_sdk.MotionControl) -> List[float]
739 *
740 * @par Lua函数原型
741 * getPauseJointPositions() -> table
742 *
743 * @par JSON-RPC请求示例
744 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getPauseJointPositions","params":[],"id":1}
745 *
746 * @par JSON-RPC响应示例
747 * {"id":1,"jsonrpc":"2.0","result":[8.2321e-13,-0.200999,1.33999,0.334999,1.206,-6.39383e-12]}
748 *
749 */
750 std::vector<double> getPauseJointPositions();
751
752 /**
753 * 设置伺服模式
754 * 使用 setServoModeSelect 替代
755 *
756 * @param enable 是否使能
757 * @return 成功返回0; 失败返回错误码
758 * AUBO_BAD_STATE
759 * AUBO_BUSY
760 * -AUBO_BAD_STATE
761 *
762 * @throws arcs::common_interface::AuboException
763 *
764 * @par Python函数原型
765 * setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
766 *
767 * @par Lua函数原型
768 * setServoMode(enable: boolean) -> nil
769 *
770 * @par JSON-RPC请求示例
771 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
772 *
773 * @par JSON-RPC响应示例
774 * {"id":1,"jsonrpc":"2.0","result":0}
775 *
776 */
777 ARCS_DEPRECATED int setServoMode(bool enable);
778
779 /**
780 * 判断伺服模式是否使能
781 * 使用 getServoModeSelect 替代
782 *
783 * @return 已使能返回true,反之则返回false
784 *
785 * @throws arcs::common_interface::AuboException
786 *
787 * @par Python函数原型
788 * isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
789 *
790 * @par Lua函数原型
791 * isServoModeEnabled() -> boolean
792 *
793 * @par JSON-RPC请求示例
794 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
795 *
796 * @par JSON-RPC响应示例
797 * {"id":1,"jsonrpc":"2.0","result":false}
798 *
799 */
800 ARCS_DEPRECATED bool isServoModeEnabled();
801
802 /**
803 * 设置伺服运动模式
804 *
805 * @param mode
806 * 0-退出伺服模式
807 * 1-规划伺服模式
808 * 2-透传模式(直接下发)
809 * 3-透传模式(缓存)
810 * @return
811 *
812 * @par JSON-RPC请求示例
813 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
814 *
815 * @par JSON-RPC响应示例
816 * {"id":1,"jsonrpc":"2.0","result":0}
817 *
818 */
819 int setServoModeSelect(int mode);
820
821 /**
822 * 获取伺服运动模式
823 *
824 * @return
825 *
826 * @par JSON-RPC请求示例
827 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
828 *
829 * @par JSON-RPC响应示例
830 * {"id":1,"jsonrpc":"2.0","result":0}
831 *
832 */
834
835 /**
836 * 关节空间伺服
837 *
838 * 目前可用参数只有 q 和 t;
839 * @param q 关节角, 单位 rad,
840 * @param a 加速度, 单位 rad/s^2,
841 * @param v 速度,单位 rad/s,
842 * @param t 运行时间,单位 s \n
843 * t 值越大,机器臂运动越慢,反之,运动越快;
844 * 该参数最优值为连续调用 servoJoint 接口的间隔时间。
845 * @param lookahead_time 前瞻时间,单位 s \n
846 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
847 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
848 * 该参数最优值为一个控制周期。
849 * @param gain 比例增益
850 * 跟踪目标位置的比例增益[100, 200],
851 * 用于控制运动的顺滑性和精度,
852 * 比例增益越大,到达目标位置的时间越长,超调量越小。
853 *
854 * @return 成功返回0;失败返回错误码,正数为警告,负数为错误。
855 * AUBO_BAD_STATE(1): 当前安全模式处于非 Normal、ReducedMode、Recovery 状态;
856 * AUBO_BUSY(3): 上一条指令正在执行中;
857 * AUBO_QUEUE_FULL(2): 轨迹队列已满;
858 * -AUBO_REQUEST_IGNORE(-13): 当前处于非 servo 模式;
859 * -AUBO_BAD_STATE(-1): 当前机器臂模式处于 Running 状态;
860 * -AUBO_INVL_ARGUMENT(-5): 轨迹位置超限或速度超限;
861 *
862 * @throws arcs::common_interface::AuboException
863 *
864 * @par Python函数原型
865 * servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
866 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
867 *
868 * @par Lua函数原型
869 * servoJoint(q: table, a: number, v: number, t: number, lookahead_time:
870 * number, gain: number) -> nil
871 *
872 * @par JSON-RPC请求示例
873 * {"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
874 *
875 * @par JSON-RPC响应示例
876 * {"id":1,"jsonrpc":"2.0","result":-13}
877 *
878 */
879 int servoJoint(const std::vector<double> &q, double a, double v, double t,
880 double lookahead_time, double gain);
881
882 /**
883 * 笛卡尔空间伺服
884 *
885 * 目前可用参数只有 pose 和 t;
886 * @param pose 位姿, 单位 m,
887 * @param a 加速度, 单位 m/s^2,
888 * @param v 速度,单位 m/s,
889 * @param t 运行时间,单位 s \n
890 * t 值越大,机器臂运动越慢,反之,运动越快;
891 * 该参数最优值为连续调用 servoCartesian 接口的间隔时间。
892 * @param lookahead_time 前瞻时间,单位 s \n
893 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
894 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
895 * 该参数最优值为一个控制周期。
896 * @param gain 比例增益
897 * 跟踪目标位置的比例增益[100, 200],
898 * 用于控制运动的顺滑性和精度,
899 * 比例增益越大,到达目标位置的时间越长,超调量越小。
900 *
901 * @return 成功返回0;失败返回错误码,正数为警告,负数为错误。
902 * AUBO_BAD_STATE(1): 当前安全模式处于非 Normal、ReducedMode、Recovery 状态;
903 * AUBO_BUSY(3): 上一条指令正在执行中;
904 * AUBO_QUEUE_FULL(2): 轨迹队列已满;
905 * -AUBO_REQUEST_IGNORE(-13): 当前处于非 servo 模式;
906 * -AUBO_BAD_STATE(-1): 当前机器臂模式处于 Running 状态;
907 * -AUBO_INVL_ARGUMENT(-5): 轨迹位置超限或速度超限;
908 * -AUBO_IK_NO_CONVERGE(-23): 逆解计算不收敛,计算出错;
909 * -AUBO_IK_OUT_OF_RANGE(-24): 逆解计算超出机器人最大限制;
910 * -AUBO_IK_CONFIG_DISMATCH(-25): 逆解输入配置存在错误;
911 * -AUBO_IK_JACOBIAN_FAILED(-26): 逆解雅可比矩阵计算失败;
912 * -AUBO_IK_NO_SOLU(-27): 目标点存在解析解,但均不满足选解条件;
913 * -AUBO_IK_UNKOWN_ERROR(-28): 逆解返回未知类型错误;
914 *
915 * @throws arcs::common_interface::AuboException
916 *
917 * @par Python函数原型
918 * servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
919 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
920 *
921 * @par Lua函数原型
922 * servoCartesian(pose: table, a: number, v: number, t: number,
923 * lookahead_time: number, gain: number) -> nil
924 *
925 * @par JSON-RPC请求示例
926 * {"jsonrpc":"2.0","method":"rob1.MotionControl.servoCartesian","params":[[0.58712,-0.15775,0.48703,2.76,0.344,1.432],0,0,10,0,0],"id":1}
927 *
928 * @par JSON-RPC响应示例
929 * {"id":1,"jsonrpc":"2.0","result":-13}
930 *
931 */
932 int servoCartesian(const std::vector<double> &pose, double a, double v,
933 double t, double lookahead_time, double gain);
934
935 /**
936 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
937 *
938 * @param q
939 * @param extq
940 * @param t
941 * @param smooth_scale
942 * @param delay_sacle
943 * @return
944 */
945 int servoJointWithAxes(const std::vector<double> &q,
946 const std::vector<double> &extq, double a, double v,
947 double t, double lookahead_time, double gain);
948
949 /**
950 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
951 * 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度
952 * (由软件内部直接做逆解)
953 *
954 * @param pose
955 * @param extq
956 * @param t
957 * @param smooth_scale
958 * @param delay_sacle
959 * @return
960 */
961 int servoCartesianWithAxes(const std::vector<double> &pose,
962 const std::vector<double> &extq, double a,
963 double v, double t, double lookahead_time,
964 double gain);
965
966 /**
967 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
968 *
969 * @param q
970 * @param smooth_scale
971 * @param delay_sacle
972 * @return
973 *
974 * @par JSON-RPC请求示例
975 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
976 *
977 * @par JSON-RPC响应示例
978 * {"id":1,"jsonrpc":"2.0","result":0}
979 *
980 */
981 int trackJoint(const std::vector<double> &q, double t, double smooth_scale,
982 double delay_sacle);
983
984 /**
985 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
986 * 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度
987 * (由软件内部直接做逆解)
988 *
989 * @param pose
990 * @param t
991 * @param smooth_scale
992 * @param delay_sacle
993 * @return
994 *
995 * @par JSON-RPC请求示例
996 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackCartesian","params":[[0.58712,-0.15775,0.48703,2.76,0.344,1.432],0.01,0.5,1],"id":1}
997 *
998 * @par JSON-RPC响应示例
999 * {"id":1,"jsonrpc":"2.0","result":0}
1000 *
1001 */
1002 int trackCartesian(const std::vector<double> &pose, double t,
1003 double smooth_scale, double delay_sacle);
1004
1005 /**
1006 * 关节空间跟随
1007 *
1008 * @note 暂未实现
1009 *
1010 * @throws arcs::common_interface::AuboException
1011 *
1012 * @par Python函数原型
1013 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
1014 *
1015 * @par Lua函数原型
1016 * followJoint(q: table) -> nil
1017 *
1018 */
1019 int followJoint(const std::vector<double> &q);
1020
1021 /**
1022 * 笛卡尔空间跟随
1023 *
1024 * @note 暂未实现
1025 *
1026 * @throws arcs::common_interface::AuboException
1027 *
1028 * @par Python函数原型
1029 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
1030 *
1031 * @par Lua函数原型
1032 * followLine(pose: table) -> nil
1033 *
1034 */
1035 int followLine(const std::vector<double> &pose);
1036
1037 /**
1038 * 关节空间速度跟随
1039 *
1040 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1041 *
1042 * @param qd 目标关节速度, 单位 rad/s
1043 * @param a 主轴的加速度, 单位 rad/s^2
1044 * @param t 函数返回所需要的时间, 单位 s \n
1045 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1046 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。\n
1047 * 如果没有达到目标速度,会减速到零。
1048 * 如果达到了目标速度就是按照目标速度匀速运动。
1049 * @return 成功返回0; 失败返回错误码,正数为警告,负数为错误。
1050 * AUBO_BAD_STATE(1): 当前安全模式处于非 Normal、ReducedMode、Recovery 状态;
1051 * AUBO_BUSY(3): 上一条指令正在执行中;
1052 * -AUBO_INVL_ARGUMENT(-5): 参数数组qd的长度小于当前机器臂的自由度;
1053 * -AUBO_BAD_STATE(-1): 当前机器臂模式处于 Running 状态;
1054 *
1055 * @throws arcs::common_interface::AuboException
1056 *
1057 * @par Python函数原型
1058 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1059 * float, arg2: float) -> int
1060 *
1061 * @par Lua函数原型
1062 * speedJoint(qd: table, a: number, t: number) -> nil
1063 *
1064 * @par JSON-RPC请求示例
1065 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
1066 *
1067 * @par JSON-RPC响应示例
1068 * {"id":1,"jsonrpc":"2.0","result":0}
1069 *
1070 */
1071 int speedJoint(const std::vector<double> &qd, double a, double t);
1072
1073 /**
1074 * 关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
1075 *
1076 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1077 *
1078 * @param qd 目标关节速度, 单位 rad/s
1079 * @param a 主轴的加速度, 单位 rad/s^2
1080 * @param t 函数返回所需要的时间, 单位 s
1081 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1082 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1083 * 如果没有达到目标速度,会减速到零。
1084 * 如果达到了目标速度就是按照目标速度匀速运动。
1085 * @return 成功返回0; 失败返回错误码
1086 * AUBO_BUSY
1087 * -AUBO_INVL_ARGUMENT
1088 * -AUBO_BAD_STATE
1089 *
1090 * @throws arcs::common_interface::AuboException
1091 *
1092 * @par Python函数原型
1093 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1094 * float, arg2: float) -> int
1095 *
1096 *
1097 * @par Lua函数原型
1098 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
1099 *
1100 * @par JSON-RPC请求示例
1101 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
1102 *
1103 * @par JSON-RPC响应示例
1104 * {"id":1,"jsonrpc":"2.0","result":-1}
1105 *
1106 */
1107 int resumeSpeedJoint(const std::vector<double> &qd, double a, double t);
1108
1109 /**
1110 * 笛卡尔空间速度跟随
1111 *
1112 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1113 *
1114 * @param xd 工具速度, 单位 m/s
1115 * @param a 工具位置加速度, 单位 m/s^2
1116 * @param t 函数返回所需要的时间, 单位 s \n
1117 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1118 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1119 * 如果没有达到目标速度,会减速到零。
1120 * 如果达到了目标速度就是按照目标速度匀速运动。
1121 * @return 成功返回0; 失败返回错误码
1122 * AUBO_BUSY(3): 上一条指令正在执行中;
1123 * AUBO_BAD_STATE(1): 当前安全模式处于非 Normal、ReducedMode、Recovery 状态;
1124 * -AUBO_BAD_STATE(-1): 当前机器臂模式处于 Running 状态;
1125 *
1126 * @throws arcs::common_interface::AuboException
1127 *
1128 * @par Python函数原型
1129 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1130 * arg2: float) -> int
1131 *
1132 * @par Lua函数原型
1133 * speedLine(pose: table, a: number, t: number) -> nil
1134 *
1135 * @par JSON-RPC请求示例
1136 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
1137 *
1138 * @par JSON-RPC响应示例
1139 * {"id":1,"jsonrpc":"2.0","result":0}
1140 *
1141 */
1142 int speedLine(const std::vector<double> &xd, double a, double t);
1143
1144 /**
1145 * 笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
1146 *
1147 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1148 *
1149 * @param xd 工具速度, 单位 m/s
1150 * @param a 工具位置加速度, 单位 m/s^2
1151 * @param t 函数返回所需要的时间, 单位 s \n
1152 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1153 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1154 * 如果没有达到目标速度,会减速到零。
1155 * 如果达到了目标速度就是按照目标速度匀速运动。
1156 * @return 成功返回0; 失败返回错误码
1157 * -AUBO_BAD_STATE
1158 *
1159 * @throws arcs::common_interface::AuboException
1160 *
1161 * @par Python函数原型
1162 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1163 * float, arg2: float) -> int
1164 *
1165 * @par Lua函数原型
1166 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
1167 *
1168 * @par JSON-RPC请求示例
1169 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
1170 *
1171 * @par JSON-RPC响应示例
1172 * {"id":1,"jsonrpc":"2.0","result":-1}
1173 *
1174 */
1175 int resumeSpeedLine(const std::vector<double> &xd, double a, double t);
1176
1177 /**
1178 * 在关节空间做样条插值
1179 *
1180 * @param q 关节角度,如果传入参数维度为0,表示样条运动结束
1181 * @param a 加速度, 单位 rad/s^2,
1182 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
1183 * @param v 速度, 单位 rad/s,
1184 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
1185 * @param duration
1186 * @return 成功返回0; 失败返回错误码
1187 * AUBO_BUSY
1188 * AUBO_BAD_STATE
1189 * -AUBO_BAD_STATE
1190 *
1191 * @throws arcs::common_interface::AuboException
1192 *
1193 * @par Python函数原型
1194 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1195 * float, arg2: float, arg3: float) -> int
1196 *
1197 * @par Lua函数原型
1198 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
1199 *
1200 * @par JSON-RPC请求示例
1201 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
1202 *
1203 * @par JSON-RPC响应示例
1204 * {"id":1,"jsonrpc":"2.0","result":0}
1205 *
1206 */
1207 int moveSpline(const std::vector<double> &q, double a, double v,
1208 double duration);
1209
1210 /**
1211 * 添加关节运动
1212 *
1213 * @param q 关节角, 单位 rad
1214 * @param a 加速度, 单位 rad/s^2,
1215 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
1216 * @param v 速度, 单位 rad/s,
1217 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
1218 * @param blend_radius 交融半径, 单位 m
1219 * @param duration 运行时间,单位 s \n
1220 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1221 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1222 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1223 * 当 duration = 0的时候,
1224 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1225 * 如果duration不等于0,a 和 v 的值将被忽略。
1226 * @return 成功返回0;失败返回错误码,正数为警告,负数为错误。
1227 * AUBO_BAD_STATE(1): 当前安全模式处于非 Normal、ReducedMode、Recovery 状态;
1228 * AUBO_BUSY(3): 上一条指令正在执行中;
1229 * -AUBO_INVL_ARGUMENT(-5): 参数数组q的长度小于当前机器臂的自由度;
1230 * -AUBO_BAD_STATE(-1): 当前机器臂模式处于 Running 状态;
1231 *
1232 * @throws arcs::common_interface::AuboException
1233 *
1234 * @par Python函数原型
1235 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1236 * arg2: float, arg3: float, arg4: float) -> int
1237 *
1238 * @par Lua函数原型
1239 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
1240 * number) -> nil
1241 *
1242 * @par JSON-RPC请求示例
1243 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
1244 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
1245 *
1246 * @par JSON-RPC响应示例
1247 * {"id":1,"jsonrpc":"2.0","result":0}
1248 *
1249 */
1250 int moveJoint(const std::vector<double> &q, double a, double v,
1251 double blend_radius, double duration);
1252
1253 /**
1254 * 通过关节运动移动到暂停点的位置
1255 *
1256 * @param q 关节角, 单位 rad
1257 * @param a 加速度, 单位 rad/s^2
1258 * @param v 速度, 单位 rad/s
1259 * @param duration 运行时间,单位 s \n
1260 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1261 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1262 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1263 * 当 duration = 0的时候,
1264 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1265 * 如果duration不等于0,a 和 v 的值将被忽略。
1266 * @return 成功返回0;失败返回错误码
1267 * -AUBO_INVL_ARGUMENT
1268 * -AUBO_BAD_STATE
1269 *
1270 * @throws arcs::common_interface::AuboException
1271 *
1272 * @par Python函数原型
1273 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1274 * float, arg2: float, arg3: float) -> int
1275 *
1276 * @par Lua函数原型
1277 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
1278 *
1279 * @par JSON-RPC请求示例
1280 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
1281 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
1282 *
1283 * @par JSON-RPC响应示例
1284 * {"id":1,"jsonrpc":"2.0","result":-1}
1285 */
1286 int resumeMoveJoint(const std::vector<double> &q, double a, double v,
1287 double duration);
1288
1289 /**
1290 * 添加直线运动
1291 *
1292 * @param pose 目标位姿
1293 * @param a 加速度(如果位置变化小于1mm,姿态变化大于 1e-4
1294 * rad,此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
1295 * 最大值可通过RobotConfig类中的接口getTcpMaxAccelerations()来获取
1296 * @param v 速度(如果位置变化小于1mm,姿态变化大于 1e-4
1297 * rad,此速度会被作为角速度,单位 rad/s.否则为线速度,单位 m/s)
1298 * 最大值可通过RobotConfig类中的接口getTcpMaxSpeeds()来获取
1299 * @param blend_radius 交融半径,单位 m,值介于0.001和1之间
1300 * @param duration 运行时间,单位 s \n
1301 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1302 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1303 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1304 * 当 duration = 0的时候,
1305 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1306 * 如果duration不等于0,a 和 v 的值将被忽略。
1307 * @return 成功返回0;失败返回错误码,正数为警告,负数为错误。
1308 * AUBO_BAD_STATE(1): 当前安全模式处于非 Normal、ReducedMode、Recovery 状态;
1309 * AUBO_BUSY(3): 上一条指令正在执行中;
1310 * -AUBO_INVL_ARGUMENT(-5): 参数数组 pose 的长度小于当前机器臂的自由度;
1311 * -AUBO_BAD_STATE(-1): 当前机器臂模式处于 Running 状态;
1312 *
1313 * @throws arcs::common_interface::AuboException
1314 *
1315 * @par Python函数原型
1316 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1317 * arg2: float, arg3: float, arg4: float) -> int
1318 *
1319 * @par Lua函数原型
1320 * moveLine(pose: table, a: number, v: number, blend_radius: number,
1321 * duration: number) -> nil
1322 *
1323 * @par JSON-RPC请求示例
1324 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveLine","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],1.2,0.25,0,0],"id":1}
1325 *
1326 * @par JSON-RPC响应示例
1327 * {"id":1,"jsonrpc":"2.0","result":0}
1328 *
1329 */
1330 int moveLine(const std::vector<double> &pose, double a, double v,
1331 double blend_radius, double duration);
1332
1333 /**
1334 * 添加工艺运动
1335 *
1336 * @param pose
1337 * @param a
1338 * @param v
1339 * @param blend_radius
1340 * @return 成功返回0;失败返回错误码
1341 * AUBO_BAD_STATE
1342 * AUBO_BUSY
1343 * -AUBO_INVL_ARGUMENT
1344 * -AUBO_BAD_STATE
1345 *
1346 * @throws arcs::common_interface::AuboException
1347 *
1348 * @par JSON-RPC请求示例
1349 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveProcess","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],1.2,0.25,0],"id":1}
1350 *
1351 * @par JSON-RPC响应示例
1352 * {"id":1,"jsonrpc":"2.0","result":0}
1353 *
1354 */
1355 int moveProcess(const std::vector<double> &pose, double a, double v,
1356 double blend_radius);
1357
1358 /**
1359 * 通过直线运动移动到暂停点的位置
1360 *
1361 * @param pose 目标位姿
1362 * @param a 加速度, 单位 m/s^2
1363 * @param v 速度, 单位 m/s
1364 * @param duration 运行时间,单位 s \n
1365 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1366 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1367 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1368 * 当 duration = 0的时候,
1369 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1370 * 如果duration不等于0,a 和 v 的值将被忽略。
1371 * @return 成功返回0;失败返回错误码
1372 * -AUBO_INVL_ARGUMENT
1373 * -AUBO_BAD_STATE
1374 *
1375 * @throws arcs::common_interface::AuboException
1376 *
1377 * @par Python函数原型
1378 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1379 * float, arg2: float, arg3: float) -> int
1380 *
1381 * @par Lua函数原型
1382 * resumeMoveLine(pose: table, a: number, v: number,duration: number) -> nil
1383 *
1384 * @par JSON-RPC请求示例
1385 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveLine","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],1.2,0.25,0],"id":1}
1386 *
1387 * @par JSON-RPC响应示例
1388 * {"id":1,"jsonrpc":"2.0","result":0}
1389 *
1390 */
1391 int resumeMoveLine(const std::vector<double> &pose, double a, double v,
1392 double duration);
1393
1394 /**
1395 * 添加圆弧运动
1396 *
1397 * @todo 可以由多段圆弧组成圆周运动
1398 *
1399 * @param via_pose 圆弧运动途中点的位姿
1400 * @param end_pose 圆弧运动结束点的位姿
1401 * @param a 加速度(如果via_pose与上一个路点位置变化小于1mm,姿态变化大于 1e-4
1402 * rad, 此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
1403 * @param v 速度(如果via_pose与上一个路点位置变化小于1mm, 姿态变化大于 1e-4
1404 * rad, 此速度会被作为角速度, 单位 rad / s.否则为线速度, 单位 m / s)
1405 * @param blend_radius 交融半径,单位: m
1406 * @param duration 运行时间,单位: s \n
1407 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1408 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1409 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1410 * 当 duration = 0 的时候,
1411 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1412 * 如果duration不等于0,a 和 v 的值将被忽略。
1413 * @return 成功返回0;失败返回错误码
1414 * AUBO_BAD_STATE
1415 * AUBO_BUSY
1416 * -AUBO_INVL_ARGUMENT
1417 * -AUBO_BAD_STATE
1418 *
1419 * @throws arcs::common_interface::AuboException
1420 *
1421 * @par Python函数原型
1422 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1423 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
1424 *
1425 * @par Lua函数原型
1426 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
1427 * blend_radius: number, duration: number) -> nil
1428 *
1429 * @par JSON-RPC请求示例
1430 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle","params":[[0.440164,-0.00249391,0.398658,2.45651,0,1.5708],[0.440164,0.166256,0.297599,2.45651,0,1.5708],1.2,0.25,0,0],"id":1}
1431 *
1432 * @par JSON-RPC响应示例
1433 * {"id":1,"jsonrpc":"2.0","result":0}
1434 *
1435 */
1436 int moveCircle(const std::vector<double> &via_pose,
1437 const std::vector<double> &end_pose, double a, double v,
1438 double blend_radius, double duration);
1439
1440 /**
1441 * 设置圆弧路径模式
1442 *
1443 * @param mode 模式 \n
1444 * 0:工具姿态相对于圆弧路径点坐标系保持不变 \n
1445 * 1:姿态线性变化,绕着空间定轴转动,从起始点姿态变化到目标点姿态 \n
1446 * 2:从起点姿态开始经过中间点姿态,变化到目标点姿态
1447 * @return 成功返回0;失败返回错误码
1448 * AUBO_BAD_STATE
1449 * AUBO_BUSY
1450 * -AUBO_INVL_ARGUMENT
1451 * -AUBO_BAD_STATE
1452 *
1453 * @throws arcs::common_interface::AuboException
1454 *
1455 * @par Python函数原型
1456 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
1457 *
1458 * @par Lua函数原型
1459 * setCirclePathMode(mode: number) -> nil
1460 *
1461 * @par JSON-RPC请求示例
1462 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
1463 *
1464 * @par JSON-RPC响应示例
1465 * {"id":1,"jsonrpc":"2.0","result":0}
1466 *
1467 */
1468 int setCirclePathMode(int mode);
1469
1470 /**
1471 * 高级圆弧或者圆周运动
1472 *
1473 * @param param 圆周运动参数
1474 * @return 成功返回0;失败返回错误码
1475 * AUBO_BAD_STATE
1476 * AUBO_BUSY
1477 * -AUBO_INVL_ARGUMENT
1478 * -AUBO_BAD_STATE
1479 *
1480 * @throws arcs::common_interface::AuboException
1481 *
1482 * @par Python函数原型
1483 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
1484 * arcs::common_interface::CircleParameters) -> int
1485 *
1486 * @par Lua函数原型
1487 * moveCircle2(param: table) -> nil
1488 *
1489 * @par JSON-RPC请求示例
1490 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
1491 * "pose_to":[0.440164,0.166256,0.297599,2.45651,0,1.5708],"a":1.2,"v":0.25,"blend_radius":0,"duration":0,"helix":0,
1492 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
1493 *
1494 * @par JSON-RPC响应示例
1495 * {"id":1,"jsonrpc":"2.0","result":0}
1496 *
1497 */
1499
1500 /**
1501 * 新建一个路径点缓存
1502 *
1503 * @param name 指定路径的名字
1504 * @param type 路径的类型 \n
1505 * 1: toppra 时间最优路径规划 \n
1506 * 2: cubic_spline(录制的轨迹) \n
1507 * 3: 关节B样条插值,最少三个点
1508 * @param size 缓存区大小
1509 * @return 新建成功返回 AUBO_OK(0)
1510 *
1511 * @throws arcs::common_interface::AuboException
1512 *
1513 * @par Python函数原型
1514 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
1515 * arg2: int) -> int
1516 *
1517 * @par Lua函数原型
1518 * pathBufferAlloc(name: string, type: number, size: number) -> nil
1519 *
1520 * @par JSON-RPC请求示例
1521 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
1522 *
1523 * @par JSON-RPC响应示例
1524 * {"id":1,"jsonrpc":"2.0","result":0}
1525 *
1526 */
1527 int pathBufferAlloc(const std::string &name, int type, int size);
1528
1529 /**
1530 * 向路径缓存添加路点
1531 *
1532 * @param name 路径缓存的名字
1533 * @param waypoints 路点
1534 * @return 成功返回0;失败返回错误码
1535 * -AUBO_INVL_ARGUMENT
1536 * -AUBO_BAD_STATE
1537 *
1538 * @throws arcs::common_interface::AuboException
1539 *
1540 * @par Python函数原型
1541 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1542 * List[List[float]]) -> int
1543 *
1544 * @par Lua函数原型
1545 * pathBufferAppend(name: string, waypoints: table) -> nil
1546 *
1547 * @par JSON-RPC请求示例
1548 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAppend","params":["rec",[[-0.000000,0.000009,-0.000001,0.000002,0.000002,0.000000],[-0.000001,0.000010,-0.000002,0.000000,0.000003,0.000002]]],"id":1}
1549 *
1550 * @par JSON-RPC响应示例
1551 * {"id":1,"jsonrpc":"2.0","result":0}
1552 *
1553 */
1554 int pathBufferAppend(const std::string &name,
1555 const std::vector<std::vector<double>> &waypoints);
1556
1557 /**
1558 * 计算、优化等耗时操作,传入的参数相同时不会重新计算
1559 *
1560 * @param name 通过pathBufferAlloc新建的路径点缓存的名字
1561 * @param a 关节加速度限制,需要和机器人自由度大小相同,单位 m/s^2
1562 * @param v 关节速度限制,需要和机器人自由度大小相同,单位 m/s
1563 * @param t 时间 \n
1564 * pathBufferAlloc 这个接口分配内存的时候要指定类型,
1565 * 根据pathBufferAlloc这个接口的类型:\n
1566 * 类型为1时,表示运动持续时间\n
1567 * 类型为2时,表示采样时间间隔\n
1568 * 类型为3时,t参数设置为0
1569 * @return 成功返回0;失败返回错误码
1570 * -AUBO_INVL_ARGUMENT
1571 * -AUBO_BAD_STATE
1572 *
1573 * @throws arcs::common_interface::AuboException
1574 *
1575 * @par Python函数原型
1576 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1577 * List[float], arg2: List[float], arg3: float) -> int
1578 *
1579 * @par Lua函数原型
1580 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
1581 *
1582 * @par JSON-RPC请求示例
1583 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferEval","params":["rec",[1,1,1,1,1,1],[1,1,1,1,1,1],0.02],"id":1}
1584 *
1585 * @par JSON-RPC响应示例
1586 * {"id":1,"jsonrpc":"2.0","result":0}
1587 *
1588 */
1589 int pathBufferEval(const std::string &name, const std::vector<double> &a,
1590 const std::vector<double> &v, double t);
1591
1592 /**
1593 * 指定名字的buffer是否有效
1594 *
1595 * buffer需要满足三个条件有效: \n
1596 * 1、buffer存在,已经分配过内存 \n
1597 * 2、传进buffer的点要大于等于buffer的大小 \n
1598 * 3、要执行一次pathBufferEval
1599 *
1600 * @param name buffer的名字
1601 * @return 有效返回true; 无效返回false
1602 *
1603 * @throws arcs::common_interface::AuboException
1604 *
1605 * @par Python函数原型
1606 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
1607 *
1608 * @par Lua函数原型
1609 * pathBufferValid(name: string) -> boolean
1610 *
1611 * @par JSON-RPC请求示例
1612 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
1613 *
1614 * @par JSON-RPC响应示例
1615 * {"id":1,"jsonrpc":"2.0","result":false}
1616 *
1617 */
1618 bool pathBufferValid(const std::string &name);
1619
1620 /**
1621 * 释放路径缓存
1622 *
1623 * @param name 缓存路径的名字
1624 * @return 成功返回0;失败返回错误码
1625 * -AUBO_INVL_ARGUMENT
1626 * -AUBO_BAD_STATE
1627 *
1628 * @throws arcs::common_interface::AuboException
1629 *
1630 * @par Python函数原型
1631 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
1632 *
1633 * @par Lua函数原型
1634 * pathBufferFree(name: string) -> nil
1635 *
1636 * @par JSON-RPC请求示例
1637 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
1638 *
1639 * @par JSON-RPC响应示例
1640 * {"id":1,"jsonrpc":"2.0","result":-5}
1641 *
1642 */
1643 int pathBufferFree(const std::string &name);
1644
1645 /**
1646 * 关节空间路径滤波器
1647 *
1648 * @brief pathBufferFilter
1649 *
1650 * @param name 缓存路径的名称
1651 * @param order 滤波器阶数(一般取2)
1652 * @param fd 截止频率,越小越光滑,但是延迟会大(一般取3-20)
1653 * @param fs 离散数据的采样频率(一般取20-500)
1654 *
1655 * @return 成功返回0
1656 *
1657 * @throws arcs::common_interface::AuboException
1658 *
1659 * @par Python函数原型
1660 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
1661 * arg2: float, arg3: float) -> int
1662 *
1663 * @par Lua函数原型
1664 * pathBufferFree(name: string, order: number, fd: number, fs:number) -> nil
1665 */
1666 int pathBufferFilter(const std::string &name, int order, double fd,
1667 double fs);
1668
1669 /**
1670 * 列出所有缓存路径的名字
1671 *
1672 * @return 返回所有缓存路径的名字
1673 *
1674 * @throws arcs::common_interface::AuboException
1675 *
1676 * @par Python函数原型
1677 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
1678 *
1679 * @par Lua函数原型
1680 * pathBufferList() -> table
1681 *
1682 * @par JSON-RPC请求示例
1683 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
1684 *
1685 * @par JSON-RPC响应示例
1686 * {"id":1,"jsonrpc":"2.0","result":[]}
1687 *
1688 */
1689 std::vector<std::string> pathBufferList();
1690
1691 /**
1692 * 执行缓存的路径
1693 *
1694 * @param name 缓存路径的名字
1695 * @return 成功返回0;失败返回错误码
1696 * -AUBO_INVL_ARGUMENT
1697 * -AUBO_BAD_STATE
1698 *
1699 * @throws arcs::common_interface::AuboException
1700 *
1701 * @par Python函数原型
1702 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
1703 *
1704 * @par Lua函数原型
1705 * movePathBuffer(name: string) -> nil
1706 *
1707 * @par JSON-RPC请求示例
1708 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
1709 *
1710 * @par JSON-RPC响应示例
1711 * {"id":1,"jsonrpc":"2.0","result":0}
1712 *
1713 */
1714 int movePathBuffer(const std::string &name);
1715
1716 /**
1717 * 相贯线接口
1718 *
1719 * @param pose由三个示教位姿组成(首先需要运动到起始点,起始点的要求:过主圆柱
1720 * 柱体轴心且与子圆柱体轴线平行的平面与子圆柱体在底部的交点)
1721 * p1:过子圆柱体轴线且与大圆柱体轴线平行的平面,与小圆柱体在左侧顶部的交点
1722 * p2:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在左侧底部的交点
1723 * p3:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在右侧底部的交点
1724 * @param v:速度
1725 * @param a:加速度
1726 * @param main_pipe_radius: 主圆柱体半径
1727 * @param sub_pipe_radius: 子圆柱体半径
1728 * @param normal_distance: 两圆柱体轴线距离
1729 * @param normal_alpha: 两圆柱体轴线的夹角
1730 *
1731 * @return 成功返回0;失败返回错误码
1732 * AUBO_BUSY
1733 * AUBO_BAD_STATE
1734 * -AUBO_INVL_ARGUMENT
1735 * -AUBO_BAD_STATE
1736 *
1737 * @throws arcs::common_interface::AuboException
1738 *
1739 * @par Python函数原型
1740 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1741 float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float) ->
1742 int
1743 *
1744 * @par Lua函数原型
1745 * moveIntersection(poses: table, a: number, v: number,
1746 * main_pipe_radius:number, sub_pipe_radius: number,normal_distance:
1747 * number,normal_alpha: number,) -> nil
1748 */
1749 int moveIntersection(const std::vector<std::vector<double>> &poses,
1750 double a, double v, double main_pipe_radius,
1751 double sub_pipe_radius, double normal_distance,
1752 double normal_alpha);
1753 /**
1754 * 关节空间停止运动
1755 *
1756 * @param acc 关节加速度,单位: rad/s^2
1757 * @return 成功返回0;失败返回错误码
1758 * AUBO_BUSY
1759 * AUBO_BAD_STATE
1760 * -AUBO_INVL_ARGUMENT
1761 * -AUBO_BAD_STATE
1762 *
1763 * @throws arcs::common_interface::AuboException
1764 *
1765 * @par Python函数原型
1766 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
1767 *
1768 * @par Lua函数原型
1769 * stopJoint(acc: number) -> nil
1770 *
1771 * @par JSON-RPC请求示例
1772 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
1773 *
1774 * @par JSON-RPC响应示例
1775 * {"id":1,"jsonrpc":"2.0","result":0}
1776 *
1777 */
1778 int stopJoint(double acc);
1779
1780 /**
1781 * 关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
1782 *
1783 * @param acc 关节加速度,单位: rad/s^2
1784 * @return 成功返回0;失败返回错误码
1785 * AUBO_BUSY
1786 * AUBO_BAD_STATE
1787 * -AUBO_INVL_ARGUMENT
1788 * -AUBO_BAD_STATE
1789 *
1790 * @throws arcs::common_interface::AuboException
1791 *
1792 * @par Python函数原型
1793 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
1794 *
1795 * @par Lua函数原型
1796 * resumeStopJoint(acc: number) -> nil
1797 *
1798 * @par JSON-RPC请求示例
1799 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
1800 *
1801 * @par JSON-RPC响应示例
1802 * {"id":1,"jsonrpc":"2.0","result":-1}
1803 *
1804 */
1805 int resumeStopJoint(double acc);
1806
1807 /**
1808 * 笛卡尔空间停止运动
1809 *
1810 * @param acc 工具加速度, 单位: m/s^2
1811 * @param acc_rot
1812 * @return 成功返回0;失败返回错误码
1813 * AUBO_BUSY
1814 * AUBO_BAD_STATE
1815 * -AUBO_INVL_ARGUMENT
1816 * -AUBO_BAD_STATE
1817 *
1818 * @throws arcs::common_interface::AuboException
1819 *
1820 * @par Python函数原型
1821 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
1822 *
1823 * @par Lua函数原型
1824 * stopLine(acc: number, acc_rot: number) -> nil
1825 *
1826 * @par JSON-RPC请求示例
1827 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
1828 *
1829 * @par JSON-RPC响应示例
1830 * {"id":1,"jsonrpc":"2.0","result":0}
1831 *
1832 */
1833 int stopLine(double acc, double acc_rot);
1834
1835 /**
1836 * 笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
1837 *
1838 * @param acc 位置加速度, 单位: m/s^2
1839 * @param acc_rot 姿态加速度,单位: rad/s^2
1840 * @return 成功返回0;失败返回错误码
1841 * AUBO_BUSY
1842 * AUBO_BAD_STATE
1843 * -AUBO_INVL_ARGUMENT
1844 * -AUBO_BAD_STATE
1845 *
1846 * @throws arcs::common_interface::AuboException
1847 *
1848 * @par Python函数原型
1849 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
1850 * -> int
1851 *
1852 * @par Lua函数原型
1853 * resumeStopLine(acc: number, acc_rot: number) -> nil
1854 *
1855 * @par JSON-RPC请求示例
1856 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
1857 *
1858 * @par JSON-RPC响应示例
1859 * {"id":1,"jsonrpc":"2.0","result":-1}
1860 *
1861 */
1862 int resumeStopLine(double acc, double acc_rot);
1863
1864 /**
1865 * 开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params
1866 * 进行摆动
1867 *
1868 * @param params Json字符串用于定义摆动参数
1869 * {
1870 * "type": <string>, // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
1871 * "step": <num>,
1872 * "amplitude": {<num>,<num>},
1873 * "hold_distance": {<num>,<num>},
1874 * "angle": <num>
1875 * "direction": <num>
1876 * }
1877 * @return 成功返回0;失败返回错误码
1878 * AUBO_BUSY
1879 * AUBO_BAD_STATE
1880 * -AUBO_INVL_ARGUMENT
1881 * -AUBO_BAD_STATE
1882 *
1883 * @throws arcs::common_interface::AuboException
1884 *
1885 */
1886 int weaveStart(const std::string &params);
1887
1888 /**
1889 * 结束摆动
1890 *
1891 * @return 成功返回0;失败返回错误码
1892 * AUBO_BUSY
1893 * AUBO_BAD_STATE
1894 * -AUBO_BAD_STATE
1895 *
1896 * @throws arcs::common_interface::AuboException
1897 *
1898 * @par JSON-RPC请求示例
1899 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
1900 *
1901 * @par JSON-RPC响应示例
1902 * {"id":1,"jsonrpc":"2.0","result":0}
1903 *
1904 */
1906
1907 /**
1908 * 设置未来路径上点的采样时间间隔
1909 *
1910 * @param sample_time 采样时间间隔 单位: m/s^2
1911 * @return 成功返回0;失败返回错误码
1912 * AUBO_BUSY
1913 * AUBO_BAD_STATE
1914 * -AUBO_INVL_ARGUMENT
1915 * -AUBO_BAD_STATE
1916 *
1917 * @throws arcs::common_interface::AuboException
1918 *
1919 */
1920 int setFuturePointSamplePeriod(double sample_time);
1921
1922 /**
1923 * 获取未来路径上的轨迹点
1924 *
1925 * @return 路点(100ms * 10)
1926 *
1927 * @throws arcs::common_interface::AuboException
1928 *
1929 * @par JSON-RPC请求示例
1930 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
1931 *
1932 * @par JSON-RPC响应示例
1933 * {"id":1,"jsonrpc":"2.0","result":[]}
1934 *
1935 */
1936 std::vector<std::vector<double>> getFuturePathPointsJoint();
1937
1938 /**
1939 * 圆形传送带跟随
1940 *
1941 * @note 暂未实现
1942 *
1943 * @param encoder_id
1944 * 0-集成传感器
1945 *
1946 * @param center
1947 * @param tick_per_revo
1948 * @param rotate_tool
1949 * @return
1950 *
1951 * @throws arcs::common_interface::AuboException
1952 *
1953 */
1954 int conveyorTrackCircle(int encoder_id, const std::vector<double> &center,
1955 int tick_per_revo, bool rotate_tool);
1956
1957 /**
1958 * 线性传送带跟随
1959 *
1960 * @note 暂未实现
1961 *
1962 * @param encoder_id 预留
1963 * @param direction
1964 * @param tick_per_meter
1965 * @return
1966 *
1967 * @throws arcs::common_interface::AuboException
1968 *
1969 */
1970 int conveyorTrackLine(int encoder_id, const std::vector<double> &direction,
1971 int tick_per_meter);
1972
1973 /**
1974 * 终止传送带跟随
1975 *
1976 * @note 暂未实现
1977 *
1978 * @param a
1979 * @return
1980 *
1981 * @throws arcs::common_interface::AuboException
1982 *
1983 */
1984 int conveyorTrackStop(double a);
1985
1986 /**
1987 * 螺旋线运动
1988 *
1989 * @param param 封装的参数
1990 * @param blend_radius
1991 * @param v
1992 * @param a
1993 * @param t
1994 * @return 成功返回0;失败返回错误码
1995 * AUBO_BUSY
1996 * AUBO_BAD_STATE
1997 * -AUBO_INVL_ARGUMENT
1998 * -AUBO_BAD_STATE
1999 *
2000 * @throws arcs::common_interface::AuboException
2001 *
2002 * @par JSON-RPC请求示例
2003 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
2004 * "params":[{"spiral":0.005,"helix":0.005,"angle":18.84,"plane":0,"frame":[0,0,0,0,0,0]},0,0.25,1.2,0],"id":1}
2005 *
2006 * @par JSON-RPC响应示例
2007 * {"id":1,"jsonrpc":"2.0","result":0}
2008 *
2009 */
2010 int moveSpiral(const SpiralParameters &param, double blend_radius, double v,
2011 double a, double t);
2012
2013 /**
2014 * 获取前瞻段数
2015 *
2016 * @return 返回前瞻段数
2017 *
2018 * @throws arcs::common_interface::AuboException
2019 *
2020 * @par Python函数原型
2021 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
2022 *
2023 * @par Lua函数原型
2024 * getLookAheadSize() -> number
2025 *
2026 * @par JSON-RPC请求示例
2027 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
2028 *
2029 * @par JSON-RPC响应示例
2030 * {"id":1,"jsonrpc":"2.0","result":1}
2031 *
2032 */
2034
2035 /**
2036 * 设置前瞻段数
2037 * 1.对于有较高速度平稳性要求的任务,如数控加工,涂胶,焊接等匀速需求,较长的前瞻段数可以提供更优的速度规划,产生的运动会更加平滑;
2038 * 2.对于快速响应的抓取类任务,更倾向于较短的前瞻段数,以提高反应速度,但可能因为进给的路径不够及时导致速度波动很大.
2039 *
2040 * @return 成功返回0
2041 *
2042 * @throws arcs::common_interface::AuboException
2043 *
2044 * @par Python函数原型
2045 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
2046 *
2047 * @par Lua函数原型
2048 * setLookAheadSize(eqradius: number) -> number
2049 *
2050 * @par JSON-RPC请求示例
2051 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
2052 *
2053 * @par JSON-RPC响应示例
2054 * {"id":1,"jsonrpc":"2.0","result":0}
2055 *
2056 */
2057 int setLookAheadSize(int size);
2058
2059protected:
2060 void *d_;
2061};
2062using MotionControlPtr = std::shared_ptr<MotionControl>;
2063
2064// clang-format off
2065#define MotionControl_DECLARES \
2066 _FUNC(MotionControl, 0, getEqradius) \
2067 _FUNC(MotionControl, 1, setEqradius,eqradius) \
2068 _FUNC(MotionControl, 0, getSpeedFraction) \
2069 _FUNC(MotionControl, 1, setSpeedFraction, fraction) \
2070 _INST(MotionControl, 1, speedFractionCritical, enable) \
2071 _FUNC(MotionControl, 0, isSpeedFractionCritical) \
2072 _FUNC(MotionControl, 0, isBlending) \
2073 _INST(MotionControl, 0, pathOffsetEnable) \
2074 _INST(MotionControl, 2, pathOffsetSet, offset, type) \
2075 _INST(MotionControl, 0, pathOffsetDisable) \
2076 _INST(MotionControl, 0, jointOffsetEnable) \
2077 _INST(MotionControl, 2, jointOffsetSet, offset, type) \
2078 _INST(MotionControl, 0, jointOffsetDisable) \
2079 _FUNC(MotionControl, 0, getTrajectoryQueueSize) \
2080 _FUNC(MotionControl, 0, getQueueSize) \
2081 _FUNC(MotionControl, 0, getExecId) \
2082 _FUNC(MotionControl, 1, getDuration, id) \
2083 _FUNC(MotionControl, 1, getMotionLeftTime, id) \
2084 _FUNC(MotionControl, 0, getProgress) \
2085 _INST(MotionControl, 2, setWorkObjectHold, module_name, mounting_pose) \
2086 _FUNC(MotionControl, 0, getWorkObjectHold) \
2087 _FUNC(MotionControl, 0, getPauseJointPositions) \
2088 _FUNC(MotionControl, 1, setServoMode, enable) \
2089 _FUNC(MotionControl, 0, isServoModeEnabled) \
2090 _FUNC(MotionControl, 1, setServoModeSelect, mode) \
2091 _FUNC(MotionControl, 0, getServoModeSelect) \
2092 _FUNC(MotionControl, 6, servoJoint, q, a, v, t, lookahead_time, gain) \
2093 _FUNC(MotionControl, 6, servoCartesian, pose, a, v, t, lookahead_time, gain)\
2094 _INST(MotionControl, 7, servoJointWithAxes, q, extq, a, v, t, lookahead_time, gain) \
2095 _INST(MotionControl, 7, servoCartesianWithAxes, pose, extq, a, v, t, lookahead_time, gain) \
2096 _INST(MotionControl, 4, trackJoint, q, t, smooth_scale, delay_sacle) \
2097 _INST(MotionControl, 4, trackCartesian, pose, t, smooth_scale, delay_sacle) \
2098 _INST(MotionControl, 1, followJoint, q) \
2099 _INST(MotionControl, 1, followLine, pose) \
2100 _INST(MotionControl, 3, speedJoint, qd, a, t) \
2101 _FUNC(MotionControl, 3, resumeSpeedJoint, qd, a, t) \
2102 _INST(MotionControl, 3, speedLine, xd, a, t) \
2103 _FUNC(MotionControl, 3, resumeSpeedLine, xd, a, t) \
2104 _INST(MotionControl, 4, moveSpline, q, a, v, duration) \
2105 _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration) \
2106 _FUNC(MotionControl, 4, resumeMoveJoint, q, a, v, duration) \
2107 _INST(MotionControl, 5, moveLine, pose, a, v, blend_radius, duration) \
2108 _INST(MotionControl, 4, moveProcess, pose, a, v, blend_radius) \
2109 _FUNC(MotionControl, 4, resumeMoveLine, pose, a, v, duration) \
2110 _INST(MotionControl, 6, moveCircle, via_pose, end_pose, a, v, \
2111 blend_radius, duration) \
2112 _INST(MotionControl, 1, setCirclePathMode, mode) \
2113 _INST(MotionControl, 1, moveCircle2, param) \
2114 _FUNC(MotionControl, 3, pathBufferAlloc, name, type, size) \
2115 _FUNC(MotionControl, 2, pathBufferAppend, name, waypoints) \
2116 _FUNC(MotionControl, 4, pathBufferEval, name, a, v, t) \
2117 _FUNC(MotionControl, 1, pathBufferValid, name) \
2118 _FUNC(MotionControl, 1, pathBufferFree, name) \
2119 _FUNC(MotionControl, 0, pathBufferList) \
2120 _INST(MotionControl, 1, movePathBuffer, name) \
2121 _INST(MotionControl, 7, moveIntersection, poses, a, v, main_pipe_radius, sub_pipe_radius, normal_distance, normal_alpha)\
2122 _FUNC(MotionControl, 1, stopJoint, acc) \
2123 _FUNC(MotionControl, 1, resumeStopJoint, acc) \
2124 _FUNC(MotionControl, 2, stopLine, acc, acc_rot) \
2125 _FUNC(MotionControl, 2, resumeStopLine, acc, acc_rot) \
2126 _INST(MotionControl, 1, weaveStart, params) \
2127 _INST(MotionControl, 0, weaveEnd) \
2128 _FUNC(MotionControl, 1, storePath, keep_sync) \
2129 _FUNC(MotionControl, 2, stopMove, quick, all_tasks) \
2130 _FUNC(MotionControl, 0, startMove) \
2131 _FUNC(MotionControl, 0, clearPath) \
2132 _FUNC(MotionControl, 0, restoPath) \
2133 _FUNC(MotionControl, 1, setFuturePointSamplePeriod, sample_time) \
2134 _FUNC(MotionControl, 0, getFuturePathPointsJoint) \
2135 _INST(MotionControl, 4, conveyorTrackCircle, encoder_id, center, tick_per_revo, rotate_tool) \
2136 _INST(MotionControl, 3, conveyorTrackLine, encoder_id, direction, tick_per_meter) \
2137 _INST(MotionControl, 1, conveyorTrackStop, a) \
2138 _INST(MotionControl, 5, moveSpiral, param, blend_radius, v, a, t) \
2139 _INST(MotionControl, 2, pathOffsetLimits, v, a) \
2140 _INST(MotionControl, 1, pathOffsetCoordinate, ref_coord) \
2141 _FUNC(MotionControl, 0, getLookAheadSize) \
2142 _INST(MotionControl, 1, setLookAheadSize, size) \
2143 _INST(MotionControl, 3, pathOffsetSupv, min, max, strategy) \
2144 _INST(MotionControl, 4, pathBufferFilter, name, order, fd, fs)
2145
2146// clang-format on
2147} // namespace common_interface
2148} // namespace arcs
2149
2150#endif // AUBO_SDK_MOTION_CONTROL_INTERFACE_H
int resumeMoveJoint(const std::vector< double > &q, double a, double v, double duration)
通过关节运动移动到暂停点的位置
int pathOffsetLimits(double v, double a)
设置偏移的最大速度和最大加速度 仅对pathOffsetSet中 type=1 有效
int followJoint(const std::vector< double > &q)
关节空间跟随
int setLookAheadSize(int size)
设置前瞻段数 1.
int jointOffsetDisable()
关节偏移失能
int followLine(const std::vector< double > &pose)
笛卡尔空间跟随
int stopJoint(double acc)
关节空间停止运动
int speedJoint(const std::vector< double > &qd, double a, double t)
关节空间速度跟随
int moveCircle2(const CircleParameters &param)
高级圆弧或者圆周运动
int getServoModeSelect()
获取伺服运动模式
int pathOffsetSupv(const std::vector< double > &min, const std::vector< double > &max, int strategy)
监控轨迹偏移范围
int getTrajectoryQueueSize()
获取已经入队的运动规划插补点数量
int clearPath()
ClearPath (Clear Path) clears the whole motion path on the current motion path level (base level or S...
std::vector< std::vector< double > > getFuturePathPointsJoint()
获取未来路径上的轨迹点
int conveyorTrackStop(double a)
终止传送带跟随
int jointOffsetSet(const std::vector< double > &offset, int type=1)
设置关节偏移
int resumeSpeedLine(const std::vector< double > &xd, double a, double t)
笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
double getMotionLeftTime(int id)
获取指定ID的运动指令段的剩余执行时间
int pathBufferAlloc(const std::string &name, int type, int size)
新建一个路径点缓存
int servoCartesian(const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain)
笛卡尔空间伺服
double getSpeedFraction()
获取速度和加速度比例,默认为 1 可以通过 setSpeedFraction 接口设置
std::vector< double > getPauseJointPositions()
getPauseJointPositions
int startMove()
StartMove is used to resume robot, external axes movement and belonging process after the movement ha...
int storePath(bool keep_sync)
storePath
int moveJoint(const std::vector< double > &q, double a, double v, double blend_radius, double duration)
添加关节运动
bool isBlending()
是否处交融区
int moveSpline(const std::vector< double > &q, double a, double v, double duration)
在关节空间做样条插值
int resumeMoveLine(const std::vector< double > &pose, double a, double v, double duration)
通过直线运动移动到暂停点的位置
int stopLine(double acc, double acc_rot)
笛卡尔空间停止运动
int resumeStopLine(double acc, double acc_rot)
笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
std::tuple< std::string, std::vector< double > > getWorkObjectHold()
getWorkObjectHold
int moveCircle(const std::vector< double > &via_pose, const std::vector< double > &end_pose, double a, double v, double blend_radius, double duration)
添加圆弧运动
int speedFractionCritical(bool enable)
速度比例设置临界区,使能之后速度比例被强制设定为1.
std::vector< std::string > pathBufferList()
列出所有缓存路径的名字
int stopMove(bool quick, bool all_tasks)
StopMove is used to stop robot and external axes movements and any belonging process temporarily.
int jointOffsetEnable()
关节偏移使能
ARCS_DEPRECATED bool isServoModeEnabled()
判断伺服模式是否使能 使用 getServoModeSelect 替代
int pathOffsetDisable()
路径偏移失能
int conveyorTrackCircle(int encoder_id, const std::vector< double > &center, int tick_per_revo, bool rotate_tool)
圆形传送带跟随
int conveyorTrackLine(int encoder_id, const std::vector< double > &direction, int tick_per_meter)
线性传送带跟随
int getQueueSize()
获取已经入队的指令段(INST)数量,运动指令包括 moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令
int movePathBuffer(const std::string &name)
执行缓存的路径
int moveIntersection(const std::vector< std::vector< double > > &poses, double a, double v, double main_pipe_radius, double sub_pipe_radius, double normal_distance, double normal_alpha)
相贯线接口
int pathBufferAppend(const std::string &name, const std::vector< std::vector< double > > &waypoints)
向路径缓存添加路点
int getLookAheadSize()
获取前瞻段数
int moveLine(const std::vector< double > &pose, double a, double v, double blend_radius, double duration)
添加直线运动
int resumeSpeedJoint(const std::vector< double > &qd, double a, double t)
关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
int moveProcess(const std::vector< double > &pose, double a, double v, double blend_radius)
添加工艺运动
int pathBufferFilter(const std::string &name, int order, double fd, double fs)
关节空间路径滤波器
bool pathBufferValid(const std::string &name)
指定名字的buffer是否有效
ARCS_DEPRECATED int setServoMode(bool enable)
设置伺服模式 使用 setServoModeSelect 替代
int setCirclePathMode(int mode)
设置圆弧路径模式
int setServoModeSelect(int mode)
设置伺服运动模式
int speedLine(const std::vector< double > &xd, double a, double t)
笛卡尔空间速度跟随
double getDuration(int id)
获取指定ID的运动指令段的预期执行时间
int trackCartesian(const std::vector< double > &pose, double t, double smooth_scale, double delay_sacle)
跟踪运动,用于执行离线轨迹、透传用户规划轨迹等 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
int pathOffsetSet(const std::vector< double > &offset, int type=0)
设置路径偏移
int servoJointWithAxes(const std::vector< double > &q, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
double getProgress()
获取当前运动指令段的执行进度
int pathOffsetCoordinate(int ref_coord)
设置偏移的参考坐标系 仅对pathOffsetSet中 type=1 有效
int pathOffsetEnable()
路径偏移使能
int moveSpiral(const SpiralParameters &param, double blend_radius, double v, double a, double t)
螺旋线运动
int weaveStart(const std::string &params)
开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params 进行摆动
int pathBufferFree(const std::string &name)
释放路径缓存
int setFuturePointSamplePeriod(double sample_time)
设置未来路径上点的采样时间间隔
double getEqradius()
获取等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动 可以通过 setEqradius 设置,默认为1
int setWorkObjectHold(const std::string &module_name, const std::vector< double > &mounting_pose)
当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
int setEqradius(double eqradius)
设置等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
int getExecId()
获取当前正在插补的运动指令段的ID
int setSpeedFraction(double fraction)
动态调整机器人运行速度和加速度比例 (0., 1.
int resumeStopJoint(double acc)
关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
int trackJoint(const std::vector< double > &q, double t, double smooth_scale, double delay_sacle)
跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
bool isSpeedFractionCritical()
是否处于速度比例设置临界区
int servoJoint(const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain)
关节空间伺服
int pathBufferEval(const std::string &name, const std::vector< double > &a, const std::vector< double > &v, double t)
计算、优化等耗时操作,传入的参数相同时不会重新计算
int servoCartesianWithAxes(const std::vector< double > &pose, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
std::shared_ptr< MotionControl > MotionControlPtr
PathBufferType
pathBuffer类型
@ PathBuffer_JointSpline
3: 关节B样条插值,最少三个点 废弃,建议用5替代,现在实际是关节空间 CUBIC_SPLINE
@ PathBuffer_CubicSpline
2: cubic_spline(录制的轨迹)
@ PathBuffer_TOPPRA
1: toppra 时间最优路径规划
@ PathBuffer_JointSplineC
4:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿 废弃,建议用6替代,现在实际是关节空间 CUBIC_SPLINE
@ PathBuffer_JointBSplineC
6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
数据类型的定义