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 *
755 * @param q 继续运动起始位置
756 * @param move_type 0:关节空间 1:笛卡尔空间
757 * @param blend_radius 交融半径
758 * @param qdmax 关节运动最大速度(6维度数据)
759 * @param qddmax 关节运动最大加速度(6维度数据)
760 * @param vmax 直线运动最大线速度,角速度(2维度数据)
761 * @param amax 直线运动最大线加速度,角加速度(2维度数据)
762 * @return 成功返回0; 失败返回错误码
763 * AUBO_BAD_STATE
764 * AUBO_BUSY
765 * -AUBO_BAD_STATE
766 *
767 * @throws arcs::common_interface::AuboException
768 *
769 * @par Python函数原型
770 * setResumeStartPoint(self: pyaubo_sdk.MotionControl,
771 * arg0:List[float],arg1: int, arg2: float,arg3: List[float], arg4:
772 * List[float],arg5:float,arg5:float) -> int
773 *
774 * @par Lua函数原型
775 * setResumeStartPoint(q : table, move_type: number,blend_radius:
776 * number, qdmax: table, qddmax:
777 * table,vmax:number,amax:number) -> nil
778 *
779 * @par JSON-RPC请求示例
780 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setResumeStartPoint","params":[[0,0,0,0,0,0],1,1,[0,0,0,0,0,0],[0,0,0,0,0,0],1,1],"id":1}
781 *
782 * @par JSON-RPC响应示例
783 * {"id":1,"jsonrpc":"2.0","result":0}
784 *
785 */
786 int setResumeStartPoint(const std::vector<double> &q, int move_type,
787 double blend_radius,
788 const std::vector<double> &qdmax,
789 const std::vector<double> &qddmax,
790 const std::vector<double> &vmax,
791 const std::vector<double> &amax);
792 /**
793 * 获取继续运动模式
794 *
795 * @return 0:继续运动起始点为暂停点 1:继续运动起始点为指定点
796 *
797 * @throws arcs::common_interface::AuboException
798 *
799 * @par Python函数原型
800 * getResumeMode(self: pyaubo_sdk.MotionControl) -> int
801 *
802 * @par Lua函数原型
803 * getResumeMode() -> int
804 *
805 * @par JSON-RPC请求示例
806 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getResumeMode","params":[],"id":1}
807 *
808 * @par JSON-RPC响应示例
809 * {"id":1,"jsonrpc":"2.0","result":false}
810 *
811 */
813
814 /**
815 * 设置伺服模式
816 * 使用 setServoModeSelect 替代
817 *
818 * @param enable 是否使能
819 * @return 成功返回0; 失败返回错误码
820 * AUBO_BAD_STATE
821 * AUBO_BUSY
822 * -AUBO_BAD_STATE
823 *
824 * @throws arcs::common_interface::AuboException
825 *
826 * @par Python函数原型
827 * setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
828 *
829 * @par Lua函数原型
830 * setServoMode(enable: boolean) -> nil
831 *
832 * @par JSON-RPC请求示例
833 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
834 *
835 * @par JSON-RPC响应示例
836 * {"id":1,"jsonrpc":"2.0","result":0}
837 *
838 */
839 ARCS_DEPRECATED int setServoMode(bool enable);
840
841 /**
842 * 判断伺服模式是否使能
843 * 使用 getServoModeSelect 替代
844 *
845 * @return 已使能返回true,反之则返回false
846 *
847 * @throws arcs::common_interface::AuboException
848 *
849 * @par Python函数原型
850 * isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
851 *
852 * @par Lua函数原型
853 * isServoModeEnabled() -> boolean
854 *
855 * @par JSON-RPC请求示例
856 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
857 *
858 * @par JSON-RPC响应示例
859 * {"id":1,"jsonrpc":"2.0","result":false}
860 *
861 */
862 ARCS_DEPRECATED bool isServoModeEnabled();
863
864 /**
865 * 设置伺服运动模式
866 *
867 * @param mode
868 * 0-退出伺服模式
869 * 1-规划伺服模式
870 * 2-透传模式(直接下发)
871 * 3-透传模式(缓存)
872 * @return
873 *
874 * @par JSON-RPC请求示例
875 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
876 *
877 * @par JSON-RPC响应示例
878 * {"id":1,"jsonrpc":"2.0","result":0}
879 *
880 */
881 int setServoModeSelect(int mode);
882
883 /**
884 * 获取伺服运动模式
885 *
886 * @return
887 *
888 * @par JSON-RPC请求示例
889 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
890 *
891 * @par JSON-RPC响应示例
892 * {"id":1,"jsonrpc":"2.0","result":0}
893 *
894 */
896
897 /**
898 * 关节空间伺服
899 *
900 * 目前可用参数只有 q 和 t;
901 * @param q 关节角, 单位 rad,
902 * @param a 加速度, 单位 rad/s^2,
903 * @param v 速度,单位 rad/s,
904 * @param t 运行时间,单位 s \n
905 * t 值越大,机器臂运动越慢,反之,运动越快;
906 * 该参数最优值为连续调用 servoJoint 接口的间隔时间。
907 * @param lookahead_time 前瞻时间,单位 s \n
908 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
909 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
910 * 该参数最优值为一个控制周期。
911 * @param gain 比例增益
912 * 跟踪目标位置的比例增益[100, 200],
913 * 用于控制运动的顺滑性和精度,
914 * 比例增益越大,到达目标位置的时间越长,超调量越小。
915 *
916 * @retval 0 成功
917 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
918 * Normal、ReducedMode、Recovery 状态
919 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
920 * @retval AUBO_BUSY(3) 上一条指令正在执行中
921 * @retval -AUBO_BAD_STATE(-1)
922 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
923 * 未找到,或者当前机器人模式非 Running
924 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
925 * @retval -AUBO_INVL_ARGUMENT(-5) 轨迹位置超限或速度超限
926 * @retval -AUBO_REQUEST_IGNORE(-13) 当前处于非 servo 模式
927
928 * @throws arcs::common_interface::AuboException
929 *
930 * @par Python函数原型
931 * servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
932 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
933 *
934 * @par Lua函数原型
935 * servoJoint(q: table, a: number, v: number, t: number, lookahead_time:
936 * number, gain: number) -> nil
937 *
938 * @par JSON-RPC请求示例
939 * {"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
940 *
941 * @par JSON-RPC响应示例
942 * {"id":1,"jsonrpc":"2.0","result":-13}
943 *
944 */
945 int servoJoint(const std::vector<double> &q, double a, double v, double t,
946 double lookahead_time, double gain);
947
948 /**
949 * 笛卡尔空间伺服
950 *
951 * 目前可用参数只有 pose 和 t;
952 * @param pose 位姿, 单位 m,
953 * @param a 加速度, 单位 m/s^2,
954 * @param v 速度,单位 m/s,
955 * @param t 运行时间,单位 s \n
956 * t 值越大,机器臂运动越慢,反之,运动越快;
957 * 该参数最优值为连续调用 servoCartesian 接口的间隔时间。
958 * @param lookahead_time 前瞻时间,单位 s \n
959 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
960 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
961 * 该参数最优值为一个控制周期。
962 * @param gain 比例增益
963 * 跟踪目标位置的比例增益[100, 200],
964 * 用于控制运动的顺滑性和精度,
965 * 比例增益越大,到达目标位置的时间越长,超调量越小。
966 *
967 * @retval 0 成功
968 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
969 * Normal、ReducedMode、Recovery 状态
970 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
971 * @retval AUBO_BUSY(3) 上一条指令正在执行中
972 * @retval -AUBO_BAD_STATE(-1)
973 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
974 * 未找到,或者当前机器人模式非 Running
975 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
976 * @retval -AUBO_INVL_ARGUMENT(-5) 轨迹位置超限或速度超限
977 * @retval -AUBO_REQUEST_IGNORE(-13) 当前处于非 servo 模式
978 * @retval -AUBO_IK_NO_CONVERGE(-23) 逆解计算不收敛,计算出错;
979 * @retval -AUBO_IK_OUT_OF_RANGE(-24) 逆解计算超出机器人最大限制;
980 * @retval AUBO_IK_CONFIG_DISMATCH(-25) 逆解输入配置存在错误;
981 * @retval -AUBO_IK_JACOBIAN_FAILED(-26) 逆解雅可比矩阵计算失败;
982 * @retval -AUBO_IK_NO_SOLU(-27) 目标点存在解析解,但均不满足选解条件;
983 * @retval -AUBO_IK_UNKOWN_ERROR(-28) 逆解返回未知类型错误;
984 *
985 * @throws arcs::common_interface::AuboException
986 *
987 * @par Python函数原型
988 * servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
989 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
990 *
991 * @par Lua函数原型
992 * servoCartesian(pose: table, a: number, v: number, t: number,
993 * lookahead_time: number, gain: number) -> nil
994 *
995 * @par JSON-RPC请求示例
996 * {"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}
997 *
998 * @par JSON-RPC响应示例
999 * {"id":1,"jsonrpc":"2.0","result":-13}
1000 *
1001 */
1002 int servoCartesian(const std::vector<double> &pose, double a, double v,
1003 double t, double lookahead_time, double gain);
1004
1005 /**
1006 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
1007 *
1008 * @param q
1009 * @param extq
1010 * @param t
1011 * @param smooth_scale
1012 * @param delay_sacle
1013 * @return
1014 */
1015 int servoJointWithAxes(const std::vector<double> &q,
1016 const std::vector<double> &extq, double a, double v,
1017 double t, double lookahead_time, double gain);
1018
1019 int servoJointWithAxisGroup(const std::vector<double> &q, double a,
1020 double v, double t, double lookahead_time,
1021 double gain, const std::string &group_name,
1022 const std::vector<double> &extq);
1023
1024 /**
1025 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
1026 * 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度
1027 * (由软件内部直接做逆解)
1028 *
1029 * @param pose
1030 * @param extq
1031 * @param t
1032 * @param smooth_scale
1033 * @param delay_sacle
1034 * @return
1035 */
1036 int servoCartesianWithAxes(const std::vector<double> &pose,
1037 const std::vector<double> &extq, double a,
1038 double v, double t, double lookahead_time,
1039 double gain);
1040
1041 int servoCartesianWithAxisGroup(const std::vector<double> &pose, double a,
1042 double v, double t, double lookahead_time,
1043 double gain, const std::string &group_name,
1044 const std::vector<double> &extq);
1045
1046 /**
1047 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
1048 *
1049 * @param q
1050 * @param smooth_scale
1051 * @param delay_sacle
1052 * @return
1053 *
1054 * @par JSON-RPC请求示例
1055 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
1056 *
1057 * @par JSON-RPC响应示例
1058 * {"id":1,"jsonrpc":"2.0","result":0}
1059 *
1060 */
1061 int trackJoint(const std::vector<double> &q, double t, double smooth_scale,
1062 double delay_sacle);
1063
1064 /**
1065 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
1066 * 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度
1067 * (由软件内部直接做逆解)
1068 *
1069 * @param pose
1070 * @param t
1071 * @param smooth_scale
1072 * @param delay_sacle
1073 * @return
1074 *
1075 * @par JSON-RPC请求示例
1076 * {"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}
1077 *
1078 * @par JSON-RPC响应示例
1079 * {"id":1,"jsonrpc":"2.0","result":0}
1080 *
1081 */
1082 int trackCartesian(const std::vector<double> &pose, double t,
1083 double smooth_scale, double delay_sacle);
1084
1085 /**
1086 * 关节空间跟随
1087 *
1088 * @note 暂未实现
1089 *
1090 * @throws arcs::common_interface::AuboException
1091 *
1092 * @par Python函数原型
1093 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
1094 *
1095 * @par Lua函数原型
1096 * followJoint(q: table) -> nil
1097 *
1098 */
1099 int followJoint(const std::vector<double> &q);
1100
1101 /**
1102 * 笛卡尔空间跟随
1103 *
1104 * @note 暂未实现
1105 *
1106 * @throws arcs::common_interface::AuboException
1107 *
1108 * @par Python函数原型
1109 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
1110 *
1111 * @par Lua函数原型
1112 * followLine(pose: table) -> nil
1113 *
1114 */
1115 int followLine(const std::vector<double> &pose);
1116
1117 /**
1118 * 关节空间速度跟随
1119 *
1120 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1121 *
1122 * @param qd 目标关节速度, 单位 rad/s
1123 * @param a 主轴的加速度, 单位 rad/s^2
1124 * @param t 函数返回所需要的时间, 单位 s \n
1125 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1126 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。\n
1127 * 如果没有达到目标速度,会减速到零。
1128 * 如果达到了目标速度就是按照目标速度匀速运动。
1129 * @retval 0 成功
1130 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1131 * Normal、ReducedMode、Recovery 状态
1132 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1133 * @retval -AUBO_BAD_STATE(-1)
1134 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1135 * 未找到,或者当前机器人模式非 Running
1136 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1137 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组qd的长度小于当前机器臂的自由度
1138 *
1139 * @throws arcs::common_interface::AuboException
1140 *
1141 * @par Python函数原型
1142 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1143 * float, arg2: float) -> int
1144 *
1145 * @par Lua函数原型
1146 * speedJoint(qd: table, a: number, t: number) -> nil
1147 *
1148 * @par JSON-RPC请求示例
1149 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
1150 *
1151 * @par JSON-RPC响应示例
1152 * {"id":1,"jsonrpc":"2.0","result":0}
1153 *
1154 */
1155 int speedJoint(const std::vector<double> &qd, double a, double t);
1156
1157 /**
1158 * 关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
1159 *
1160 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1161 *
1162 * @param qd 目标关节速度, 单位 rad/s
1163 * @param a 主轴的加速度, 单位 rad/s^2
1164 * @param t 函数返回所需要的时间, 单位 s
1165 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1166 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1167 * 如果没有达到目标速度,会减速到零。
1168 * 如果达到了目标速度就是按照目标速度匀速运动。
1169 * @return 成功返回0; 失败返回错误码
1170 * AUBO_BUSY
1171 * -AUBO_INVL_ARGUMENT
1172 * -AUBO_BAD_STATE
1173 *
1174 * @throws arcs::common_interface::AuboException
1175 *
1176 * @par Python函数原型
1177 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1178 * float, arg2: float) -> int
1179 *
1180 *
1181 * @par Lua函数原型
1182 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
1183 *
1184 * @par JSON-RPC请求示例
1185 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
1186 *
1187 * @par JSON-RPC响应示例
1188 * {"id":1,"jsonrpc":"2.0","result":-1}
1189 *
1190 */
1191 int resumeSpeedJoint(const std::vector<double> &qd, double a, double t);
1192
1193 /**
1194 * 笛卡尔空间速度跟随
1195 *
1196 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1197 *
1198 * @param xd 工具速度, 单位 m/s
1199 * @param a 工具位置加速度, 单位 m/s^2
1200 * @param t 函数返回所需要的时间, 单位 s \n
1201 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1202 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1203 * 如果没有达到目标速度,会减速到零。
1204 * 如果达到了目标速度就是按照目标速度匀速运动。
1205 * @retval 0 成功
1206 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1207 * Normal、ReducedMode、Recovery 状态
1208 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1209 * @retval -AUBO_BAD_STATE(-1)
1210 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1211 * 未找到,或者当前机器人模式非 Running
1212 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1213 *
1214 * @throws arcs::common_interface::AuboException
1215 *
1216 * @par Python函数原型
1217 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1218 * arg2: float) -> int
1219 *
1220 * @par Lua函数原型
1221 * speedLine(pose: table, a: number, t: number) -> nil
1222 *
1223 * @par JSON-RPC请求示例
1224 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
1225 *
1226 * @par JSON-RPC响应示例
1227 * {"id":1,"jsonrpc":"2.0","result":0}
1228 *
1229 */
1230 int speedLine(const std::vector<double> &xd, double a, double t);
1231
1232 /**
1233 * 笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
1234 *
1235 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1236 *
1237 * @param xd 工具速度, 单位 m/s
1238 * @param a 工具位置加速度, 单位 m/s^2
1239 * @param t 函数返回所需要的时间, 单位 s \n
1240 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1241 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1242 * 如果没有达到目标速度,会减速到零。
1243 * 如果达到了目标速度就是按照目标速度匀速运动。
1244 * @return 成功返回0; 失败返回错误码
1245 * -AUBO_BAD_STATE
1246 *
1247 * @throws arcs::common_interface::AuboException
1248 *
1249 * @par Python函数原型
1250 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1251 * float, arg2: float) -> int
1252 *
1253 * @par Lua函数原型
1254 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
1255 *
1256 * @par JSON-RPC请求示例
1257 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
1258 *
1259 * @par JSON-RPC响应示例
1260 * {"id":1,"jsonrpc":"2.0","result":-1}
1261 *
1262 */
1263 int resumeSpeedLine(const std::vector<double> &xd, double a, double t);
1264
1265 /**
1266 * 在关节空间做样条插值
1267 *
1268 * @param q 关节角度,如果传入参数维度为0,表示样条运动结束
1269 * @param a 加速度, 单位 rad/s^2,
1270 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
1271 * @param v 速度, 单位 rad/s,
1272 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
1273 * @param duration
1274 * @return 成功返回0; 失败返回错误码
1275 * AUBO_BUSY
1276 * AUBO_BAD_STATE
1277 * -AUBO_BAD_STATE
1278 *
1279 * @throws arcs::common_interface::AuboException
1280 *
1281 * @par Python函数原型
1282 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1283 * float, arg2: float, arg3: float) -> int
1284 *
1285 * @par Lua函数原型
1286 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
1287 *
1288 * @par JSON-RPC请求示例
1289 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
1290 *
1291 * @par JSON-RPC响应示例
1292 * {"id":1,"jsonrpc":"2.0","result":0}
1293 *
1294 */
1295 int moveSpline(const std::vector<double> &q, double a, double v,
1296 double duration);
1297
1298 /**
1299 * 添加关节运动
1300 *
1301 * @param q 关节角, 单位 rad
1302 * @param a 加速度, 单位 rad/s^2,
1303 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
1304 * @param v 速度, 单位 rad/s,
1305 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
1306 * @param blend_radius 交融半径, 单位 m
1307 * @param duration 运行时间,单位 s \n
1308 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1309 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1310 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1311 * 当 duration = 0的时候,
1312 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1313 * 如果duration不等于0,a 和 v 的值将被忽略。
1314 * @retval 0 成功
1315 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1316 * Normal、ReducedMode、Recovery 状态
1317 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
1318 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1319 * @retval -AUBO_BAD_STATE(-1)
1320 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1321 * 未找到,或者当前机器人模式非 Running
1322 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1323 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组q的长度小于当前机器臂的自由度
1324 *
1325 * @throws arcs::common_interface::AuboException
1326 *
1327 * @par Python函数原型
1328 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1329 * arg2: float, arg3: float, arg4: float) -> int
1330 *
1331 * @par Lua函数原型
1332 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
1333 * number) -> nil
1334 *
1335 * @par JSON-RPC请求示例
1336 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
1337 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
1338 *
1339 * @par JSON-RPC响应示例
1340 * {"id":1,"jsonrpc":"2.0","result":0}
1341 *
1342 */
1343 int moveJoint(const std::vector<double> &q, double a, double v,
1344 double blend_radius, double duration);
1345
1346 /**
1347 * 机器人与外部轴同步运动
1348 *
1349 * @param group_name
1350 * @param q
1351 * @param a
1352 * @param v
1353 * @param blend_radius
1354 * @param duration
1355 * @return
1356 */
1357 int moveJointWithAxisGroup(const std::vector<double> &q, double a, double v,
1358 double blend_radius, double duration,
1359 const std::string &group_name,
1360 const std::vector<double> &extq);
1361
1362 /**
1363 * 通过关节运动移动到暂停点的位置
1364 *
1365 * @param q 关节角, 单位 rad
1366 * @param a 加速度, 单位 rad/s^2
1367 * @param v 速度, 单位 rad/s
1368 * @param duration 运行时间,单位 s \n
1369 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1370 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1371 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1372 * 当 duration = 0的时候,
1373 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1374 * 如果duration不等于0,a 和 v 的值将被忽略。
1375 * @return 成功返回0;失败返回错误码
1376 * -AUBO_INVL_ARGUMENT
1377 * -AUBO_BAD_STATE
1378 *
1379 * @throws arcs::common_interface::AuboException
1380 *
1381 * @par Python函数原型
1382 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1383 * float, arg2: float, arg3: float) -> int
1384 *
1385 * @par Lua函数原型
1386 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
1387 *
1388 * @par JSON-RPC请求示例
1389 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
1390 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
1391 *
1392 * @par JSON-RPC响应示例
1393 * {"id":1,"jsonrpc":"2.0","result":-1}
1394 */
1395 int resumeMoveJoint(const std::vector<double> &q, double a, double v,
1396 double duration);
1397
1398 /**
1399 * 添加直线运动
1400 *
1401 * @param pose 目标位姿
1402 * @param a 加速度(如果位置变化小于1mm,姿态变化大于 1e-4
1403 * rad,此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
1404 * 最大值可通过RobotConfig类中的接口getTcpMaxAccelerations()来获取
1405 * @param v 速度(如果位置变化小于1mm,姿态变化大于 1e-4
1406 * rad,此速度会被作为角速度,单位 rad/s.否则为线速度,单位 m/s)
1407 * 最大值可通过RobotConfig类中的接口getTcpMaxSpeeds()来获取
1408 * @param blend_radius 交融半径,单位 m,值介于0.001和1之间
1409 * @param duration 运行时间,单位 s \n
1410 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1411 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1412 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1413 * 当 duration = 0的时候,
1414 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1415 * 如果duration不等于0,a 和 v 的值将被忽略。
1416 * @retval 0 成功
1417 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1418 * Normal、ReducedMode、Recovery 状态
1419 * @retval AUBO_QUEUE_FULL(2) 轨迹队列已满
1420 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1421 * @retval -AUBO_BAD_STATE(-1)
1422 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1423 * 未找到,或者当前机器人模式非 Running
1424 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1425 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组 pose
1426 * 的长度小于当前机器臂的自由度
1427 *
1428 * @throws arcs::common_interface::AuboException
1429 *
1430 * @par Python函数原型
1431 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1432 * arg2: float, arg3: float, arg4: float) -> int
1433 *
1434 * @par Lua函数原型
1435 * moveLine(pose: table, a: number, v: number, blend_radius: number,
1436 * duration: number) -> nil
1437 *
1438 * @par JSON-RPC请求示例
1439 * {"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}
1440 *
1441 * @par JSON-RPC响应示例
1442 * {"id":1,"jsonrpc":"2.0","result":0}
1443 *
1444 */
1445 int moveLine(const std::vector<double> &pose, double a, double v,
1446 double blend_radius, double duration);
1447
1448 /**
1449 * 直线运动与外部轴同步运动
1450 *
1451 * @param group_name
1452 * @param pose
1453 * @param a
1454 * @param v
1455 * @param blend_radius
1456 * @param duration
1457 * @return
1458 */
1459 int moveLineWithAxisGroup(const std::vector<double> &pose, double a,
1460 double v, double blend_radius, double duration,
1461 const std::string &group_name,
1462 const std::vector<double> &extq);
1463
1464 /**
1465 * 添加工艺运动
1466 *
1467 * @param pose
1468 * @param a
1469 * @param v
1470 * @param blend_radius
1471 * @return 成功返回0;失败返回错误码
1472 * AUBO_BAD_STATE
1473 * AUBO_BUSY
1474 * -AUBO_INVL_ARGUMENT
1475 * -AUBO_BAD_STATE
1476 *
1477 * @throws arcs::common_interface::AuboException
1478 *
1479 * @par JSON-RPC请求示例
1480 * {"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}
1481 *
1482 * @par JSON-RPC响应示例
1483 * {"id":1,"jsonrpc":"2.0","result":0}
1484 *
1485 */
1486 int moveProcess(const std::vector<double> &pose, double a, double v,
1487 double blend_radius);
1488
1489 /**
1490 * 通过直线运动移动到暂停点的位置
1491 *
1492 * @param pose 目标位姿
1493 * @param a 加速度, 单位 m/s^2
1494 * @param v 速度, 单位 m/s
1495 * @param duration 运行时间,单位 s \n
1496 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1497 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1498 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1499 * 当 duration = 0的时候,
1500 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1501 * 如果duration不等于0,a 和 v 的值将被忽略。
1502 * @return 成功返回0;失败返回错误码
1503 * -AUBO_INVL_ARGUMENT
1504 * -AUBO_BAD_STATE
1505 *
1506 * @throws arcs::common_interface::AuboException
1507 *
1508 * @par Python函数原型
1509 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1510 * float, arg2: float, arg3: float) -> int
1511 *
1512 * @par Lua函数原型
1513 * resumeMoveLine(pose: table, a: number, v: number,duration: number) -> nil
1514 *
1515 * @par JSON-RPC请求示例
1516 * {"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}
1517 *
1518 * @par JSON-RPC响应示例
1519 * {"id":1,"jsonrpc":"2.0","result":0}
1520 *
1521 */
1522 int resumeMoveLine(const std::vector<double> &pose, double a, double v,
1523 double duration);
1524
1525 /**
1526 * 添加圆弧运动
1527 *
1528 * @todo 可以由多段圆弧组成圆周运动
1529 *
1530 * @param via_pose 圆弧运动途中点的位姿
1531 * @param end_pose 圆弧运动结束点的位姿
1532 * @param a 加速度(如果via_pose与上一个路点位置变化小于1mm,姿态变化大于 1e-4
1533 * rad, 此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
1534 * @param v 速度(如果via_pose与上一个路点位置变化小于1mm, 姿态变化大于 1e-4
1535 * rad, 此速度会被作为角速度, 单位 rad / s.否则为线速度, 单位 m / s)
1536 * @param blend_radius 交融半径,单位: m
1537 * @param duration 运行时间,单位: s \n
1538 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1539 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1540 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1541 * 当 duration = 0 的时候,
1542 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1543 * 如果duration不等于0,a 和 v 的值将被忽略。
1544 * @return 成功返回0;失败返回错误码
1545 * AUBO_BAD_STATE
1546 * AUBO_BUSY
1547 * -AUBO_INVL_ARGUMENT
1548 * -AUBO_BAD_STATE
1549 *
1550 * @throws arcs::common_interface::AuboException
1551 *
1552 * @par Python函数原型
1553 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1554 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
1555 *
1556 * @par Lua函数原型
1557 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
1558 * blend_radius: number, duration: number) -> nil
1559 *
1560 * @par JSON-RPC请求示例
1561 * {"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}
1562 *
1563 * @par JSON-RPC响应示例
1564 * {"id":1,"jsonrpc":"2.0","result":0}
1565 *
1566 */
1567 int moveCircle(const std::vector<double> &via_pose,
1568 const std::vector<double> &end_pose, double a, double v,
1569 double blend_radius, double duration);
1570
1571 /**
1572 * moveCircle 与外部轴同步运动
1573 *
1574 * @param group_name
1575 * @param via_pose
1576 * @param end_pose
1577 * @param a
1578 * @param v
1579 * @param blend_radius
1580 * @param duration
1581 * @return
1582 */
1583 int moveCircleWithAxisGroup(const std::vector<double> &via_pose,
1584 const std::vector<double> &end_pose, double a,
1585 double v, double blend_radius, double duration,
1586 const std::string &group_name,
1587 const std::vector<double> &extq);
1588
1589 /**
1590 * 设置圆弧路径模式
1591 *
1592 * @param mode 模式 \n
1593 * 0:工具姿态相对于圆弧路径点坐标系保持不变 \n
1594 * 1:姿态线性变化,绕着空间定轴转动,从起始点姿态变化到目标点姿态 \n
1595 * 2:从起点姿态开始经过中间点姿态,变化到目标点姿态
1596 * @return 成功返回0;失败返回错误码
1597 * AUBO_BAD_STATE
1598 * AUBO_BUSY
1599 * -AUBO_INVL_ARGUMENT
1600 * -AUBO_BAD_STATE
1601 *
1602 * @throws arcs::common_interface::AuboException
1603 *
1604 * @par Python函数原型
1605 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
1606 *
1607 * @par Lua函数原型
1608 * setCirclePathMode(mode: number) -> nil
1609 *
1610 * @par JSON-RPC请求示例
1611 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
1612 *
1613 * @par JSON-RPC响应示例
1614 * {"id":1,"jsonrpc":"2.0","result":0}
1615 *
1616 */
1617 int setCirclePathMode(int mode);
1618
1619 /**
1620 * 高级圆弧或者圆周运动
1621 *
1622 * @param param 圆周运动参数
1623 * @return 成功返回0;失败返回错误码
1624 * AUBO_BAD_STATE
1625 * AUBO_BUSY
1626 * -AUBO_INVL_ARGUMENT
1627 * -AUBO_BAD_STATE
1628 *
1629 * @throws arcs::common_interface::AuboException
1630 *
1631 * @par Python函数原型
1632 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
1633 * arcs::common_interface::CircleParameters) -> int
1634 *
1635 * @par Lua函数原型
1636 * moveCircle2(param: table) -> nil
1637 *
1638 * @par JSON-RPC请求示例
1639 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
1640 * "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,
1641 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
1642 *
1643 * @par JSON-RPC响应示例
1644 * {"id":1,"jsonrpc":"2.0","result":0}
1645 *
1646 */
1648
1649 /**
1650 * 新建一个路径点缓存
1651 *
1652 * @param name 指定路径的名字
1653 * @param type 路径的类型 \n
1654 * 1: toppra 时间最优路径规划 \n
1655 * 2: cubic_spline(录制的轨迹) \n
1656 * 3: 关节B样条插值,最少三个点
1657 * @param size 缓存区大小
1658 * @return 新建成功返回 AUBO_OK(0)
1659 *
1660 * @throws arcs::common_interface::AuboException
1661 *
1662 * @par Python函数原型
1663 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
1664 * arg2: int) -> int
1665 *
1666 * @par Lua函数原型
1667 * pathBufferAlloc(name: string, type: number, size: number) -> nil
1668 *
1669 * @par JSON-RPC请求示例
1670 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
1671 *
1672 * @par JSON-RPC响应示例
1673 * {"id":1,"jsonrpc":"2.0","result":0}
1674 *
1675 */
1676 int pathBufferAlloc(const std::string &name, int type, int size);
1677
1678 /**
1679 * 向路径缓存添加路点
1680 *
1681 * @param name 路径缓存的名字
1682 * @param waypoints 路点
1683 * @return 成功返回0;失败返回错误码
1684 * -AUBO_INVL_ARGUMENT
1685 * -AUBO_BAD_STATE
1686 *
1687 * @throws arcs::common_interface::AuboException
1688 *
1689 * @par Python函数原型
1690 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1691 * List[List[float]]) -> int
1692 *
1693 * @par Lua函数原型
1694 * pathBufferAppend(name: string, waypoints: table) -> nil
1695 *
1696 * @par JSON-RPC请求示例
1697 * {"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}
1698 *
1699 * @par JSON-RPC响应示例
1700 * {"id":1,"jsonrpc":"2.0","result":0}
1701 *
1702 */
1703 int pathBufferAppend(const std::string &name,
1704 const std::vector<std::vector<double>> &waypoints);
1705
1706 /**
1707 * 计算、优化等耗时操作,传入的参数相同时不会重新计算
1708 *
1709 * @param name 通过pathBufferAlloc新建的路径点缓存的名字
1710 * @param a 关节加速度限制,需要和机器人自由度大小相同,单位 rad/s^2
1711 * @param v 关节速度限制,需要和机器人自由度大小相同,单位 rad/s
1712 * @param t 时间 \n
1713 * pathBufferAlloc 这个接口分配内存的时候要指定类型,
1714 * 根据pathBufferAlloc这个接口的类型:\n
1715 * 类型为1时,表示运动持续时间\n
1716 * 类型为2时,表示采样时间间隔\n
1717 * 类型为3时:t表示运动持续时间\n
1718 * 若 t=0, 则由使用软件内部默认的时间(推荐使用)\n
1719 * 若 t!=0, t需要设置为 路径点数*相邻点时间间隔(points *
1720 * interval,interval >= 0.01)
1721 * @return 成功返回0;失败返回错误码
1722 * -AUBO_INVL_ARGUMENT
1723 * -AUBO_BAD_STATE
1724 *
1725 * @throws arcs::common_interface::AuboException
1726 *
1727 * @par Python函数原型
1728 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1729 * List[float], arg2: List[float], arg3: float) -> int
1730 *
1731 * @par Lua函数原型
1732 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
1733 *
1734 * @par JSON-RPC请求示例
1735 * {"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}
1736 *
1737 * @par JSON-RPC响应示例
1738 * {"id":1,"jsonrpc":"2.0","result":0}
1739 *
1740 */
1741 int pathBufferEval(const std::string &name, const std::vector<double> &a,
1742 const std::vector<double> &v, double t);
1743
1744 /**
1745 * 指定名字的buffer是否有效
1746 *
1747 * buffer需要满足三个条件有效: \n
1748 * 1、buffer存在,已经分配过内存 \n
1749 * 2、传进buffer的点要大于等于buffer的大小 \n
1750 * 3、要执行一次pathBufferEval
1751 *
1752 * @param name buffer的名字
1753 * @return 有效返回true; 无效返回false
1754 *
1755 * @throws arcs::common_interface::AuboException
1756 *
1757 * @par Python函数原型
1758 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
1759 *
1760 * @par Lua函数原型
1761 * pathBufferValid(name: string) -> boolean
1762 *
1763 * @par JSON-RPC请求示例
1764 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
1765 *
1766 * @par JSON-RPC响应示例
1767 * {"id":1,"jsonrpc":"2.0","result":false}
1768 *
1769 */
1770 bool pathBufferValid(const std::string &name);
1771
1772 /**
1773 * 释放路径缓存
1774 *
1775 * @param name 缓存路径的名字
1776 * @return 成功返回0;失败返回错误码
1777 * -AUBO_INVL_ARGUMENT
1778 * -AUBO_BAD_STATE
1779 *
1780 * @throws arcs::common_interface::AuboException
1781 *
1782 * @par Python函数原型
1783 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
1784 *
1785 * @par Lua函数原型
1786 * pathBufferFree(name: string) -> nil
1787 *
1788 * @par JSON-RPC请求示例
1789 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
1790 *
1791 * @par JSON-RPC响应示例
1792 * {"id":1,"jsonrpc":"2.0","result":-5}
1793 *
1794 */
1795 int pathBufferFree(const std::string &name);
1796
1797 /**
1798 * 关节空间路径滤波器
1799 *
1800 * @brief pathBufferFilter
1801 *
1802 * @param name 缓存路径的名称
1803 * @param order 滤波器阶数(一般取2)
1804 * @param fd 截止频率,越小越光滑,但是延迟会大(一般取3-20)
1805 * @param fs 离散数据的采样频率(一般取20-500)
1806 *
1807 * @return 成功返回0
1808 *
1809 * @throws arcs::common_interface::AuboException
1810 *
1811 * @par Python函数原型
1812 * pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
1813 * arg2: float, arg3: float) -> int
1814 *
1815 * @par Lua函数原型
1816 * pathBufferFilter(name: string, order: number, fd: number, fs:number) ->
1817 * nil
1818 */
1819 int pathBufferFilter(const std::string &name, int order, double fd,
1820 double fs);
1821
1822 /**
1823 * 列出所有缓存路径的名字
1824 *
1825 * @return 返回所有缓存路径的名字
1826 *
1827 * @throws arcs::common_interface::AuboException
1828 *
1829 * @par Python函数原型
1830 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
1831 *
1832 * @par Lua函数原型
1833 * pathBufferList() -> table
1834 *
1835 * @par JSON-RPC请求示例
1836 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
1837 *
1838 * @par JSON-RPC响应示例
1839 * {"id":1,"jsonrpc":"2.0","result":[]}
1840 *
1841 */
1842 std::vector<std::string> pathBufferList();
1843
1844 /**
1845 * 执行缓存的路径
1846 *
1847 * @param name 缓存路径的名字
1848 * @return 成功返回0;失败返回错误码
1849 * -AUBO_INVL_ARGUMENT
1850 * -AUBO_BAD_STATE
1851 *
1852 * @throws arcs::common_interface::AuboException
1853 *
1854 * @par Python函数原型
1855 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
1856 *
1857 * @par Lua函数原型
1858 * movePathBuffer(name: string) -> nil
1859 *
1860 * @par JSON-RPC请求示例
1861 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
1862 *
1863 * @par JSON-RPC响应示例
1864 * {"id":1,"jsonrpc":"2.0","result":0}
1865 *
1866 */
1867 int movePathBuffer(const std::string &name);
1868
1869 /**
1870 * 相贯线接口
1871 *
1872 * @param pose由三个示教位姿组成(首先需要运动到起始点,起始点的要求:过主圆柱
1873 * 柱体轴心且与子圆柱体轴线平行的平面与子圆柱体在底部的交点)
1874 * p1:过子圆柱体轴线且与大圆柱体轴线平行的平面,与小圆柱体在左侧顶部的交点
1875 * p2:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在左侧底部的交点
1876 * p3:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在右侧底部的交点
1877 * @param v:速度
1878 * @param a:加速度
1879 * @param main_pipe_radius: 主圆柱体半径
1880 * @param sub_pipe_radius: 子圆柱体半径
1881 * @param normal_distance: 两圆柱体轴线距离
1882 * @param normal_alpha: 两圆柱体轴线的夹角
1883 *
1884 * @return 成功返回0;失败返回错误码
1885 * AUBO_BUSY
1886 * AUBO_BAD_STATE
1887 * -AUBO_INVL_ARGUMENT
1888 * -AUBO_BAD_STATE
1889 *
1890 * @throws arcs::common_interface::AuboException
1891 *
1892 * @par Python函数原型
1893 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1894 float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float) ->
1895 int
1896 *
1897 * @par Lua函数原型
1898 * moveIntersection(poses: table, a: number, v: number,
1899 * main_pipe_radius:number, sub_pipe_radius: number,normal_distance:
1900 * number,normal_alpha: number,) -> nil
1901 */
1902 int moveIntersection(const std::vector<std::vector<double>> &poses,
1903 double a, double v, double main_pipe_radius,
1904 double sub_pipe_radius, double normal_distance,
1905 double normal_alpha);
1906 /**
1907 * 关节空间停止运动
1908 *
1909 * @param acc 关节加速度,单位: rad/s^2
1910 * @return 成功返回0;失败返回错误码
1911 * AUBO_BUSY
1912 * AUBO_BAD_STATE
1913 * -AUBO_INVL_ARGUMENT
1914 * -AUBO_BAD_STATE
1915 *
1916 * @throws arcs::common_interface::AuboException
1917 *
1918 * @par Python函数原型
1919 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
1920 *
1921 * @par Lua函数原型
1922 * stopJoint(acc: number) -> nil
1923 *
1924 * @par JSON-RPC请求示例
1925 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
1926 *
1927 * @par JSON-RPC响应示例
1928 * {"id":1,"jsonrpc":"2.0","result":0}
1929 *
1930 */
1931 int stopJoint(double acc);
1932
1933 /**
1934 * 关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
1935 *
1936 * @param acc 关节加速度,单位: rad/s^2
1937 * @return 成功返回0;失败返回错误码
1938 * AUBO_BUSY
1939 * AUBO_BAD_STATE
1940 * -AUBO_INVL_ARGUMENT
1941 * -AUBO_BAD_STATE
1942 *
1943 * @throws arcs::common_interface::AuboException
1944 *
1945 * @par Python函数原型
1946 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
1947 *
1948 * @par Lua函数原型
1949 * resumeStopJoint(acc: number) -> nil
1950 *
1951 * @par JSON-RPC请求示例
1952 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
1953 *
1954 * @par JSON-RPC响应示例
1955 * {"id":1,"jsonrpc":"2.0","result":-1}
1956 *
1957 */
1958 int resumeStopJoint(double acc);
1959
1960 /**
1961 * 笛卡尔空间停止运动
1962 *
1963 * @param acc 工具加速度, 单位: m/s^2
1964 * @param acc_rot
1965 * @return 成功返回0;失败返回错误码
1966 * AUBO_BUSY
1967 * AUBO_BAD_STATE
1968 * -AUBO_INVL_ARGUMENT
1969 * -AUBO_BAD_STATE
1970 *
1971 * @throws arcs::common_interface::AuboException
1972 *
1973 * @par Python函数原型
1974 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
1975 *
1976 * @par Lua函数原型
1977 * stopLine(acc: number, acc_rot: number) -> nil
1978 *
1979 * @par JSON-RPC请求示例
1980 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
1981 *
1982 * @par JSON-RPC响应示例
1983 * {"id":1,"jsonrpc":"2.0","result":0}
1984 *
1985 */
1986 int stopLine(double acc, double acc_rot);
1987
1988 /**
1989 * 笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
1990 *
1991 * @param acc 位置加速度, 单位: m/s^2
1992 * @param acc_rot 姿态加速度,单位: rad/s^2
1993 * @return 成功返回0;失败返回错误码
1994 * AUBO_BUSY
1995 * AUBO_BAD_STATE
1996 * -AUBO_INVL_ARGUMENT
1997 * -AUBO_BAD_STATE
1998 *
1999 * @throws arcs::common_interface::AuboException
2000 *
2001 * @par Python函数原型
2002 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
2003 * -> int
2004 *
2005 * @par Lua函数原型
2006 * resumeStopLine(acc: number, acc_rot: number) -> nil
2007 *
2008 * @par JSON-RPC请求示例
2009 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
2010 *
2011 * @par JSON-RPC响应示例
2012 * {"id":1,"jsonrpc":"2.0","result":-1}
2013 *
2014 */
2015 int resumeStopLine(double acc, double acc_rot);
2016
2017 /**
2018 * 开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params
2019 * 进行摆动
2020 *
2021 * @param params Json字符串用于定义摆动参数
2022 * {
2023 * "type": <string>, // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
2024 * "step": <num>,
2025 * "amplitude": {<num>,<num>},
2026 * "hold_distance": {<num>,<num>},
2027 * "angle": <num>
2028 * "direction": <num>
2029 * }
2030 * @return 成功返回0;失败返回错误码
2031 * AUBO_BUSY
2032 * AUBO_BAD_STATE
2033 * -AUBO_INVL_ARGUMENT
2034 * -AUBO_BAD_STATE
2035 *
2036 * @throws arcs::common_interface::AuboException
2037 *
2038 */
2039 int weaveStart(const std::string &params);
2040
2041 /**
2042 * 结束摆动
2043 *
2044 * @return 成功返回0;失败返回错误码
2045 * AUBO_BUSY
2046 * AUBO_BAD_STATE
2047 * -AUBO_BAD_STATE
2048 *
2049 * @throws arcs::common_interface::AuboException
2050 *
2051 * @par JSON-RPC请求示例
2052 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
2053 *
2054 * @par JSON-RPC响应示例
2055 * {"id":1,"jsonrpc":"2.0","result":0}
2056 *
2057 */
2059
2060 /**
2061 * 设置未来路径上点的采样时间间隔
2062 *
2063 * @param sample_time 采样时间间隔 单位: m/s^2
2064 * @return 成功返回0;失败返回错误码
2065 * AUBO_BUSY
2066 * AUBO_BAD_STATE
2067 * -AUBO_INVL_ARGUMENT
2068 * -AUBO_BAD_STATE
2069 *
2070 * @throws arcs::common_interface::AuboException
2071 *
2072 */
2073 int setFuturePointSamplePeriod(double sample_time);
2074
2075 /**
2076 * 获取未来路径上的轨迹点
2077 *
2078 * @return 路点(100ms * 10)
2079 *
2080 * @throws arcs::common_interface::AuboException
2081 *
2082 * @par JSON-RPC请求示例
2083 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
2084 *
2085 * @par JSON-RPC响应示例
2086 * {"id":1,"jsonrpc":"2.0","result":[]}
2087 *
2088 */
2089 std::vector<std::vector<double>> getFuturePathPointsJoint();
2090
2091 /**
2092 * 圆形传送带跟随
2093 *
2094 * @note 暂未实现
2095 *
2096 * @param encoder_id
2097 * 0-集成传感器
2098 *
2099 * @param center
2100 * @param tick_per_revo
2101 * @param rotate_tool
2102 * @return
2103 *
2104 * @throws arcs::common_interface::AuboException
2105 *
2106 */
2107 int conveyorTrackCircle(int encoder_id, const std::vector<double> &center,
2108 int tick_per_revo, bool rotate_tool);
2109
2110 /**
2111 * 线性传送带跟随
2112 *
2113 * @param encoder_id 预留
2114 * @param direction 传送带偏移方向
2115 * @param tick_per_meter 编码器脉冲值===>传送带每走每米的脉冲值
2116 * @return
2117 *
2118 * @throws arcs::common_interface::AuboException
2119 *
2120 * @par Python函数原型
2121 * conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
2122 *
2123 * @par Lua函数原型
2124 * conveyorTrackLine -> boolean
2125 *
2126 * @par JSON-RPC请求示例
2127 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,1.0,1.0,0.0,0.0,0.0],40000],"id":1}
2128 *
2129 * @par JSON-RPC响应示例
2130 * {"id":1,"jsonrpc":"2.0","result":0}
2131 *
2132 */
2133 int conveyorTrackLine(int encoder_id, const std::vector<double> &direction,
2134 int tick_per_meter);
2135
2136 /**
2137 * 终止传送带跟随
2138 *
2139 *
2140 * @param a 停止类型
2141 * a = 0.0 : 停止所有物品的跟随
2142 * a = 1.0 : 停止当前物品的跟随
2143 * @return
2144 *
2145 * @throws arcs::common_interface::AuboException
2146 *
2147 * @par Python函数原型
2148 * conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
2149 *
2150 * @par Lua函数原型
2151 * conveyorTrackStop -> int
2152 *
2153 * @par JSON-RPC请求示例
2154 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":1.0,"id":1}
2155 *
2156 * @par JSON-RPC响应示例
2157 * {"id":1,"jsonrpc":"2.0","result":0}
2158 *
2159 */
2160 int conveyorTrackStop(double a);
2161
2162 /**
2163 * 切换传送带追踪物品
2164 * 如果没有物品,会自动关闭传送带追踪功能
2165 *
2166 * @return 有物品返回true,反之则返回false
2167 *
2168 * @throws arcs::common_interface::AuboException
2169 *
2170 * @param encoder_id 预留
2171 *
2172 * @par Python函数原型
2173 * conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
2174 *
2175 * @par Lua函数原型
2176 * conveyorTrackSwitch() -> boolean
2177 *
2178 * @par JSON-RPC请求示例
2179 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
2180 *
2181 * @par JSON-RPC响应示例
2182 * {"id":1,"jsonrpc":"2.0","result":true}
2183 *
2184 */
2185 bool conveyorTrackSwitch(int encoder_id);
2186
2187 /**
2188 * 获取传送带上还未追踪的工件数量
2189 *
2190 * @return 返回物品在传送带上的工件数量
2191 *
2192 * @throws arcs::common_interface::AuboException
2193 *
2194 * @par Python函数原型
2195 * getConveyorItemNums(self: pyaubo_sdk.MotionControl) -> int
2196 *
2197 * @par Lua函数原型
2198 * getConveyorItemNums() -> number
2199 *
2200 * @par JSON-RPC请求示例
2201 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorItemNums","params":[],"id":1}
2202 *
2203 * @par JSON-RPC响应示例
2204 * {"id":1,"jsonrpc":"2.0","result":{2}}
2205 *
2206 */
2208
2209 /**
2210 * 增加传送带上检测到的物品
2211 *
2212 * @param encoder_id 预留
2213 * @return
2214 *
2215 * @throws arcs::common_interface::AuboException
2216 *
2217 * @par Python函数原型
2218 * conveyorCreatItem(self: pyaubo_sdk.MotionControl, arg0: int) -> int
2219 *
2220 * @par Lua函数原型
2221 * conveyorCreatItem(id: number) -> number
2222 *
2223 * @par JSON-RPC请求示例
2224 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorCreatItem","params":[0],"id":1}
2225 *
2226 * @par JSON-RPC响应示例
2227 * {"id":1,"jsonrpc":"2.0","result":0.0}
2228 *
2229 */
2230 int conveyorCreatItem(int encoder_id);
2231
2232 /**
2233 * 设置传送带跟踪的补偿值
2234 *
2235 * @param comp 传送带补偿值
2236 * @return
2237 *
2238 * @throws arcs::common_interface::AuboException
2239 *
2240 * @par Python函数原型
2241 * setConveyorCompensate(self: pyaubo_sdk.MotionControl, arg0: float) ->
2242 * float
2243 *
2244 * @par Lua函数原型
2245 * setConveyorCompensate(comp: number) -> number
2246 *
2247 * @par JSON-RPC请求示例
2248 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorCompensate","params":[0.1],"id":1}
2249 *
2250 * @par JSON-RPC响应示例
2251 * {"id":1,"jsonrpc":"2.0","result":0.0}
2252 *
2253 */
2254 int conveyorTrackCompensate(double comp);
2255
2256 /**
2257 * 判断传送带与机械臂之间是否达到相对静止
2258 *
2259 * @param encoder_id 预留
2260 * @return
2261 *
2262 * @throws arcs::common_interface::AuboException
2263 *
2264 * @par Python函数原型
2265 * conveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) ->
2266 * bool
2267 *
2268 * @par Lua函数原型
2269 * conveyorTrackSync(encoder_id: number) -> bool
2270 *
2271 * @par JSON-RPC请求示例
2272 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSync","params":[0],"id":1}
2273 *
2274 * @par JSON-RPC响应示例
2275 * {"id":1,"jsonrpc":"2.0","result":false}
2276 *
2277 */
2278 bool conveyorTrackSync(int encoder_id);
2279
2280 /**
2281 * 传送带同步分离,用于过滤掉同步开关中不需要的信号
2282 *
2283 * @param encoder_id 预留
2284 * @param distance
2285 * 从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短距离,单位:米
2286 * @param time
2287 * 从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短时间,单位:秒
2288 *
2289 * distance和time设置数值大于0即为生效
2290 * 当distance与time同时设置时,优先生效distance
2291 * @return
2292 *
2293 * @throws arcs::common_interface::AuboException
2294 *
2295 * @par Python函数原型
2296 * conveyorSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
2297 * double, arg2: double) -> int
2298 *
2299 * @par Lua函数原型
2300 * conveyorSyncSeparation(encoder_id: number, distance: number, time:
2301 * number) -> int
2302 *
2303 * @par JSON-RPC请求示例
2304 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorSyncSeparation","params":[0,
2305 * 0.05, 0.2],"id":1}
2306 *
2307 * @par JSON-RPC响应示例
2308 * {"id":1,"jsonrpc":"2.0","result":0}
2309 *
2310 */
2311 int conveyorSyncSeparation(int encoder_id, double distance, double time);
2312
2313 /**
2314 * 传送带跟踪的最大距离限制
2315 *
2316 * @param encoder_id 预留
2317 * @param limit
2318 * 传送带跟踪的最大距离限制,单位:米
2319 * @return
2320 *
2321 * @throws arcs::common_interface::AuboException
2322 *
2323 * @par Python函数原型
2324 * conveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
2325 * double) -> int
2326 *
2327 * @par Lua函数原型
2328 * conveyorTrackLimit(encoder_id: number, limit: number) -> int
2329 *
2330 * @par JSON-RPC请求示例
2331 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLimit","params":[0,
2332 * 1.5],"id":1}
2333 *
2334 * @par JSON-RPC响应示例
2335 * {"id":1,"jsonrpc":"2.0","result":0}
2336 *
2337 */
2338 int conveyorTrackLimit(int encoder_id, double limit);
2339
2340 /**
2341 * 传送带跟踪的启动窗口
2342 *
2343 * @param encoder_id 预留
2344 * @param min_window
2345 * 启动窗口的起始位置,单位:米
2346 * @param max_window
2347 * 启动窗口的结束位置,单位:米
2348 * @return
2349 *
2350 * @throws arcs::common_interface::AuboException
2351 *
2352 * @par Python函数原型
2353 * conveyorStartWindow(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
2354 * double, arg2: double) -> int
2355 *
2356 * @par Lua函数原型
2357 * conveyorStartWindow(encoder_id: number, min_window: number, max_window:
2358 * number) -> int
2359 *
2360 * @par JSON-RPC请求示例
2361 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorStartWindow","params":[0,
2362 * 0.2, 1.0],"id":1}
2363 *
2364 * @par JSON-RPC响应示例
2365 * {"id":1,"jsonrpc":"2.0","result":0}
2366 *
2367 */
2368 int conveyorStartWindow(int encoder_id, double window_min,
2369 double window_max);
2370
2371 /**
2372 * 传送带示教位置到同步开关之间的距离
2373 *
2374 * @param encoder_id 预留
2375 * @param offset
2376 * 传送带示教位置到同步开关之间的距离,单位:米
2377 * @return
2378 *
2379 * @throws arcs::common_interface::AuboException
2380 *
2381 * @par Python函数原型
2382 * conveyorTeachOffset(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
2383 * double) -> int
2384 *
2385 * @par Lua函数原型
2386 * conveyorTeachOffset(encoder_id: number, offset: number) -> int
2387 *
2388 * @par JSON-RPC请求示例
2389 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTeachOffset","params":[0,
2390 * 0.2],"id":1}
2391 *
2392 * @par JSON-RPC响应示例
2393 * {"id":1,"jsonrpc":"2.0","result":0}
2394 *
2395 */
2396 int conveyorTeachOffset(int encoder_id, double offset);
2397
2398 /**
2399 * 螺旋线运动
2400 *
2401 * @param param 封装的参数
2402 * @param blend_radius
2403 * @param v
2404 * @param a
2405 * @param t
2406 * @return 成功返回0;失败返回错误码
2407 * AUBO_BUSY
2408 * AUBO_BAD_STATE
2409 * -AUBO_INVL_ARGUMENT
2410 * -AUBO_BAD_STATE
2411 *
2412 * @throws arcs::common_interface::AuboException
2413 *
2414 * @par JSON-RPC请求示例
2415 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
2416 * "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}
2417 *
2418 * @par JSON-RPC响应示例
2419 * {"id":1,"jsonrpc":"2.0","result":0}
2420 *
2421 */
2422 int moveSpiral(const SpiralParameters &param, double blend_radius, double v,
2423 double a, double t);
2424
2425 /**
2426 * 获取前瞻段数
2427 *
2428 * @return 返回前瞻段数
2429 *
2430 * @throws arcs::common_interface::AuboException
2431 *
2432 * @par Python函数原型
2433 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
2434 *
2435 * @par Lua函数原型
2436 * getLookAheadSize() -> number
2437 *
2438 * @par JSON-RPC请求示例
2439 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
2440 *
2441 * @par JSON-RPC响应示例
2442 * {"id":1,"jsonrpc":"2.0","result":1}
2443 *
2444 */
2446
2447 /**
2448 * 设置前瞻段数
2449 * 1.对于有较高速度平稳性要求的任务,如数控加工,涂胶,焊接等匀速需求,较长的前瞻段数可以提供更优的速度规划,产生的运动会更加平滑;
2450 * 2.对于快速响应的抓取类任务,更倾向于较短的前瞻段数,以提高反应速度,但可能因为进给的路径不够及时导致速度波动很大.
2451 *
2452 * @return 成功返回0
2453 *
2454 * @throws arcs::common_interface::AuboException
2455 *
2456 * @par Python函数原型
2457 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
2458 *
2459 * @par Lua函数原型
2460 * setLookAheadSize(eqradius: number) -> number
2461 *
2462 * @par JSON-RPC请求示例
2463 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
2464 *
2465 * @par JSON-RPC响应示例
2466 * {"id":1,"jsonrpc":"2.0","result":0}
2467 *
2468 */
2469 int setLookAheadSize(int size);
2470
2471 /**
2472 * 更新摆动过程中的频率和振幅
2473 *
2474 * @param params Json字符串用于定义摆动参数
2475 * {
2476 * "frequency": <num>,
2477 * "amplitude": {<num>,<num>}
2478 * }
2479 *
2480 * @return 成功返回0
2481 *
2482 * @throws arcs::common_interface::AuboException
2483 */
2484 int weaveUpdateParameters(const std::string &params);
2485
2486protected:
2487 void *d_;
2488};
2489using MotionControlPtr = std::shared_ptr<MotionControl>;
2490} // namespace common_interface
2491} // namespace arcs
2492
2493#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 servoJointWithAxisGroup(const std::vector< double > &q, double a, double v, double t, double lookahead_time, double gain, const std::string &group_name, const std::vector< double > &extq)
int followLine(const std::vector< double > &pose)
笛卡尔空间跟随
int getResumeMode()
获取继续运动模式
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...
bool conveyorTrackSwitch(int encoder_id)
切换传送带追踪物品 如果没有物品,会自动关闭传送带追踪功能
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 conveyorSyncSeparation(int encoder_id, double distance, double time)
传送带同步分离,用于过滤掉同步开关中不需要的信号
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)
笛卡尔空间伺服
int moveLineWithAxisGroup(const std::vector< double > &pose, double a, double v, double blend_radius, double duration, const std::string &group_name, const std::vector< double > &extq)
直线运动与外部轴同步运动
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 servoCartesianWithAxisGroup(const std::vector< double > &pose, double a, double v, double t, double lookahead_time, double gain, const std::string &group_name, const std::vector< double > &extq)
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 conveyorStartWindow(int encoder_id, double window_min, double window_max)
传送带跟踪的启动窗口
int stopMove(bool quick, bool all_tasks)
StopMove is used to stop robot and external axes movements and any belonging process temporarily.
int getConveyorItemNums()
获取传送带上还未追踪的工件数量
int jointOffsetEnable()
关节偏移使能
ARCS_DEPRECATED bool isServoModeEnabled()
判断伺服模式是否使能 使用 getServoModeSelect 替代
int conveyorCreatItem(int encoder_id)
增加传送带上检测到的物品
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 conveyorTeachOffset(int encoder_id, double offset)
传送带示教位置到同步开关之间的距离
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 moveCircleWithAxisGroup(const std::vector< double > &via_pose, const std::vector< double > &end_pose, double a, double v, double blend_radius, double duration, const std::string &group_name, const std::vector< double > &extq)
moveCircle 与外部轴同步运动
int pathBufferAppend(const std::string &name, const std::vector< std::vector< double > > &waypoints)
向路径缓存添加路点
int conveyorTrackLimit(int encoder_id, double limit)
传送带跟踪的最大距离限制
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 setResumeStartPoint(const std::vector< double > &q, int move_type, double blend_radius, const std::vector< double > &qdmax, const std::vector< double > &qddmax, const std::vector< double > &vmax, const std::vector< double > &amax)
设置继续运动参数
int moveJointWithAxisGroup(const std::vector< double > &q, double a, double v, double blend_radius, double duration, const std::string &group_name, const std::vector< double > &extq)
机器人与外部轴同步运动
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 weaveUpdateParameters(const std::string &params)
更新摆动过程中的频率和振幅
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 conveyorTrackCompensate(double comp)
设置传送带跟踪的补偿值
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 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
bool conveyorTrackSync(int encoder_id)
判断传送带与机械臂之间是否达到相对静止
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样条插值,最少三个点,但是传入的是笛卡尔空间位姿
数据类型的定义