PDF
AUBO SDK  0.26.0
motion_control.h
浏览该文件的文档.
1/** @file motion_control.h
2 * \~chinese @brief 运动控制接口
3 * \~english @brief Motion control interface
4 */
5#ifndef AUBO_SDK_MOTION_CONTROL_INTERFACE_H
6#define AUBO_SDK_MOTION_CONTROL_INTERFACE_H
7
8#include <vector>
9#include <functional>
10#include <thread>
11
12#include <aubo/global_config.h>
13#include <aubo/type_def.h>
14
15namespace arcs {
16namespace common_interface {
17
18/**
19 * \chinese
20 * pathBuffer类型
21 *
22 * 机器人运动被编程为位姿到位姿的运动,即从当前位置移动到新位置。两点之间的路径由机器人自动计算。
23 * \endchinese
24 * \english
25 *
26 * pathBuffer Type
27 *
28 * The robot movements are programmed as pose-to-pose movements, that is move
29 * from the current position to a new position. The path between these two
30 * positions is then automatically calculated by the robot.
31 * \endenglish
32 */
33
35{
36 PathBuffer_TOPPRA = 1, ///< \~chinese 1: toppra 时间最优路径规划 \~english
37 ///< 1: toppra time optimal path planning
39 2, ///< \~chinese 2: cubic_spline(录制的轨迹) \~english 2: cubic_spline
40 ///< (recorded trajectory)
41
42 /// \~chinese 3: 关节B样条插值,最少三个点 \~english 3: Joint B-spline
43 /// interpolation, at least three points
44 /// \~chinese 废弃,建议用5替代,现在实际是关节空间 CUBIC_SPLINE \~english
45 /// Deprecated, use 5 instead, currently it is joint space CUBIC_SPLINE
47
48 /// \~chinese 4:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
49 /// \~english 4: Joint B-spline interpolation, at least three points, but
50 /// the input is Cartesian space pose 废弃,建议用6替代,现在实际是关节空间
51 /// CUBIC_SPLINE
53
54 ///< \~chinese 5: 关节B样条插值,最少三个点 \~english 5: Joint B-spline
55 ///< interpolation, at least three points
57
58 /// \~chinese 6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
59 /// \~english 6: Joint B-spline interpolation, at least three points, but
60 /// the input is Cartesian space pose
62};
63
64/**
65 * \chinese
66 * @defgroup MotionControl MotionControl (运动规划与控制)
67 * @ingroup RobotInterface
68 * \endchinese
69 *
70 * \english
71 * @defgroup MotionControl Motion Planning and Control
72 * @ingroup RobotInterface
73 * \endenglish
74 * MotionControl
75 */
76class ARCS_ABI_EXPORT MotionControl
77{
78public:
80 virtual ~MotionControl();
81
82 /**
83 * @ingroup MotionControl
84 * \chinese
85 * 获取等效半径,单位 m
86 * moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动
87 * 可以通过 setEqradius 设置,默认为1
88 *
89 * @return 返回等效半径
90 *
91 * @throws arcs::common_interface::AuboException
92 *
93 * @par Python函数原型
94 * getEqradius(self: pyaubo_sdk.MotionControl) -> float
95 *
96 * @par Lua函数原型
97 * getEqradius() -> number
98 *
99 * @par Lua 示例
100 * num = getEqradius()
101 *
102 * @par JSON-RPC请求示例
103 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getEqradius","params":[],"id":1}
104 *
105 * @par JSON-RPC响应示例
106 * {"id":1,"jsonrpc":"2.0","result":1.0}
107 * \endchinese
108 * \english
109 * Get the equivalent radius, in meters.
110 * When using moveLine/moveCircle, the rotation angle of the end effector's
111 * pose is converted to an equivalent end position movement. Can be set via
112 * setEqradius, default is 1.
113 *
114 * @return Returns the equivalent radius.
115 *
116 * @throws arcs::common_interface::AuboException
117 *
118 * @par Python function prototype
119 * getEqradius(self: pyaubo_sdk.MotionControl) -> float
120 *
121 * @par Lua function prototype
122 * getEqradius() -> number
123 *
124 * @par Lua example
125 * num = getEqradius()
126 *
127 * @par JSON-RPC request example
128 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getEqradius","params":[],"id":1}
129 *
130 * @par JSON-RPC response example
131 * {"id":1,"jsonrpc":"2.0","result":1.0}
132 * \endenglish
133 */
134 double getEqradius();
135
136 /**
137 * @ingroup MotionControl
138 * \chinese
139 * 设置等效半径,单位 m
140 * moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
141 *
142 * @param eqradius 0表示只规划移动,姿态旋转跟随移动
143 *
144 * @return 成功返回0; 失败返回错误码
145 * AUBO_BAD_STATE
146 * AUBO_BUSY
147 * -AUBO_INVL_ARGUMENT
148 * -AUBO_BAD_STATE
149 *
150 * @throws arcs::common_interface::AuboException
151 *
152 * @par JSON-RPC请求示例
153 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setEqradius","params":[0.8],"id":1}
154 *
155 * @par JSON-RPC响应示例
156 * {"id":1,"jsonrpc":"2.0","result":0}
157 *
158 * @par Python函数原型
159 * setEqradius(self: pyaubo_sdk.MotionControl, arg0: float) -> int
160 *
161 * @par Lua函数原型
162 * setEqradius(eqradius: number) -> number
163 *
164 * @par Lua示例
165 * num = setEqradius(1)
166 *
167 * \endchinese
168 * \english
169 * Set the equivalent radius, in meters.
170 * When using moveLine/moveCircle, the rotation angle of the end effector's
171 * pose is converted to an equivalent end position movement. The larger the
172 * value, the faster the posture rotation speed.
173 *
174 * @param eqradius 0 means only plan the movement, and the posture rotation
175 * follows the movement.
176 *
177 * @return Returns 0 on success; otherwise returns an error code:
178 * AUBO_BAD_STATE
179 * AUBO_BUSY
180 * -AUBO_INVL_ARGUMENT
181 * -AUBO_BAD_STATE
182 *
183 * @throws arcs::common_interface::AuboException
184 *
185 * @par JSON-RPC request example
186 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setEqradius","params":[0.8],"id":1}
187 *
188 * @par JSON-RPC response example
189 * {"id":1,"jsonrpc":"2.0","result":0}
190 *
191 * @par Python function prototype
192 * setEqradius(self: pyaubo_sdk.MotionControl, arg0: float) -> int
193 *
194 * @par Lua function prototype
195 * setEqradius(eqradius: number) -> number
196 *
197 * @par Lua example
198 * num = setEqradius(1)
199 *
200 * \endenglish
201 */
202 int setEqradius(double eqradius);
203
204 /**
205 * @ingroup MotionControl
206 * \chinese
207 * 动态调整机器人运行速度和加速度比例 (0., 1.]
208 *
209 * @param fraction 机器人运行速度和加速度比例
210 * @return 成功返回0; 失败返回错误码
211 * AUBO_INVL_ARGUMENT
212 * AUBO_BUSY
213 * AUBO_BAD_STATE
214 * -AUBO_INVL_ARGUMENT
215 * -AUBO_BAD_STATE
216 *
217 * @throws arcs::common_interface::AuboException
218 *
219 * @par Python函数原型
220 * setSpeedFraction(self: pyaubo_sdk.MotionControl, arg0: float) -> int
221 *
222 * @par Lua函数原型
223 * setSpeedFraction(fraction: number) -> nil
224 *
225 * @par Lua示例
226 * setSpeedFraction(0.5)
227 *
228 * @par JSON-RPC请求示例
229 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setSpeedFraction","params":[0.8],"id":1}
230 *
231 * @par JSON-RPC响应示例
232 * {"id":1,"jsonrpc":"2.0","result":0}
233 * \endchinese
234 * \english
235 * Dynamically adjust the robot's speed and acceleration ratio (0., 1.]
236 *
237 * @param fraction The ratio of robot speed and acceleration
238 * @return Returns 0 on success; otherwise returns an error code:
239 * AUBO_INVL_ARGUMENT
240 * AUBO_BUSY
241 * AUBO_BAD_STATE
242 * -AUBO_INVL_ARGUMENT
243 * -AUBO_BAD_STATE
244 *
245 * @throws arcs::common_interface::AuboException
246 *
247 * @par Python function prototype
248 * setSpeedFraction(self: pyaubo_sdk.MotionControl, arg0: float) -> int
249 *
250 * @par Lua function prototype
251 * setSpeedFraction(fraction: number) -> nil
252 *
253 * @par Lua example
254 * setSpeedFraction(0.5)
255 *
256 * @par JSON-RPC request example
257 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setSpeedFraction","params":[0.8],"id":1}
258 *
259 * @par JSON-RPC response example
260 * {"id":1,"jsonrpc":"2.0","result":0}
261 * \endenglish
262 */
263 int setSpeedFraction(double fraction);
264
265 /**
266 * @ingroup MotionControl
267 * \chinese
268 * 获取速度和加速度比例,默认为 1
269 * 可以通过 setSpeedFraction 接口设置
270 *
271 * @return 返回速度和加速度比例
272 *
273 * @throws arcs::common_interface::AuboException
274 *
275 * @par Python函数原型
276 * getSpeedFraction(self: pyaubo_sdk.MotionControl) -> float
277 *
278 * @par Lua函数原型
279 * getSpeedFraction() -> number
280 *
281 * @par Lua示例
282 * num = getSpeedFraction()
283 *
284 * @par JSON-RPC请求示例
285 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getSpeedFraction","params":[],"id":1}
286 *
287 * @par JSON-RPC响应示例
288 * {"id":1,"jsonrpc":"2.0","result":1.0}
289 * \endchinese
290 * \english
291 * Get the speed and acceleration ratio, default is 1.
292 * Can be set via setSpeedFraction interface.
293 *
294 * @return Returns the speed and acceleration ratio.
295 *
296 * @throws arcs::common_interface::AuboException
297 *
298 * @par Python function prototype
299 * getSpeedFraction(self: pyaubo_sdk.MotionControl) -> float
300 *
301 * @par Lua function prototype
302 * getSpeedFraction() -> number
303 *
304 * @par Lua example
305 * num = getSpeedFraction()
306 *
307 * @par JSON-RPC request example
308 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getSpeedFraction","params":[],"id":1}
309 *
310 * @par JSON-RPC response example
311 * {"id":1,"jsonrpc":"2.0","result":1.0}
312 * \endenglish
313 */
315
316 /**
317 * @ingroup MotionControl
318 * \chinese
319 * 速度比例设置临界区,使能之后速度比例被强制设定为1. ,
320 * 失能之后恢复之前的速度比例
321 *
322 * @param enable
323 * @return 成功返回0; 失败返回错误码
324 * AUBO_BAD_STATE
325 * AUBO_BUSY
326 * -AUBO_BAD_STATE
327 *
328 * @throws arcs::common_interface::AuboException
329 *
330 * @par Lua函数原型
331 * speedFractionCritical() -> int
332 *
333 * @par Lua示例
334 * speedFractionCritical(true)
335 *
336 * @par JSON-RPC请求示例
337 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical","params":[true],"id":1}
338 *
339 * @par JSON-RPC响应示例
340 * {"id":1,"jsonrpc":"2.0","result":0}
341 * \endchinese
342 * \english
343 * Speed fraction critical section. When enabled, the speed fraction is
344 * forced to 1. When disabled, the previous speed fraction is restored.
345 *
346 * @param enable
347 * @return Returns 0 on success; otherwise returns an error code:
348 * AUBO_BAD_STATE
349 * AUBO_BUSY
350 * -AUBO_BAD_STATE
351 *
352 * @throws arcs::common_interface::AuboException
353 *
354 * @par Lua function prototype
355 * speedFractionCritical() -> int
356 *
357 * @par Lua example
358 * speedFractionCritical(true)
359 *
360 * @par JSON-RPC request example
361 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical","params":[true],"id":1}
362 *
363 * @par JSON-RPC response example
364 * {"id":1,"jsonrpc":"2.0","result":0}
365 * \endenglish
366 */
367 int speedFractionCritical(bool enable);
368
369 /**
370 * @ingroup MotionControl
371 * \chinese
372 * 速度比例设置临界区,使能之后速度比例被强制设定为当前生效的比例,
373 * 失能之后恢复之前的速度比例
374 *
375 * @param enable
376 * @return 成功返回0; 失败返回错误码
377 * AUBO_BAD_STATE
378 * AUBO_BUSY
379 * -AUBO_BAD_STATE
380 *
381 * @throws arcs::common_interface::AuboException
382 *
383 * @par Lua函数原型
384 * speedFractionCritical1() -> int
385 *
386 * @par Lua示例
387 * speedFractionCritical1(true)
388 *
389 * @par JSON-RPC请求示例
390 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical1","params":[true],"id":1}
391 *
392 * @par JSON-RPC响应示例
393 * {"id":1,"jsonrpc":"2.0","result":0}
394 * \endchinese
395 * \english
396 * Speed fraction critical section. When enabled, the speed fraction is
397 * forced to the currently effective speed fraction. When disabled, the
398 * previous speed fraction is restored.
399 *
400 * @param enable
401 * @return Returns 0 on success; otherwise returns an error code:
402 * AUBO_BAD_STATE
403 * AUBO_BUSY
404 * -AUBO_BAD_STATE
405 *
406 * @throws arcs::common_interface::AuboException
407 *
408 * @par Lua function prototype
409 * speedFractionCritical1() -> int
410 *
411 * @par Lua example
412 * speedFractionCritical1(true)
413 *
414 * @par JSON-RPC request example
415 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical1","params":[true],"id":1}
416 *
417 * @par JSON-RPC response example
418 * {"id":1,"jsonrpc":"2.0","result":0}
419 * \endenglish
420 */
421 int speedFractionCritical1(bool enable);
422
423 /**
424 * @ingroup MotionControl
425 * \chinese
426 * 是否处于速度比例设置临界区
427 *
428 * @return 处于速度比例设置临界区返回 true; 反之返回 false
429 *
430 * @throws arcs::common_interface::AuboException
431 *
432 * @par Lua函数原型
433 * isSpeedFractionCritical() -> bool
434 *
435 * @par Lua示例
436 * status = isSpeedFractionCritical()
437 *
438 * @par JSON-RPC请求示例
439 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isSpeedFractionCritical","params":[],"id":1}
440 *
441 * @par JSON-RPC响应示例
442 * {"id":1,"jsonrpc":"2.0","result":true}
443 * \endchinese
444 * \english
445 * Whether it is in the speed fraction critical section
446 *
447 * @return Returns true if in the speed fraction critical section; otherwise
448 * returns false
449 *
450 * @throws arcs::common_interface::AuboException
451 *
452 * @par Lua function prototype
453 * isSpeedFractionCritical() -> bool
454 *
455 * @par Lua example
456 * status = isSpeedFractionCritical()
457 *
458 * @par JSON-RPC request example
459 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isSpeedFractionCritical","params":[],"id":1}
460 *
461 * @par JSON-RPC response example
462 * {"id":1,"jsonrpc":"2.0","result":true}
463 * \endenglish
464 */
466
467 /**
468 * @ingroup MotionControl
469 * \chinese
470 * 是否处交融区
471 *
472 * @return 处交融区返回 true; 反之返回 false
473 *
474 * @throws arcs::common_interface::AuboException
475 *
476 * @par Lua函数原型
477 * isBlending() -> bool
478 *
479 * @par Lua示例
480 * status = isBlending()
481 *
482 * @par JSON-RPC请求示例
483 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isBlending","params":[],"id":1}
484 *
485 * @par JSON-RPC响应示例
486 * {"id":1,"jsonrpc":"2.0","result":false}
487 * \endchinese
488 * \english
489 * Whether it is in the blending area
490 *
491 * @return Returns true if in the blending area; otherwise returns false
492 *
493 * @throws arcs::common_interface::AuboException
494 *
495 * @par Lua function prototype
496 * isBlending() -> bool
497 *
498 * @par Lua example
499 * status = isBlending()
500 *
501 * @par JSON-RPC request example
502 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isBlending","params":[],"id":1}
503 *
504 * @par JSON-RPC response example
505 * {"id":1,"jsonrpc":"2.0","result":false}
506 * \endenglish
507 */
509
510 /**
511 * @ingroup MotionControl
512 * \chinese
513 * 设置偏移的最大速度和最大加速度
514 * 仅对pathOffsetSet中 type=1 有效
515 * @param v 最大速度
516 * @param a 最大加速度
517 * @return 成功返回0;失败返回错误码
518 * AUBO_BUSY
519 * AUBO_BAD_STATE
520 * -AUBO_INVL_ARGUMENT
521 * -AUBO_BAD_STATE
522 *
523 * @throws arcs::common_interface::AuboException
524 *
525 * @par Python函数原型
526 * pathOffsetLimits(self: pyaubo_sdk.MotionControl, arg0: float, arg1:
527 * float) -> int
528 *
529 * @par Lua函数原型
530 * pathOffsetLimits(v: number, a: number) -> nil
531 *
532 * @par Lua示例
533 * pathOffsetLimits(1.5,2.5)
534 *
535 * \endchinese
536 * \english
537 * Set the maximum speed and maximum acceleration for offset.
538 * Only valid when type=1 in pathOffsetSet.
539 * @param v Maximum speed
540 * @param a Maximum acceleration
541 * @return Returns 0 on success; otherwise returns an error code:
542 * AUBO_BUSY
543 * AUBO_BAD_STATE
544 * -AUBO_INVL_ARGUMENT
545 * -AUBO_BAD_STATE
546 *
547 * @throws arcs::common_interface::AuboException
548 *
549 * @par Python function prototype
550 * pathOffsetLimits(self: pyaubo_sdk.MotionControl, arg0: float, arg1:
551 * float) -> int
552 *
553 * @par Lua function prototype
554 * pathOffsetLimits(v: number, a: number) -> nil
555 *
556 * @par Lua example
557 * pathOffsetLimits(1.5,2.5)
558 *
559 * \endenglish
560 */
561 int pathOffsetLimits(double v, double a);
562
563 /**
564 * @ingroup MotionControl
565 * \chinese
566 * 设置偏移的参考坐标系
567 * 仅对pathOffsetSet中 type=1 有效
568 * @param ref_coord 参考坐标系 0-基坐标系 1-TCP
569 *
570 * @throws arcs::common_interface::AuboException
571 *
572 * @par Python函数原型
573 * pathOffsetCoordinate(self: pyaubo_sdk.MotionControl, arg0: int) -> float
574 *
575 * @par Lua函数原型
576 * pathOffsetCoordinate(ref_coord: number) -> number
577 *
578 * @par Lua示例
579 * num = pathOffsetCoordinate(0)
580 *
581 * @par JSON-RPC请求示例
582 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetCoordinate","params":[0],"id":1}
583 *
584 * @par JSON-RPC响应示例
585 * {"id":1,"jsonrpc":"2.0","result":0}
586 * \endchinese
587 * \english
588 * Set the reference coordinate system for offset.
589 * Only valid when type=1 in pathOffsetSet.
590 * @param ref_coord Reference coordinate system: 0-base coordinate, 1-TCP
591 *
592 * @throws arcs::common_interface::AuboException
593 *
594 * @par Python function prototype
595 * pathOffsetCoordinate(self: pyaubo_sdk.MotionControl, arg0: int) -> float
596 *
597 * @par Lua function prototype
598 * pathOffsetCoordinate(ref_coord: number) -> number
599 *
600 * @par Lua example
601 * num = pathOffsetCoordinate(0)
602 *
603 * @par JSON-RPC request example
604 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetCoordinate","params":[0],"id":1}
605 *
606 * @par JSON-RPC response example
607 * {"id":1,"jsonrpc":"2.0","result":0}
608 * \endenglish
609 */
610 int pathOffsetCoordinate(int ref_coord);
611
612 /**
613 * @ingroup MotionControl
614 * \chinese
615 * 路径偏移使能
616 *
617 * @return 成功返回0; 失败返回错误码
618 * AUBO_BUSY
619 * AUBO_BAD_STATE
620 * -AUBO_BAD_STATE
621 *
622 * @throws arcs::common_interface::AuboException
623 *
624 * @par Python函数原型
625 * pathOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
626 *
627 * @par Lua函数原型
628 * pathOffsetEnable() -> number
629 *
630 * @par Lua示例
631 * num = pathOffsetEnable()
632 *
633 * @par JSON-RPC请求示例
634 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetEnable","params":[],"id":1}
635 *
636 * @par JSON-RPC响应示例
637 * {"id":1,"jsonrpc":"2.0","result":0}
638 * \endchinese
639 * \english
640 * Enable path offset
641 *
642 * @return Returns 0 on success; otherwise returns an error code:
643 * AUBO_BUSY
644 * AUBO_BAD_STATE
645 * -AUBO_BAD_STATE
646 *
647 * @throws arcs::common_interface::AuboException
648 *
649 * @par Python function prototype
650 * pathOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
651 *
652 * @par Lua function prototype
653 * pathOffsetEnable() -> number
654 *
655 * @par Lua example
656 * num = pathOffsetEnable()
657 *
658 * @par JSON-RPC request example
659 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetEnable","params":[],"id":1}
660 *
661 * @par JSON-RPC response example
662 * {"id":1,"jsonrpc":"2.0","result":0}
663 * \endenglish
664 */
666
667 /**
668 * @ingroup MotionControl
669 * \chinese
670 * 设置路径偏移
671 *
672 * @param offset 在各方向的位姿偏移
673 * @param type 运动类型 0-位置规划 1-速度规划
674 * @return 成功返回0; 失败返回错误码
675 * AUBO_BAD_STATE
676 * AUBO_BUSY
677 * -AUBO_INVL_ARGUMENT
678 * -AUBO_BAD_STATE
679 *
680 * @throws arcs::common_interface::AuboException
681 *
682 * @par Python函数原型
683 * pathOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
684 * int) -> int
685 *
686 * @par Lua函数原型
687 * pathOffsetSet(offset: table, type: number) -> nil
688 *
689 * @par Lua 示例
690 * pathOffsetSet({ 0, 0, 0.1, 0, 0, 0 }, 0)
691 *
692 * @par JSON-RPC请求示例
693 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetSet","params":[[0,0,0.01,0,0,0],0],"id":1}
694 *
695 * @par JSON-RPC响应示例
696 * {"id":1,"jsonrpc":"2.0","result":0}
697 * \endchinese
698 * \english
699 * Set path offset
700 *
701 * @param offset Pose offset in each direction
702 * @param type Motion type 0-position planning 1-velocity planning
703 * @return Returns 0 on success; otherwise returns error code
704 * AUBO_BAD_STATE
705 * AUBO_BUSY
706 * -AUBO_INVL_ARGUMENT
707 * -AUBO_BAD_STATE
708 *
709 * @throws arcs::common_interface::AuboException
710 *
711 * @par Python function prototype
712 * pathOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
713 * int) -> int
714 *
715 * @par Lua function prototype
716 * pathOffsetSet(offset: table, type: number) -> nil
717 *
718 * @par Lua example
719 * pathOffsetSet({ 0, 0, 0.1, 0, 0, 0 }, 0)
720 *
721 * @par JSON-RPC request example
722 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetSet","params":[[0,0,0.01,0,0,0],0],"id":1}
723 *
724 * @par JSON-RPC response example
725 * {"id":1,"jsonrpc":"2.0","result":0}
726 * \endenglish
727 */
728 int pathOffsetSet(const std::vector<double> &offset, int type = 0);
729
730 /**
731 * @ingroup MotionControl
732 * \chinese
733 * 路径偏移失能
734 *
735 * @return 成功返回0; 失败返回错误码
736 * AUBO_BAD_STATE
737 * AUBO_BUSY
738 * -AUBO_BAD_STATE
739 *
740 * @throws arcs::common_interface::AuboException
741 *
742 * @par Python函数原型
743 * pathOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
744 *
745 * @par Lua函数原型
746 * pathOffsetDisable() -> nil
747 *
748 * @par Lua示例
749 * pathOffsetDisable()
750 *
751 * @par JSON-RPC请求示例
752 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetDisable","params":[],"id":1}
753 *
754 * @par JSON-RPC响应示例
755 * {"id":1,"jsonrpc":"2.0","result":0}
756 * \endchinese
757 * \english
758 * Disable path offset
759 *
760 * @return Returns 0 on success; otherwise returns an error code:
761 * AUBO_BAD_STATE
762 * AUBO_BUSY
763 * -AUBO_BAD_STATE
764 *
765 * @throws arcs::common_interface::AuboException
766 *
767 * @par Python function prototype
768 * pathOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
769 *
770 * @par Lua function prototype
771 * pathOffsetDisable() -> nil
772 *
773 * @par Lua example
774 * pathOffsetDisable()
775 *
776 * @par JSON-RPC request example
777 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetDisable","params":[],"id":1}
778 *
779 * @par JSON-RPC response example
780 * {"id":1,"jsonrpc":"2.0","result":0}
781 * \endenglish
782 */
784
785 /**
786 * @ingroup MotionControl
787 * \chinese
788 * @brief 监控轨迹偏移范围
789 * @param min: 沿坐标轴负方向最大偏移量
790 * @param max: 沿坐标轴正方向最大偏移量
791 * @param strategy: 达到最大偏移量后监控策略
792 *     0-禁用监控
793 *     1-饱和限制,即维持最大姿态
794 *     2-保护停止
795 * @return
796 *
797 * @throws arcs::common_interface::AuboException
798 *
799 * @par Python函数原型
800 * pathOffsetSupv(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
801 * List[float], arg2: int) -> int
802 *
803 * @par Lua函数原型
804 * pathOffsetSupv(min: table, max: table, strategy: number) -> number
805 *
806 * @par Lua示例
807 * num = pathOffsetSupv({0,0,-0.2,0,0,0},{0,0,0.5,0,0,0},0)
808 *
809 * \endchinese
810 * \english
811 * @brief Monitor trajectory offset range
812 * @param min: Maximum offset in the negative direction of the coordinate
813 * axis
814 * @param max: Maximum offset in the positive direction of the coordinate
815 * axis
816 * @param strategy: Monitoring strategy after reaching the maximum offset
817 *     0 - Disable monitoring
818 *     1 - Saturation limit, i.e., maintain maximum pose
819 *     2 - Protective stop
820 * @return
821 *
822 * @throws arcs::common_interface::AuboException
823 *
824 * @par Python function prototype
825 * pathOffsetSupv(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
826 * List[float], arg2: int) -> int
827 *
828 * @par Lua function prototype
829 * pathOffsetSupv(min: table, max: table, strategy: number) -> number
830 *
831 * @par Lua example
832 * num = pathOffsetSupv({0,0,-0.2,0,0,0},{0,0,0.5,0,0,0},0)
833 *
834 * \endenglish
835 */
836 int pathOffsetSupv(const std::vector<double> &min,
837 const std::vector<double> &max, int strategy);
838
839 /**
840 * @ingroup MotionControl
841 * \chinese
842 * 关节偏移使能
843 *
844 * @return 成功返回0; 失败返回错误码
845 * AUBO_BAD_STATE
846 * AUBO_BUSY
847 * -AUBO_BAD_STATE
848 *
849 * @throws arcs::common_interface::AuboException
850 *
851 * @par Python函数原型
852 * jointOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
853 *
854 * @par Lua函数原型
855 * jointOffsetEnable() -> nil
856 *
857 * @par Lua示例
858 * jointOffsetEnable()
859 *
860 * @par JSON-RPC请求示例
861 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetEnable","params":[],"id":1}
862 *
863 * @par JSON-RPC响应示例
864 * {"id":1,"jsonrpc":"2.0","result":0}
865 * \endchinese
866 * \english
867 * Enable joint offset
868 *
869 * @return Returns 0 on success; otherwise returns an error code:
870 * AUBO_BAD_STATE
871 * AUBO_BUSY
872 * -AUBO_BAD_STATE
873 *
874 * @throws arcs::common_interface::AuboException
875 *
876 * @par Python function prototype
877 * jointOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
878 *
879 * @par Lua function prototype
880 * jointOffsetEnable() -> nil
881 *
882 * @par Lua example
883 * jointOffsetEnable()
884 *
885 * @par JSON-RPC request example
886 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetEnable","params":[],"id":1}
887 *
888 * @par JSON-RPC response example
889 * {"id":1,"jsonrpc":"2.0","result":0}
890 * \endenglish
891 */
893
894 /**
895 * @ingroup MotionControl
896 * \chinese
897 * 设置关节偏移
898 *
899 * @param offset 在各关节的位姿偏移
900 * @param type
901 * @return 成功返回0; 失败返回错误码
902 * AUBO_BAD_STATE
903 * AUBO_BUSY
904 * -AUBO_INVL_ARGUMENT
905 * -AUBO_BAD_STATE
906 *
907 * @throws arcs::common_interface::AuboException
908 *
909 * @par Python函数原型
910 * jointOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
911 * int) -> int
912 *
913 * @par Lua函数原型
914 * jointOffsetSet(offset: table, type: number) -> nil
915 *
916 * @par Lua示例
917 * jointOffsetSet({0.1,0,0,0,0,0},1)
918 *
919 * @par JSON-RPC请求示例
920 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetSet","params":[[0.1,0,0,0,0],1],"id":1}
921 *
922 * @par JSON-RPC响应示例
923 * {"id":1,"jsonrpc":"2.0","result":0}
924 * \endchinese
925 * \english
926 * Set joint offset
927 *
928 * @param offset Pose offset for each joint
929 * @param type
930 * @return Returns 0 on success; otherwise returns error code
931 * AUBO_BAD_STATE
932 * AUBO_BUSY
933 * -AUBO_INVL_ARGUMENT
934 * -AUBO_BAD_STATE
935 *
936 * @throws arcs::common_interface::AuboException
937 *
938 * @par Python function prototype
939 * jointOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
940 * int) -> int
941 *
942 * @par Lua function prototype
943 * jointOffsetSet(offset: table, type: number) -> nil
944 *
945 * @par Lua example
946 * jointOffsetSet({0.1,0,0,0,0,0},1)
947 *
948 * @par JSON-RPC request example
949 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetSet","params":[[0.1,0,0,0,0],1],"id":1}
950 *
951 * @par JSON-RPC response example
952 * {"id":1,"jsonrpc":"2.0","result":0}
953 * \endenglish
954 */
955 int jointOffsetSet(const std::vector<double> &offset, int type = 1);
956
957 /**
958 * @ingroup MotionControl
959 * \chinese
960 * 关节偏移失能
961 *
962 * @return 成功返回0; 失败返回错误码
963 * AUBO_BAD_STATE
964 * AUBO_BUSY
965 * -AUBO_BAD_STATE
966 *
967 * @throws arcs::common_interface::AuboException
968 *
969 * @par Python函数原型
970 * jointOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
971 *
972 * @par Lua函数原型
973 * jointOffsetDisable() -> nil
974 *
975 * @par Lua示例
976 * jointOffsetDisable()
977 *
978 * @par JSON-RPC请求示例
979 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetDisable","params":[],"id":1}
980 *
981 * @par JSON-RPC响应示例
982 * {"id":1,"jsonrpc":"2.0","result":0}
983 * \endchinese
984 * \english
985 * Disable joint offset
986 *
987 * @return Returns 0 on success; otherwise returns an error code:
988 * AUBO_BAD_STATE
989 * AUBO_BUSY
990 * -AUBO_BAD_STATE
991 *
992 * @throws arcs::common_interface::AuboException
993 *
994 * @par Python function prototype
995 * jointOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
996 *
997 * @par Lua function prototype
998 * jointOffsetDisable() -> nil
999 *
1000 * @par Lua example
1001 * jointOffsetDisable()
1002 *
1003 * @par JSON-RPC request example
1004 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetDisable","params":[],"id":1}
1005 *
1006 * @par JSON-RPC response example
1007 * {"id":1,"jsonrpc":"2.0","result":0}
1008 * \endenglish
1009 */
1011
1012 /**
1013 * @ingroup MotionControl
1014 * \chinese
1015 * 获取已经入队的指令段(INST)数量,运动指令包括
1016 * moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令
1017 *
1018 * 指令一般会在接口宏定义里面用 _INST 指示, 比如 moveJoint
1019 * _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration)
1020 *
1021 * @return 已经入队的指令段数量
1022 *
1023 * @throws arcs::common_interface::AuboException
1024 *
1025 * @par Python函数原型
1026 * getQueueSize(self: pyaubo_sdk.MotionControl) -> int
1027 *
1028 * @par Lua函数原型
1029 * getQueueSize() -> number
1030 *
1031 * @par Lua示例
1032 * num = getQueueSize()
1033 *
1034 * @par JSON-RPC请求示例
1035 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getQueueSize","params":[],"id":1}
1036 *
1037 * @par JSON-RPC响应示例
1038 * {"id":1,"jsonrpc":"2.0","result":0}
1039 *
1040 * \endchinese
1041 * \english
1042 * Get the number of enqueued instruction segments (INST), including motion
1043 * instructions such as moveJoint/moveLine/moveCircle and configuration
1044 * instructions such as setPayload.
1045 *
1046 * Instructions are generally indicated with _INST in macro definitions, for
1047 * example: _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius,
1048 * duration)
1049 *
1050 * @return The number of enqueued instruction segments.
1051 *
1052 * @throws arcs::common_interface::AuboException
1053 *
1054 * @par Python function prototype
1055 * getQueueSize(self: pyaubo_sdk.MotionControl) -> int
1056 *
1057 * @par Lua function prototype
1058 * getQueueSize() -> number
1059 *
1060 * @par Lua example
1061 * num = getQueueSize()
1062 *
1063 * @par JSON-RPC request example
1064 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getQueueSize","params":[],"id":1}
1065 *
1066 * @par JSON-RPC response example
1067 * {"id":1,"jsonrpc":"2.0","result":0}
1068 *
1069 * \endenglish
1070 */
1072
1073 /**
1074 * @ingroup MotionControl
1075 * \chinese
1076 * 获取已经入队的运动规划插补点数量
1077 *
1078 * @return 已经入队的运动规划插补点数量
1079 *
1080 * @throws arcs::common_interface::AuboException
1081 *
1082 * @par Python函数原型
1083 * getTrajectoryQueueSize(self: pyaubo_sdk.MotionControl) -> int
1084 *
1085 * @par Lua函数原型
1086 * getTrajectoryQueueSize() -> number
1087 *
1088 * @par Lua示例
1089 * num = getTrajectoryQueueSize()
1090 *
1091 * @par JSON-RPC请求示例
1092 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getTrajectoryQueueSize","params":[],"id":1}
1093 *
1094 * @par JSON-RPC响应示例
1095 * {"id":1,"jsonrpc":"2.0","result":0}
1096 * \endchinese
1097 * \english
1098 * Get the number of enqueued motion planning interpolation points
1099 *
1100 * @return The number of enqueued motion planning interpolation points
1101 *
1102 * @throws arcs::common_interface::AuboException
1103 *
1104 * @par Python function prototype
1105 * getTrajectoryQueueSize(self: pyaubo_sdk.MotionControl) -> int
1106 *
1107 * @par Lua function prototype
1108 * getTrajectoryQueueSize() -> number
1109 *
1110 * @par Lua example
1111 * num = getTrajectoryQueueSize()
1112 *
1113 * @par JSON-RPC request example
1114 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getTrajectoryQueueSize","params":[],"id":1}
1115 *
1116 * @par JSON-RPC response example
1117 * {"id":1,"jsonrpc":"2.0","result":0}
1118 * \endenglish
1119 */
1121
1122 /**
1123 * @ingroup MotionControl
1124 * \chinese
1125 * 获取当前正在插补的运动指令段的ID
1126 *
1127 * @return 当前正在插补的运动指令段的ID
1128 * @retval -1 表示轨迹队列为空 \n
1129 * 像movePathBuffer运动中的buffer或者规划器(moveJoint和moveLine等)里的队列都属于轨迹队列
1130 *
1131 * @throws arcs::common_interface::AuboException
1132 *
1133 * @par Python函数原型
1134 * getExecId(self: pyaubo_sdk.MotionControl) -> int
1135 *
1136 * @par Lua函数原型
1137 * getExecId() -> number
1138 *
1139 * @par Lua示例
1140 * num = getExecId()
1141 *
1142 * @par JSON-RPC请求示例
1143 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getExecId","params":[],"id":1}
1144 *
1145 * @par JSON-RPC响应示例
1146 * {"id":1,"jsonrpc":"2.0","result":-1}
1147 *
1148 * \endchinese
1149 * \english
1150 * Get the ID of the currently interpolating motion instruction segment.
1151 *
1152 * @return The ID of the currently interpolating motion instruction segment.
1153 * @retval -1 Indicates the trajectory queue is empty. \n
1154 * Both the buffer in movePathBuffer motion and the queue in the planner
1155 * (such as moveJoint and moveLine) belong to the trajectory queue.
1156 *
1157 * @throws arcs::common_interface::AuboException
1158 *
1159 * @par Python function prototype
1160 * getExecId(self: pyaubo_sdk.MotionControl) -> int
1161 *
1162 * @par Lua function prototype
1163 * getExecId() -> number
1164 *
1165 * @par Lua example
1166 * num = getExecId()
1167 *
1168 * @par JSON-RPC request example
1169 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getExecId","params":[],"id":1}
1170 *
1171 * @par JSON-RPC response example
1172 * {"id":1,"jsonrpc":"2.0","result":-1}
1173 *
1174 * \endenglish
1175 */
1177
1178 /**
1179 * @ingroup MotionControl
1180 * \chinese
1181 * 获取指定ID的运动指令段的预期执行时间
1182 *
1183 * @param id 运动指令段ID
1184 * @return 返回预期执行时间
1185 *
1186 * @throws arcs::common_interface::AuboException
1187 *
1188 * @par Python函数原型
1189 * getDuration(self: pyaubo_sdk.MotionControl, arg0: int) -> float
1190 *
1191 * @par Lua函数原型
1192 * getDuration(id: number) -> number
1193 *
1194 * @par Lua示例
1195 * num = getDuration(16)
1196 *
1197 * @par JSON-RPC请求示例
1198 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getDuration","params":[16],"id":1}
1199 *
1200 * @par JSON-RPC响应示例
1201 * {"id":1,"jsonrpc":"2.0","result":0.0}
1202 *
1203 * \endchinese
1204 * \english
1205 * Get the expected execution duration of the motion segment with the
1206 * specified ID.
1207 *
1208 * @param id Motion segment ID
1209 * @return Returns the expected execution duration
1210 *
1211 * @throws arcs::common_interface::AuboException
1212 *
1213 * @par Python function prototype
1214 * getDuration(self: pyaubo_sdk.MotionControl, arg0: int) -> float
1215 *
1216 * @par Lua function prototype
1217 * getDuration(id: number) -> number
1218 *
1219 * @par Lua example
1220 * num = getDuration(16)
1221 *
1222 * @par JSON-RPC request example
1223 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getDuration","params":[16],"id":1}
1224 *
1225 * @par JSON-RPC response example
1226 * {"id":1,"jsonrpc":"2.0","result":0.0}
1227 *
1228 * \endenglish
1229 */
1230 double getDuration(int id);
1231
1232 /**
1233 * @ingroup MotionControl
1234 * \chinese
1235 * 获取指定ID的运动指令段的剩余执行时间
1236 *
1237 * @param id 运动指令段ID
1238 * @return 返回剩余执行时间
1239 *
1240 * @throws arcs::common_interface::AuboException
1241 *
1242 * @par Python函数原型
1243 * getMotionLeftTime(self: pyaubo_sdk.MotionControl, arg0: int) -> float
1244 *
1245 * @par Lua函数原型
1246 * getMotionLeftTime(id: number) -> number
1247 *
1248 * @par Lua示例
1249 * num = getMotionLeftTime(16)
1250 *
1251 * @par JSON-RPC请求示例
1252 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getMotionLeftTime","params":[16],"id":1}
1253 *
1254 * @par JSON-RPC响应示例
1255 * {"id":1,"jsonrpc":"2.0","result":0.0}
1256 * \endchinese
1257 * \english
1258 * Get the remaining execution time of the motion segment with the specified
1259 * ID.
1260 *
1261 * @param id Motion segment ID
1262 * @return Returns the remaining execution time
1263 *
1264 * @throws arcs::common_interface::AuboException
1265 *
1266 * @par Python function prototype
1267 * getMotionLeftTime(self: pyaubo_sdk.MotionControl, arg0: int) -> float
1268 *
1269 * @par Lua function prototype
1270 * getMotionLeftTime(id: number) -> number
1271 *
1272 * @par Lua example
1273 * num = getMotionLeftTime(16)
1274 *
1275 * @par JSON-RPC request example
1276 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getMotionLeftTime","params":[16],"id":1}
1277 *
1278 * @par JSON-RPC response example
1279 * {"id":1,"jsonrpc":"2.0","result":0.0}
1280 * \endenglish
1281 */
1282 double getMotionLeftTime(int id);
1283
1284 /**
1285 * @ingroup MotionControl
1286 * \chinese
1287 * StopMove 用于临时停止机器人和外部轴的运动以及相关工艺进程。如果调用
1288 * StartMove 指令,则运动和工艺进程将恢复。
1289 *
1290 * 该指令可用于中断处理程序中,在发生中断时临时停止机器人。
1291 *
1292 * @param quick true: 以最快速度在路径上停止机器人。未指定 quick
1293 * 参数时,机器人将在路径上停止,但制动距离较长(与普通程序停止相同)。
1294 *
1295 * @return 成功返回0; 失败返回错误码
1296 * AUBO_BAD_STATE
1297 * AUBO_BUSY
1298 * -AUBO_BAD_STATE
1299 *
1300 * @throws arcs::common_interface::AuboException
1301 *
1302 * @par Lua函数原型
1303 * StopMove(quick: bool,all_tasks: bool) -> number
1304 *
1305 * @par Lua示例
1306 * num = StopMove(true,true)
1307 *
1308 * \endchinese
1309 * \english
1310 * StopMove is used to stop robot and external axes movements and any
1311 * belonging process temporarily. If the instruction StartMove is given then
1312 * the movement and process resumes.
1313 *
1314 * This instruction can, for example, be used in a trap routine to stop the
1315 * robot temporarily when an interrupt occurs.
1316 *
1317 * @param quick true: Stops the robot on the path as fast as possible.
1318 * Without the optional parameter \Quick, the robot stops on the path, but
1319 * the braking distance is longer (same as for normal Program Stop).
1320 *
1321 * @return Returns 0 on success; otherwise returns an error code:
1322 * AUBO_BAD_STATE
1323 * AUBO_BUSY
1324 * -AUBO_BAD_STATE
1325 *
1326 * @throws arcs::common_interface::AuboException
1327 *
1328 * @par Lua function prototype
1329 * StopMove(quick: bool,all_tasks: bool) -> number
1330 *
1331 * @par Lua example
1332 * num = StopMove(true,true)
1333 *
1334 * \endenglish
1335 */
1336 int stopMove(bool quick, bool all_tasks);
1337
1338 /**
1339 * @ingroup MotionControl
1340 * \chinese
1341 * StartMove 用于在以下情况下恢复机器人、外部轴的运动以及相关工艺进程:
1342 * • 通过 StopMove 指令停止后。
1343 * • 执行 StorePath ... RestoPath 序列后。
1344 * • 发生异步运动错误(如 ERR_PATH_STOP)或特定工艺错误并在 ERROR
1345 * 处理器中处理后。
1346 *
1347 * @return 成功返回0; 失败返回错误码
1348 * AUBO_BAD_STATE
1349 * AUBO_BUSY
1350 * -AUBO_BAD_STATE
1351 *
1352 * @throws arcs::common_interface::AuboException
1353 *
1354 * @par Lua函数原型
1355 * startMove() -> number
1356 *
1357 * @par Lua示例
1358 * num = startMove()
1359 *
1360 * @par JSON-RPC请求示例
1361 * {"jsonrpc":"2.0","method":"rob1.MotionControl.startMove","params":[],"id":1}
1362 *
1363 * @par JSON-RPC响应示例
1364 * {"id":1,"jsonrpc":"2.0","result":0}
1365 * \endchinese
1366 * \english
1367 * StartMove is used to resume robot, external axes movement and belonging
1368 * process after the movement has been stopped
1369 *
1370 * • by the instruction StopMove.
1371 * • after execution of StorePath ... RestoPath sequence.
1372 * • after asynchronously raised movements errors, such as ERR_PATH_STOP or
1373 * specific process error after handling in the ERROR handler.
1374 *
1375 * @return Returns 0 on success; otherwise returns an error code:
1376 * AUBO_BAD_STATE
1377 * AUBO_BUSY
1378 * -AUBO_BAD_STATE
1379 *
1380 * @throws arcs::common_interface::AuboException
1381 *
1382 * @par Lua function prototype
1383 * startMove() -> number
1384 *
1385 * @par Lua example
1386 * num = startMove()
1387 *
1388 * @par JSON-RPC request example
1389 * {"jsonrpc":"2.0","method":"rob1.MotionControl.startMove","params":[],"id":1}
1390 *
1391 * @par JSON-RPC response example
1392 * {"id":1,"jsonrpc":"2.0","result":0}
1393 * \endenglish
1394 */
1396
1397 /**
1398 * @ingroup MotionControl
1399 * \chinese
1400 * storePath
1401 *
1402 * @param keep_sync
1403 * @return 成功返回0; 失败返回错误码
1404 * AUBO_BAD_STATE
1405 * AUBO_BUSY
1406 * -AUBO_BAD_STATE
1407 *
1408 * @throws arcs::common_interface::AuboException
1409 *
1410 * @par Lua函数原型
1411 * storePath(keep_sync: bool) -> number
1412 *
1413 * @par Lua示例
1414 * num = storePath()
1415 *
1416 * \endchinese
1417 * \english
1418 * storePath
1419 *
1420 * @param keep_sync
1421 * @return Returns 0 on success; otherwise returns an error code:
1422 * AUBO_BAD_STATE
1423 * AUBO_BUSY
1424 * -AUBO_BAD_STATE
1425 *
1426 * @throws arcs::common_interface::AuboException
1427 *
1428 * @par Lua function prototype
1429 * storePath(keep_sync: bool) -> number
1430 *
1431 * @par Lua example
1432 * num = storePath()
1433 *
1434 * \endenglish
1435 */
1436 int storePath(bool keep_sync);
1437
1438 /**
1439 * @ingroup MotionControl
1440 * \chinese
1441 * ClearPath (清除路径) 清除当前运动路径层级(基础层级或 StorePath
1442 * 层级)上的所有运动路径。
1443 *
1444 * @return 成功返回0; 失败返回错误码
1445 * AUBO_BAD_STATE
1446 * AUBO_BUSY
1447 * -AUBO_BAD_STATE
1448 *
1449 * @throws arcs::common_interface::AuboException
1450 *
1451 * @par Lua函数原型
1452 * clearPath() -> number
1453 *
1454 * @par Lua示例
1455 * num = clearPath()
1456 *
1457 * @par JSON-RPC请求示例
1458 * {"jsonrpc":"2.0","method":"rob1.MotionControl.clearPath","params":[],"id":1}
1459 *
1460 * @par JSON-RPC响应示例
1461 * {"id":1,"jsonrpc":"2.0","result":0}
1462 *
1463 * \endchinese
1464 * \english
1465 * ClearPath clears the whole motion path on the current motion path level
1466 * (base level or StorePath level).
1467 *
1468 * @return Returns 0 on success; otherwise returns an error code:
1469 * AUBO_BAD_STATE
1470 * AUBO_BUSY
1471 * -AUBO_BAD_STATE
1472 *
1473 * @throws arcs::common_interface::AuboException
1474 *
1475 * @par Lua function prototype
1476 * clearPath() -> number
1477 *
1478 * @par Lua example
1479 * num = clearPath()
1480 *
1481 * @par JSON-RPC request example
1482 * {"jsonrpc":"2.0","method":"rob1.MotionControl.clearPath","params":[],"id":1}
1483 *
1484 * @par JSON-RPC response example
1485 * {"id":1,"jsonrpc":"2.0","result":0}
1486 *
1487 * \endenglish
1488 */
1490
1491 /**
1492 * @ingroup MotionControl
1493 * \chinese
1494 * restoPath
1495 *
1496 * @return 成功返回0; 失败返回错误码
1497 * AUBO_BAD_STATE
1498 * AUBO_BUSY
1499 * -AUBO_BAD_STATE
1500 *
1501 * @throws arcs::common_interface::AuboException
1502 *
1503 * @par Lua函数原型
1504 * restoPath() -> number
1505 *
1506 * @par Lua示例
1507 * num = restoPath()
1508 *
1509 * @par JSON-RPC请求示例
1510 * {"jsonrpc":"2.0","method":"rob1.MotionControl.restoPath","params":[],"id":1}
1511 *
1512 * @par JSON-RPC响应示例
1513 * {"id":1,"jsonrpc":"2.0","result":0}
1514 * \endchinese
1515 * \english
1516 * restoPath
1517 *
1518 * @return Returns 0 on success; otherwise returns an error code:
1519 * AUBO_BAD_STATE
1520 * AUBO_BUSY
1521 * -AUBO_BAD_STATE
1522 *
1523 * @throws arcs::common_interface::AuboException
1524 *
1525 * @par Lua function prototype
1526 * restoPath() -> number
1527 *
1528 * @par Lua example
1529 * num restoPath()
1530 *
1531 * @par JSON-RPC request example
1532 * {"jsonrpc":"2.0","method":"rob1.MotionControl.restoPath","params":[],"id":1}
1533 *
1534 * @par JSON-RPC response example
1535 * {"id":1,"jsonrpc":"2.0","result":0}
1536 * \endenglish
1537 */
1539
1540 /**
1541 * @ingroup MotionControl
1542 * \chinese
1543 * 获取当前运动指令段的执行进度
1544 *
1545 * @return 返回执行进度
1546 *
1547 * @throws arcs::common_interface::AuboException
1548 *
1549 * @par Python函数原型
1550 * getProgress(self: pyaubo_sdk.MotionControl) -> float
1551 *
1552 * @par Lua函数原型
1553 * getProgress() -> number
1554 *
1555 * @par Lua示例
1556 * num = getProgress()
1557 *
1558 * @par JSON-RPC请求示例
1559 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getProgress","params":[],"id":1}
1560 *
1561 * @par JSON-RPC响应示例
1562 * {"id":1,"jsonrpc":"2.0","result":0.0}
1563 *
1564 * \endchinese
1565 * \english
1566 * Get the execution progress of the current motion instruction segment.
1567 *
1568 * @return Returns the execution progress.
1569 *
1570 * @throws arcs::common_interface::AuboException
1571 *
1572 * @par Python function prototype
1573 * getProgress(self: pyaubo_sdk.MotionControl) -> float
1574 *
1575 * @par Lua function prototype
1576 * getProgress() -> number
1577 *
1578 * @par Lua example
1579 * num = getProgress()
1580 *
1581 * @par JSON-RPC request example
1582 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getProgress","params":[],"id":1}
1583 *
1584 * @par JSON-RPC response example
1585 * {"id":1,"jsonrpc":"2.0","result":0.0}
1586 *
1587 * \endenglish
1588 */
1589 double getProgress();
1590
1591 /**
1592 * @ingroup MotionControl
1593 * \chinese
1594 * 当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
1595 *
1596 * @note 暂未实现
1597 *
1598 * @param module_name 控制模块名字
1599 * @param mounting_pose 抓取的相对位置,
1600 * 如果是机器人,则相对于机器人末端中心点(非TCP点)
1601 * @return 成功返回0; 失败返回错误码
1602 * AUBO_BAD_STATE
1603 * AUBO_BUSY
1604 * -AUBO_INVL_ARGUMENT
1605 * -AUBO_BAD_STATE
1606 *
1607 * @throws arcs::common_interface::AuboException
1608 *
1609 * @par Python函数原型
1610 * setWorkObjectHold(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1611 * List[float]) -> int
1612 *
1613 * @par Lua函数原型
1614 * setWorkObjectHold(module_name: string, mounting_pose: table) -> nil
1615 *
1616 * @par Lua示例
1617 * setWorkObjectHold("object",{0.2,0.1,-0.4,3.14,0,-1.57})
1618 *
1619 * \endchinese
1620 * \english
1621 * Specify the name and mounting position when the workpiece is installed on
1622 * the end of another robot or external axis.
1623 *
1624 * @note Not implemented yet
1625 *
1626 * @param module_name Name of the control module
1627 * @param mounting_pose Relative position of the grasp,
1628 * if it is a robot, it is relative to the robot's end center point (not the
1629 * TCP point)
1630 * @return Returns 0 on success; otherwise returns an error code:
1631 * AUBO_BAD_STATE
1632 * AUBO_BUSY
1633 * -AUBO_INVL_ARGUMENT
1634 * -AUBO_BAD_STATE
1635 *
1636 * @throws arcs::common_interface::AuboException
1637 *
1638 * @par Python function prototype
1639 * setWorkObjectHold(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1640 * List[float]) -> int
1641 *
1642 * @par Lua function prototype
1643 * setWorkObjectHold(module_name: string, mounting_pose: table) -> nil
1644 *
1645 * @par Lua example
1646 * setWorkObjectHold("object",{0.2,0.1,-0.4,3.14,0,-1.57})
1647 *
1648 * \endenglish
1649 */
1650 int setWorkObjectHold(const std::string &module_name,
1651 const std::vector<double> &mounting_pose);
1652
1653 /**
1654 * @ingroup MotionControl
1655 * \chinese
1656 * 获取工件安装信息
1657 *
1658 * @note 暂未实现
1659 *
1660 * @return 返回一个包含控制模块名字和安装位姿的元组
1661 *
1662 * @throws arcs::common_interface::AuboException
1663 *
1664 * @par Python函数原型
1665 * getWorkObjectHold(self: pyaubo_sdk.MotionControl) -> Tuple[str,
1666 * List[float]]
1667 *
1668 * @par Lua函数原型
1669 * getWorkObjectHold() -> table
1670 *
1671 * @par Lua示例
1672 * Object_table = getWorkObjectHold()
1673 *
1674 * @par JSON-RPC请求示例
1675 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getWorkObjectHold","params":[],"id":1}
1676 *
1677 * @par JSON-RPC响应示例
1678 * {"id":1,"jsonrpc":"2.0","result":["",[]]}
1679 * \endchinese
1680 * \english
1681 * getWorkObjectHold
1682 *
1683 * @note Not implemented yet
1684 *
1685 * @return Returns a tuple containing the control module name and mounting
1686 * pose
1687 *
1688 * @throws arcs::common_interface::AuboException
1689 *
1690 * @par Python function prototype
1691 * getWorkObjectHold(self: pyaubo_sdk.MotionControl) -> Tuple[str,
1692 * List[float]]
1693 *
1694 * @par Lua function prototype
1695 * getWorkObjectHold() -> table
1696 *
1697 * @par Lua example
1698 * Object_table = getWorkObjectHold()
1699 *
1700 * @par JSON-RPC request example
1701 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getWorkObjectHold","params":[],"id":1}
1702 *
1703 * @par JSON-RPC response example
1704 * {"id":1,"jsonrpc":"2.0","result":["",[]]}
1705 * \endenglish
1706 */
1707 std::tuple<std::string, std::vector<double>> getWorkObjectHold();
1708
1709 /**
1710 * @ingroup MotionControl
1711 * \chinese
1712 * @note 获取暂停点关节位置
1713 *
1714 * 常用于运行工程时发生碰撞后继续运动过程中(先通过resumeMoveJoint或resumeMoveLine运动到暂停位置,再恢复工程)
1715 *
1716 * @return 暂停关节位置
1717 *
1718 * @throws arcs::common_interface::AuboException
1719 *
1720 * @par Python函数原型
1721 * getPauseJointPositions(self: pyaubo_sdk.MotionControl) -> List[float]
1722 *
1723 * @par Lua函数原型
1724 * getPauseJointPositions() -> table
1725 *
1726 * @par Lua示例
1727 * JointPositions = getPauseJointPositions()
1728 *
1729 * @par JSON-RPC请求示例
1730 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getPauseJointPositions","params":[],"id":1}
1731 *
1732 * @par JSON-RPC响应示例
1733 * {"id":1,"jsonrpc":"2.0","result":[8.2321e-13,-0.200999,1.33999,0.334999,1.206,-6.39383e-12]}
1734 * \endchinese
1735 * \english
1736 * @note Get the joint positions at the pause point.
1737 *
1738 * Commonly used during process recovery after a collision occurs (first
1739 * move to the pause position using resumeMoveJoint or resumeMoveLine, then
1740 * resume the process).
1741 *
1742 * @return Pause joint positions
1743 *
1744 * @throws arcs::common_interface::AuboException
1745 *
1746 * @par Python function prototype
1747 * getPauseJointPositions(self: pyaubo_sdk.MotionControl) -> List[float]
1748 *
1749 * @par Lua function prototype
1750 * getPauseJointPositions() -> table
1751 *
1752 * @par Lua example
1753 * JointPositions = getPauseJointPositions()
1754 *
1755 * @par JSON-RPC request example
1756 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getPauseJointPositions","params":[],"id":1}
1757 *
1758 * @par JSON-RPC response example
1759 * {"id":1,"jsonrpc":"2.0","result":[8.2321e-13,-0.200999,1.33999,0.334999,1.206,-6.39383e-12]}
1760 * \endenglish
1761 */
1762 std::vector<double> getPauseJointPositions();
1763
1764 /**
1765 * @ingroup MotionControl
1766 * \chinese
1767 * 设置继续运动参数
1768 *
1769 * @param q 继续运动起始位置
1770 * @param move_type 0:关节空间 1:笛卡尔空间
1771 * @param blend_radius 交融半径
1772 * @param qdmax 关节运动最大速度(6维度数据)
1773 * @param qddmax 关节运动最大加速度(6维度数据)
1774 * @param vmax 直线运动最大线速度,角速度(2维度数据)
1775 * @param amax 直线运动最大线加速度,角加速度(2维度数据)
1776 * @return 成功返回0; 失败返回错误码
1777 * AUBO_BAD_STATE
1778 * AUBO_BUSY
1779 * -AUBO_BAD_STATE
1780 *
1781 * @throws arcs::common_interface::AuboException
1782 *
1783 * @par Python函数原型
1784 * setResumeStartPoint(self: pyaubo_sdk.MotionControl,
1785 * arg0:List[float],arg1: int, arg2: float,arg3: List[float], arg4:
1786 * List[float],arg5:float,arg5:float) -> int
1787 *
1788 * @par Lua函数原型
1789 * setResumeStartPoint(q : table, move_type: number,blend_radius:
1790 * number, qdmax: table, qddmax:
1791 * table,vmax:number,amax:number) -> nilr
1792 *
1793 * @par Lua示例
1794 * setResumeStartPoint({0,0,0,0,0,0},1,1,{0,0,0,0,0,0},{0,0,0,0,0,0},{1,1},{1,1})
1795 *
1796 * @par JSON-RPC请求示例
1797 * {"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}
1798 *
1799 * @par JSON-RPC响应示例
1800 * {"id":1,"jsonrpc":"2.0","result":0}
1801 * \endchinese
1802 * \english
1803 * Set resume motion parameters
1804 *
1805 * @param q Resume start position
1806 * @param move_type 0: Joint space, 1: Cartesian space
1807 * @param blend_radius Blend radius
1808 * @param qdmax Maximum joint speed (6 elements)
1809 * @param qddmax Maximum joint acceleration (6 elements)
1810 * @param vmax Maximum linear and angular speed for linear motion (2
1811 * elements)
1812 * @param amax Maximum linear and angular acceleration for linear motion (2
1813 * elements)
1814 * @return Returns 0 on success; otherwise returns error code
1815 * AUBO_BAD_STATE
1816 * AUBO_BUSY
1817 * -AUBO_BAD_STATE
1818 *
1819 * @throws arcs::common_interface::AuboException
1820 *
1821 * @par Python function prototype
1822 * setResumeStartPoint(self: pyaubo_sdk.MotionControl,
1823 * arg0: List[float], arg1: int, arg2: float, arg3: List[float], arg4:
1824 * List[float], arg5: float, arg6: float) -> int
1825 *
1826 * @par Lua function prototype
1827 * setResumeStartPoint(q: table, move_type: number, blend_radius:
1828 * number, qdmax: table, qddmax:
1829 * table, vmax: number, amax: number) -> nil
1830 *
1831 * @par Lua example
1832 * setResumeStartPoint({0,0,0,0,0,0},1,1,{0,0,0,0,0,0},{0,0,0,0,0,0},{1,1},{1,1})
1833 *
1834 * @par JSON-RPC request example
1835 * {"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}
1836 *
1837 * @par JSON-RPC response example
1838 * {"id":1,"jsonrpc":"2.0","result":0}
1839 * \endenglish
1840 */
1841 int setResumeStartPoint(const std::vector<double> &q, int move_type,
1842 double blend_radius,
1843 const std::vector<double> &qdmax,
1844 const std::vector<double> &qddmax,
1845 const std::vector<double> &vmax,
1846 const std::vector<double> &amax);
1847 /**
1848 * @ingroup MotionControl
1849 * \chinese
1850 * 获取继续运动模式
1851 *
1852 * @return 0:继续运动起始点为暂停点 1:继续运动起始点为指定点
1853 *
1854 * @throws arcs::common_interface::AuboException
1855 *
1856 * @par Python函数原型
1857 * getResumeMode(self: pyaubo_sdk.MotionControl) -> int
1858 *
1859 * @par Lua函数原型
1860 * getResumeMode() -> int
1861 *
1862 * @par Lua示例
1863 * num = getResumeMode()
1864 *
1865 * @par JSON-RPC请求示例
1866 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getResumeMode","params":[],"id":1}
1867 *
1868 * @par JSON-RPC响应示例
1869 * {"id":1,"jsonrpc":"2.0","result":false}
1870 *
1871 * \endchinese
1872 * \english
1873 * Get resume motion mode
1874 *
1875 * @return 0: Resume start point is the pause point; 1: Resume start point
1876 * is the specified point
1877 *
1878 * @throws arcs::common_interface::AuboException
1879 *
1880 * @par Python function prototype
1881 * getResumeMode(self: pyaubo_sdk.MotionControl) -> int
1882 *
1883 * @par Lua function prototype
1884 * getResumeMode() -> int
1885 *
1886 * @par Lua example
1887 * num = getResumeMode()
1888 *
1889 * @par JSON-RPC request example
1890 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getResumeMode","params":[],"id":1}
1891 *
1892 * @par JSON-RPC response example
1893 * {"id":1,"jsonrpc":"2.0","result":false}
1894 *
1895 * \endenglish
1896 */
1898
1899 /**
1900 * @ingroup MotionControl
1901 * \chinese
1902 * 设置伺服模式
1903 * 使用 setServoModeSelect 替代
1904 *
1905 * @param enable 是否使能
1906 * @return 成功返回0; 失败返回错误码
1907 * AUBO_BAD_STATE
1908 * AUBO_BUSY
1909 * -AUBO_BAD_STATE
1910 *
1911 * @throws arcs::common_interface::AuboException
1912 *
1913 * @par Python函数原型
1914 * setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
1915 *
1916 * @par Lua函数原型
1917 * setServoMode(enable: boolean) -> nil
1918 *
1919 * @par Lua示例
1920 * setServoMode(true)
1921 *
1922 * @par JSON-RPC请求示例
1923 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
1924 *
1925 * @par JSON-RPC响应示例
1926 * {"id":1,"jsonrpc":"2.0","result":0}
1927 * \endchinese
1928 * \english
1929 * Set servo mode
1930 * Use setServoModeSelect instead
1931 *
1932 * @param enable Whether to enable
1933 * @return Returns 0 on success; otherwise returns an error code:
1934 * AUBO_BAD_STATE
1935 * AUBO_BUSY
1936 * -AUBO_BAD_STATE
1937 *
1938 * @throws arcs::common_interface::AuboException
1939 *
1940 * @par Python function prototype
1941 * setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
1942 *
1943 * @par Lua function prototype
1944 * setServoMode(enable: boolean) -> nil
1945 *
1946 * @par Lua example
1947 * setServoMode(true)
1948 *
1949 * @par JSON-RPC request example
1950 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
1951 *
1952 * @par JSON-RPC response example
1953 * {"id":1,"jsonrpc":"2.0","result":0}
1954 * \endenglish
1955 */
1956 ARCS_DEPRECATED int setServoMode(bool enable);
1957
1958 /**
1959 * @ingroup MotionControl
1960 * \chinese
1961 * 判断伺服模式是否使能
1962 * 使用 getServoModeSelect 替代
1963 *
1964 * @return 已使能返回true,反之则返回false
1965 *
1966 * @throws arcs::common_interface::AuboException
1967 *
1968 * @par Python函数原型
1969 * isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
1970 *
1971 * @par Lua函数原型
1972 * isServoModeEnabled() -> boolean
1973 *
1974 * @par Lua示例
1975 * Servo_status = isServoModeEnabled()
1976 *
1977 * @par JSON-RPC请求示例
1978 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
1979 *
1980 * @par JSON-RPC响应示例
1981 * {"id":1,"jsonrpc":"2.0","result":false}
1982 *
1983 * \endchinese
1984 * \english
1985 * Determine whether the servo mode is enabled.
1986 * Use getServoModeSelect instead.
1987 *
1988 * @return Returns true if enabled, otherwise returns false.
1989 *
1990 * @throws arcs::common_interface::AuboException
1991 *
1992 * @par Python function prototype
1993 * isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
1994 *
1995 * @par Lua function prototype
1996 * isServoModeEnabled() -> boolean
1997 *
1998 * @par Lua example
1999 * Servo_status = isServoModeEnabled()
2000 *
2001 * @par JSON-RPC request example
2002 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
2003 *
2004 * @par JSON-RPC response example
2005 * {"id":1,"jsonrpc":"2.0","result":false}
2006 *
2007 * \endenglish
2008 */
2009 ARCS_DEPRECATED bool isServoModeEnabled();
2010
2011 /**
2012 * @ingroup MotionControl
2013 * \chinese
2014 * 设置伺服运动模式
2015 *
2016 * @param mode
2017 * 0-退出伺服模式
2018 * 1-(截断式)规划伺服模式
2019 * 2-透传模式(直接下发)
2020 * 3-透传模式(缓存)
2021 * 4-1ms透传模式(缓存)
2022 * 5-规划伺服模式
2023 * 6-(截断式)规划伺服模式, 可以叠加力控
2024 * 7-规划伺服模式,可以叠加力控
2025 * 伺服模式1添加路点后,会实时调整目标点和规划路线(当前的目标点被更新后,不能保证达到之前设定的目标点)
2026 * 伺服模式5添加路点后,能保证经过所有目标点
2027 * @return
2028 *
2029 * @par Lua函数原型
2030 * setServoModeSelect(0) -> nil
2031 *
2032 * @par Lua示例
2033 * setServoModeSelect(0)
2034 *
2035 * @par JSON-RPC请求示例
2036 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
2037 *
2038 * @par JSON-RPC响应示例
2039 * {"id":1,"jsonrpc":"2.0","result":0}
2040 *
2041 * \endchinese
2042 * \english
2043 * Set servo motion mode
2044 *
2045 * @param mode
2046 * 0 - Exit servo mode
2047 * 1 - Planning servo mode
2048 * 2 - Transparent mode (direct send)
2049 * 3 - Transparent mode (buffered)
2050 * @return
2051 *
2052 * @par Lua function prototype
2053 * setServoModeSelect(0) -> nil
2054 *
2055 * @par Lua example
2056 * setServoModeSelect(0)
2057 *
2058 * @par JSON-RPC request example
2059 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
2060 *
2061 * @par JSON-RPC response example
2062 * {"id":1,"jsonrpc":"2.0","result":0}
2063 *
2064 * \endenglish
2065 */
2066 int setServoModeSelect(int mode);
2067
2068 /**
2069 * @ingroup MotionControl
2070 * \chinese
2071 * 获取伺服运动模式
2072 *
2073 * @return
2074 *
2075 * @par Lua函数原型
2076 * getServoModeSelect() -> number
2077 *
2078 * @par Lua示例
2079 * num = getServoModeSelect()
2080 *
2081 * @par JSON-RPC请求示例
2082 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
2083 *
2084 * @par JSON-RPC响应示例
2085 * {"id":1,"jsonrpc":"2.0","result":0}
2086 *
2087 * \endchinese
2088 * \english
2089 * Get the servo motion mode
2090 *
2091 * @return
2092 *
2093 * @par Lua function prototype
2094 * getServoModeSelect() -> number
2095 *
2096 * @par Lua example
2097 * num = getServoModeSelect()
2098 *
2099 * @par JSON-RPC request example
2100 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
2101 *
2102 * @par JSON-RPC response example
2103 * {"id":1,"jsonrpc":"2.0","result":0}
2104 *
2105 * \endenglish
2106 */
2108
2109 /**
2110 * @ingroup MotionControl
2111 * \chinese
2112 * 关节空间伺服
2113 *
2114 * 目前可用参数只有 q 和 t;
2115 * @param q 关节角, 单位 rad,
2116 * @param a 加速度, 单位 rad/s^2,
2117 * @param v 速度,单位 rad/s,
2118 * @param t 运行时间,单位 s \n
2119 * t 值越大,机器臂运动越慢,反之,运动越快;
2120 * 该参数最优值为连续调用 servoJoint 接口的间隔时间。
2121 * @param lookahead_time 前瞻时间,单位 s \n
2122 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
2123 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
2124 * 该参数最优值为一个控制周期。
2125 * @param gain 比例增益
2126 * 跟踪目标位置的比例增益[100, 200],
2127 * 用于控制运动的顺滑性和精度,
2128 * 比例增益越大,到达目标位置的时间越长,超调量越小。
2129 *
2130 * @retval 0 成功
2131 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2132 * Normal、ReducedMode、Recovery 状态
2133 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
2134 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2135 * @retval -AUBO_BAD_STATE(-1)
2136 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2137 * 未找到,或者当前机器人模式非 Running
2138 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2139 * @retval -AUBO_INVL_ARGUMENT(-5) 轨迹位置超限、速度超限或相邻点角度差超限(±15°)
2140 * @retval -AUBO_REQUEST_IGNORE(-13) 当前处于非 servo 模式
2141 * @retval -AUBO_POS_BOUND_ERR(-18) 关节位置超出机器人最大限制
2142 * @retval -AUBO_TRAJ_SELF_COLLISION(-22) 轨迹存在自碰撞风险
2143 * @retval -AUBO_ALGORITHM_PLAN_FAILED(-30) 轨迹规划失败
2144 *
2145 * @throws arcs::common_interface::AuboException
2146 *
2147 * @par Python函数原型
2148 * servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2149 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
2150 *
2151 * @par Lua函数原型
2152 * servoJoint(q: table, a: number, v: number, t: number, lookahead_time:
2153 * number, gain: number) -> nil
2154 *
2155 * @par Lua示例
2156 * servoJoint({0,0,0,0,0,0},0,0,10,0,0)
2157 *
2158 * @par JSON-RPC请求示例
2159 * {"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
2160 *
2161 * @par JSON-RPC响应示例
2162 * {"id":1,"jsonrpc":"2.0","result":-13}
2163 *
2164 * \endchinese
2165 * \english
2166 * Joint space servo
2167 *
2168 * Currently only q and t parameters are available;
2169 * @param q Joint angles, unit: rad
2170 * @param a Acceleration, unit: rad/s^2
2171 * @param v Velocity, unit: rad/s
2172 * @param t Execution time, unit: s \n
2173 * The larger the t value, the slower the robot moves, and vice versa;
2174 * The optimal value for this parameter is the interval time for continuous
2175 * calls to the servoJoint interface.
2176 * @param lookahead_time Lookahead time, unit: s \n
2177 * Specifies the duration to move before the robot starts to decelerate,
2178 * used to smooth the trajectory [0.03, 0.2]. When lookahead_time is less
2179 * than one control cycle, the smaller it is, the greater the overshoot. The
2180 * optimal value for this parameter is one control cycle.
2181 * @param gain Proportional gain
2182 * Proportional gain for tracking the target position [100, 200],
2183 * used to control the smoothness and accuracy of the motion.
2184 * The larger the proportional gain, the longer it takes to reach the target
2185 * position, and the smaller the overshoot.
2186 *
2187 * @retval 0 Success
2188 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2189 * ReducedMode, or Recovery
2190 * @retval AUBO_QUEUE_FULL(2) Planning queue is full
2191 * @retval AUBO_BUSY(3) The previous instruction is being executed
2192 * @retval -AUBO_BAD_STATE(-1)
2193 * Possible reasons include but are not limited to: thread has been
2194 * detached, thread terminated, task_id not found, or the current robot mode
2195 * is not Running
2196 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2197 * @retval -AUBO_INVL_ARGUMENT(-5) Trajectory position out of range, velocity
2198 * out of range, or adjacent points angle difference exceeded(±15°)
2199 * @retval -AUBO_REQUEST_IGNORE(-13) Not in servo mode
2200 * @retval -AUBO_POS_BOUND_ERR(-18) Joint position exceeds robot maximum limits
2201 * @retval -AUBO_TRAJ_SELF_COLLISION(-22) Trajectory has self-collision risk
2202 * @retval -AUBO_ALGORITHM_PLAN_FAILED(-30) Trajectory planning failed
2203 *
2204 * @throws arcs::common_interface::AuboException
2205 *
2206 * @par Python function prototype
2207 * servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2208 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
2209 *
2210 * @par Lua function prototype
2211 * servoJoint(q: table, a: number, v: number, t: number, lookahead_time:
2212 * number, gain: number) -> nil
2213 *
2214 * @par Lua example
2215 * servoJoint({0,0,0,0,0,0},0,0,10,0,0)
2216 *
2217 * @par JSON-RPC request example
2218 * {"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
2219 *
2220 * @par JSON-RPC response example
2221 * {"id":1,"jsonrpc":"2.0","result":-13}
2222 *
2223 * \endenglish
2224 */
2225 int servoJoint(const std::vector<double> &q, double a, double v, double t,
2226 double lookahead_time, double gain);
2227
2228 /**
2229 * @ingroup MotionControl
2230 * \chinese
2231 * 笛卡尔空间伺服
2232 *
2233 * 目前可用参数只有 pose 和 t;
2234 * @param pose 位姿, 单位 m,
2235 * @param a 加速度, 单位 m/s^2,
2236 * @param v 速度,单位 m/s,
2237 * @param t 运行时间,单位 s \n
2238 * t 值越大,机器臂运动越慢,反之,运动越快;
2239 * 该参数最优值为连续调用 servoCartesian 接口的间隔时间。
2240 * @param lookahead_time 前瞻时间,单位 s \n
2241 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
2242 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
2243 * 该参数最优值为一个控制周期。
2244 * @param gain 比例增益
2245 * 跟踪目标位置的比例增益[100, 200],
2246 * 用于控制运动的顺滑性和精度,
2247 * 比例增益越大,到达目标位置的时间越长,超调量越小。
2248 *
2249 * @retval 0 成功
2250 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2251 * Normal、ReducedMode、Recovery 状态
2252 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
2253 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2254 * @retval -AUBO_BAD_STATE(-1)
2255 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2256 * 未找到,或者当前机器人模式非 Running
2257 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2258 * @retval -AUBO_INVL_ARGUMENT(-5) 轨迹位置超限或速度超限
2259 * @retval -AUBO_REQUEST_IGNORE(-13) 当前处于非 servo 模式
2260 * @retval -AUBO_IK_NO_CONVERGE(-23) 逆解计算不收敛,计算出错;
2261 * @retval -AUBO_IK_OUT_OF_RANGE(-24) 逆解计算超出机器人最大限制;
2262 * @retval AUBO_IK_CONFIG_DISMATCH(-25) 逆解输入配置存在错误;
2263 * @retval -AUBO_IK_JACOBIAN_FAILED(-26) 逆解雅可比矩阵计算失败;
2264 * @retval -AUBO_IK_NO_SOLU(-27) 目标点存在解析解,但均不满足选解条件;
2265 * @retval -AUBO_IK_UNKOWN_ERROR(-28) 逆解返回未知类型错误;
2266 *
2267 * @throws arcs::common_interface::AuboException
2268 *
2269 * @par Python函数原型
2270 * servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2271 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
2272 *
2273 * @par Lua函数原型
2274 * servoCartesian(pose: table, a: number, v: number, t: number,
2275 * lookahead_time: number, gain: number) -> nil
2276 *
2277 * @par Lua示例
2278 * servoCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0,0,10,0,0)
2279 *
2280 * @par JSON-RPC请求示例
2281 * {"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}
2282 *
2283 * @par JSON-RPC响应示例
2284 * {"id":1,"jsonrpc":"2.0","result":-13}
2285 * \endchinese
2286 * \english
2287 * Cartesian space servo
2288 *
2289 * Currently, only pose and t parameters are available;
2290 * @param pose Pose, unit: m
2291 * @param a Acceleration, unit: m/s^2
2292 * @param v Velocity, unit: m/s
2293 * @param t Execution time, unit: s \n
2294 * The larger the t value, the slower the robot moves, and vice versa;
2295 * The optimal value for this parameter is the interval time for continuous
2296 * calls to the servoCartesian interface.
2297 * @param lookahead_time Lookahead time, unit: s \n
2298 * Specifies the duration to move before the robot starts to decelerate,
2299 * used to smooth the trajectory [0.03, 0.2]. When lookahead_time is less
2300 * than one control cycle, the smaller it is, the greater the overshoot. The
2301 * optimal value for this parameter is one control cycle.
2302 * @param gain Proportional gain
2303 * Proportional gain for tracking the target position [100, 200],
2304 * used to control the smoothness and accuracy of the motion,
2305 * The larger the proportional gain, the longer it takes to reach the target
2306 * position, and the smaller the overshoot.
2307 *
2308 * @retval 0 Success
2309 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2310 * ReducedMode, or Recovery
2311 * @retval AUBO_QUEUE_FULL(2) Planning queue is full
2312 * @retval AUBO_BUSY(3) The previous instruction is being executed
2313 * @retval -AUBO_BAD_STATE(-1)
2314 * Possible reasons include but are not limited to: thread has been
2315 * detached, thread terminated, task_id not found, or the current robot mode
2316 * is not Running
2317 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2318 * @retval -AUBO_INVL_ARGUMENT(-5) Trajectory position or velocity out of
2319 * range
2320 * @retval -AUBO_REQUEST_IGNORE(-13) Not in servo mode
2321 * @retval -AUBO_IK_NO_CONVERGE(-23) Inverse kinematics calculation does not
2322 * converge, calculation error;
2323 * @retval -AUBO_IK_OUT_OF_RANGE(-24) Inverse kinematics calculation exceeds
2324 * robot maximum limits;
2325 * @retval AUBO_IK_CONFIG_DISMATCH(-25) Inverse kinematics input
2326 * configuration error;
2327 * @retval -AUBO_IK_JACOBIAN_FAILED(-26) Inverse kinematics Jacobian
2328 * calculation failed;
2329 * @retval -AUBO_IK_NO_SOLU(-27) Analytical solution exists for the target
2330 * point, but none meet the selection criteria;
2331 * @retval -AUBO_IK_UNKOWN_ERROR(-28) Inverse kinematics returned an unknown
2332 * error type;
2333 *
2334 * @throws arcs::common_interface::AuboException
2335 *
2336 * @par Python function prototype
2337 * servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2338 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
2339 *
2340 * @par Lua function prototype
2341 * servoCartesian(pose: table, a: number, v: number, t: number,
2342 * lookahead_time: number, gain: number) -> nil
2343 *
2344 * @par Lua example
2345 * servoCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0,0,10,0,0)
2346 *
2347 * @par JSON-RPC request example
2348 * {"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}
2349 *
2350 * @par JSON-RPC response example
2351 * {"id":1,"jsonrpc":"2.0","result":-13}
2352 * \endenglish
2353 */
2354 int servoCartesian(const std::vector<double> &pose, double a, double v,
2355 double t, double lookahead_time, double gain);
2356
2357 /**
2358 * @ingroup MotionControl
2359 * \chinese
2360 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
2361 *
2362 * @param q
2363 * @param extq
2364 * @param t
2365 * @param smooth_scale
2366 * @param delay_sacle
2367 * @return
2368 * \endchinese
2369 * \english
2370 * Servo motion (with external axes), used for executing offline
2371 * trajectories, pass-through user planned trajectories, etc.
2372 *
2373 * @param q
2374 * @param extq
2375 * @param t
2376 * @param smooth_scale
2377 * @param delay_sacle
2378 * @return
2379 * \endenglish
2380 */
2381 int servoJointWithAxes(const std::vector<double> &q,
2382 const std::vector<double> &extq, double a, double v,
2383 double t, double lookahead_time, double gain);
2384
2385 int servoJointWithAxisGroup(const std::vector<double> &q, double a,
2386 double v, double t, double lookahead_time,
2387 double gain, const std::string &group_name,
2388 const std::vector<double> &extq);
2389
2390 /**
2391 * @ingroup MotionControl
2392 * \chinese
2393 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
2394 * 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度
2395 * (由软件内部直接做逆解)
2396 *
2397 * @param pose
2398 * @param extq
2399 * @param t
2400 * @param smooth_scale
2401 * @param delay_sacle
2402 * @return
2403 * \endchinese
2404 * \english
2405 * Servo motion (with external axes), used for executing offline
2406 * trajectories, pass-through user planned trajectories, etc. The difference
2407 * from servoJointWithAxes is that it receives Cartesian poses instead of
2408 * joint angles (inverse kinematics is performed internally by the
2409 * software).
2410 *
2411 * @param pose
2412 * @param extq
2413 * @param t
2414 * @param smooth_scale
2415 * @param delay_sacle
2416 * @return
2417 * \endenglish
2418 */
2419 int servoCartesianWithAxes(const std::vector<double> &pose,
2420 const std::vector<double> &extq, double a,
2421 double v, double t, double lookahead_time,
2422 double gain);
2423
2424 int servoCartesianWithAxisGroup(const std::vector<double> &pose, double a,
2425 double v, double t, double lookahead_time,
2426 double gain, const std::string &group_name,
2427 const std::vector<double> &extq);
2428
2429 /**
2430 * @ingroup MotionControl
2431 * \chinese
2432 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
2433 *
2434 * @param q
2435 * @param smooth_scale
2436 * @param delay_sacle
2437 * @return
2438 *
2439 * @par Lua函数原型
2440 * trackJoint(q: table,t: number,smooth_scale: number,delay_sacle: number)
2441 * -> nil
2442 *
2443 * @par Lua示例
2444 * trackJoint({0,0,0,0,0,0},0.01,0.5,1)
2445 *
2446 * @par JSON-RPC请求示例
2447 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
2448 *
2449 * @par JSON-RPC响应示例
2450 * {"id":1,"jsonrpc":"2.0","result":0}
2451 *
2452 * \endchinese
2453 * \english
2454 * Tracking motion, used for executing offline trajectories or passing
2455 * through user-planned trajectories, etc.
2456 *
2457 * @param q
2458 * @param smooth_scale
2459 * @param delay_sacle
2460 * @return
2461 *
2462 * @par Lua function prototype
2463 * trackJoint(q: table,t: number,smooth_scale: number,delay_sacle: number)
2464 * -> nil
2465 *
2466 * @par Lua example
2467 * trackJoint({0,0,0,0,0,0},0.01,0.5,1)
2468 *
2469 * @par JSON-RPC request example
2470 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
2471 *
2472 * @par JSON-RPC response example
2473 * {"id":1,"jsonrpc":"2.0","result":0}
2474 *
2475 * \endenglish
2476 */
2477 int trackJoint(const std::vector<double> &q, double t, double smooth_scale,
2478 double delay_sacle);
2479
2480 /**
2481 * @ingroup MotionControl
2482 * \chinese
2483 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
2484 * 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度
2485 * (由软件内部直接做逆解)
2486 *
2487 * @param pose
2488 * @param t
2489 * @param smooth_scale
2490 * @param delay_sacle
2491 * @return
2492 *
2493 * @par Lua函数原型
2494 * trackCartesian(pose: table,t: number,smooth_scale: number,delay_sacle:
2495 * number) -> nil
2496 *
2497 * @par Lua示例
2498 * trackCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0.01,0.5,1)
2499 *
2500 * @par JSON-RPC请求示例
2501 * {"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}
2502 *
2503 * @par JSON-RPC响应示例
2504 * {"id":1,"jsonrpc":"2.0","result":0}
2505 * \endchinese
2506 * \english
2507 * Tracking motion, used for executing offline trajectories or passing
2508 * through user-planned trajectories, etc. The difference from trackJoint is
2509 * that it receives Cartesian poses instead of joint angles (inverse
2510 * kinematics is performed internally by the software).
2511 *
2512 * @param pose
2513 * @param t
2514 * @param smooth_scale
2515 * @param delay_sacle
2516 * @return
2517 *
2518 * @par Lua function prototype
2519 * trackCartesian(pose: table,t: number,smooth_scale: number,delay_sacle:
2520 * number) -> nil
2521 *
2522 * @par Lua example
2523 * trackCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0.01,0.5,1)
2524 *
2525 * @par JSON-RPC request example
2526 * {"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}
2527 *
2528 * @par JSON-RPC response example
2529 * {"id":1,"jsonrpc":"2.0","result":0}
2530 * \endenglish
2531 */
2532 int trackCartesian(const std::vector<double> &pose, double t,
2533 double smooth_scale, double delay_sacle);
2534
2535 /**
2536 * @ingroup MotionControl
2537 * \chinese
2538 * 关节空间跟随
2539 *
2540 * @note 暂未实现
2541 *
2542 * @throws arcs::common_interface::AuboException
2543 *
2544 * @par Python函数原型
2545 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2546 *
2547 * @par Lua函数原型
2548 * followJoint(q: table) -> nil
2549 *
2550 * @par Lua示例
2551 * followJoint({0,0,0,0,0,0})
2552 *
2553 * \endchinese
2554 * \english
2555 * Joint space following
2556 *
2557 * @note Not implemented yet
2558 *
2559 * @throws arcs::common_interface::AuboException
2560 *
2561 * @par Python function prototype
2562 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2563 *
2564 * @par Lua function prototype
2565 * followJoint(q: table) -> nil
2566 *
2567 * @par Lua example
2568 * followJoint({0,0,0,0,0,0})
2569 *
2570 * \endenglish
2571 */
2572 int followJoint(const std::vector<double> &q);
2573
2574 /**
2575 * @ingroup MotionControl
2576 * \chinese
2577 * 笛卡尔空间跟随
2578 *
2579 * @note 暂未实现
2580 *
2581 * @throws arcs::common_interface::AuboException
2582 *
2583 * @par Python函数原型
2584 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2585 *
2586 * @par Lua函数原型
2587 * followLine(pose: table) -> nil
2588 *
2589 * @par Lua示例
2590 * followLine({0.58712,-0.15775,0.48703,2.76,0.344,1.432})
2591 *
2592 * \endchinese
2593 * \english
2594 * Cartesian space following
2595 *
2596 * @note Not implemented yet
2597 *
2598 * @throws arcs::common_interface::AuboException
2599 *
2600 * @par Python function prototype
2601 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2602 *
2603 * @par Lua function prototype
2604 * followLine(pose: table) -> nil
2605 *
2606 * @par Lua example
2607 * followLine({0.58712,-0.15775,0.48703,2.76,0.344,1.432})
2608 *
2609 * \endenglish
2610 */
2611 int followLine(const std::vector<double> &pose);
2612
2613 /**
2614 * @ingroup MotionControl
2615 * \chinese
2616 * 关节空间速度跟随
2617 *
2618 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2619 *
2620 * @param qd 目标关节速度, 单位 rad/s
2621 * @param a 主轴的加速度, 单位 rad/s^2
2622 * @param t 函数返回所需要的时间, 单位 s \n
2623 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2624 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。\n
2625 * 如果没有达到目标速度,会减速到零。
2626 * 如果达到了目标速度就是按照目标速度匀速运动。
2627 * @retval 0 成功
2628 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2629 * Normal、ReducedMode、Recovery 状态
2630 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2631 * @retval -AUBO_BAD_STATE(-1)
2632 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2633 * 未找到,或者当前机器人模式非 Running
2634 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2635 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组qd的长度小于当前机器臂的自由度
2636 *
2637 * @throws arcs::common_interface::AuboException
2638 *
2639 * @par Python函数原型
2640 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2641 * float, arg2: float) -> int
2642 *
2643 * @par Lua函数原型
2644 * speedJoint(qd: table, a: number, t: number) -> nil
2645 *
2646 * @par Lua示例
2647 * speedJoint({0.2,0,0,0,0,0}, 1.5,10)
2648 *
2649 * @par JSON-RPC请求示例
2650 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2651 *
2652 * @par JSON-RPC响应示例
2653 * {"id":1,"jsonrpc":"2.0","result":0}
2654 *
2655 * \endchinese
2656 * \english
2657 * Joint space velocity following
2658 *
2659 * When the robot arm has not yet reached the target velocity, giving a new
2660 * target velocity will cause the robot arm to immediately reach the new
2661 * target velocity.
2662 *
2663 * @param qd Target joint velocity, unit: rad/s
2664 * @param a Main axis acceleration, unit: rad/s^2
2665 * @param t Time required for the function to return, unit: s \n
2666 * If t = 0, the function returns when the target velocity is reached;
2667 * otherwise, the function returns after t seconds, regardless of whether
2668 * the target velocity is reached.\n If the target velocity is not reached,
2669 * it will decelerate to zero. If the target velocity is reached, it will
2670 * move at a constant speed.
2671 * @retval 0 Success
2672 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2673 * ReducedMode, or Recovery
2674 * @retval AUBO_BUSY(3) The previous instruction is being executed
2675 * @retval -AUBO_BAD_STATE(-1)
2676 * Possible reasons include but are not limited to: thread has been
2677 * detached, thread terminated, task_id not found, or the current robot mode
2678 * is not Running
2679 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2680 * @retval -AUBO_INVL_ARGUMENT(-5) The length of the qd array is less than
2681 * the degrees of freedom of the current robot arm
2682 *
2683 * @throws arcs::common_interface::AuboException
2684 *
2685 * @par Python function prototype
2686 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2687 * float, arg2: float) -> int
2688 *
2689 * @par Lua function prototype
2690 * speedJoint(qd: table, a: number, t: number) -> nil
2691 *
2692 * @par Lua example
2693 * speedJoint({0.2,0,0,0,0,0}, 1.5,10)
2694 *
2695 * @par JSON-RPC request example
2696 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2697 *
2698 * @par JSON-RPC response example
2699 * {"id":1,"jsonrpc":"2.0","result":0}
2700 *
2701 * \endenglish
2702 */
2703 int speedJoint(const std::vector<double> &qd, double a, double t);
2704
2705 /**
2706 * @ingroup MotionControl
2707 * \chinese
2708 * 关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
2709 *
2710 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2711 *
2712 * @param qd 目标关节速度, 单位 rad/s
2713 * @param a 主轴的加速度, 单位 rad/s^2
2714 * @param t 函数返回所需要的时间, 单位 s
2715 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2716 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
2717 * 如果没有达到目标速度,会减速到零。
2718 * 如果达到了目标速度就是按照目标速度匀速运动。
2719 * @return 成功返回0; 失败返回错误码
2720 * AUBO_BUSY
2721 * -AUBO_INVL_ARGUMENT
2722 * -AUBO_BAD_STATE
2723 *
2724 * @throws arcs::common_interface::AuboException
2725 *
2726 * @par Python函数原型
2727 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2728 * float, arg2: float) -> int
2729 *
2730 * @par Lua函数原型
2731 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
2732 *
2733 * @par Lua示例
2734 * resumeSpeedJoint({0.2,0,0,0,0,0},1.5,10)
2735 *
2736 * @par JSON-RPC请求示例
2737 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2738 *
2739 * @par JSON-RPC响应示例
2740 * {"id":1,"jsonrpc":"2.0","result":-1}
2741 * \endchinese
2742 * \english
2743 * Joint space velocity following (used to move to a safe position after a
2744 * collision during process execution)
2745 *
2746 * When the robot arm has not yet reached the target velocity, giving a new
2747 * target velocity will cause the robot arm to immediately reach the new
2748 * target velocity.
2749 *
2750 * @param qd Target joint velocity, unit: rad/s
2751 * @param a Main axis acceleration, unit: rad/s^2
2752 * @param t Time required for the function to return, unit: s
2753 * If t = 0, the function returns when the target velocity is reached;
2754 * otherwise, the function returns after t seconds, regardless of whether
2755 * the target velocity is reached. If the target velocity is not reached, it
2756 * will decelerate to zero. If the target velocity is reached, it will move
2757 * at a constant speed.
2758 * @return Returns 0 on success; otherwise returns error code
2759 * AUBO_BUSY
2760 * -AUBO_INVL_ARGUMENT
2761 * -AUBO_BAD_STATE
2762 *
2763 * @throws arcs::common_interface::AuboException
2764 *
2765 * @par Python function prototype
2766 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2767 * float, arg2: float) -> int
2768 *
2769 * @par Lua function prototype
2770 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
2771 *
2772 * @par Lua example
2773 * resumeSpeedJoint({0.2,0,0,0,0,0},1.5,10)
2774 *
2775 * @par JSON-RPC request example
2776 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2777 *
2778 * @par JSON-RPC response example
2779 * {"id":1,"jsonrpc":"2.0","result":-1}
2780 * \endenglish
2781 */
2782 int resumeSpeedJoint(const std::vector<double> &qd, double a, double t);
2783
2784 /**
2785 * @ingroup MotionControl
2786 * \chinese
2787 * 笛卡尔空间速度跟随
2788 *
2789 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2790 *
2791 * @param xd 工具速度, 单位 m/s
2792 * @param a 工具位置加速度, 单位 m/s^2
2793 * @param t 函数返回所需要的时间, 单位 s \n
2794 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2795 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
2796 * 如果没有达到目标速度,会减速到零。
2797 * 如果达到了目标速度就是按照目标速度匀速运动。
2798 * @retval 0 成功
2799 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2800 * Normal、ReducedMode、Recovery 状态
2801 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2802 * @retval -AUBO_BAD_STATE(-1)
2803 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2804 * 未找到,或者当前机器人模式非 Running
2805 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2806 *
2807 * @throws arcs::common_interface::AuboException
2808 *
2809 * @par Python函数原型
2810 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
2811 * arg2: float) -> int
2812 *
2813 * @par Lua函数原型
2814 * speedLine(pose: table, a: number, t: number) -> nil
2815 *
2816 * @par Lua示例
2817 * speedLine({0.25,0,0,0,0,0},1.2,100)
2818 *
2819 * @par JSON-RPC请求示例
2820 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2821 *
2822 * @par JSON-RPC响应示例
2823 * {"id":1,"jsonrpc":"2.0","result":0}
2824 *
2825 * \endchinese
2826 * \english
2827 * Cartesian space velocity following
2828 *
2829 * When the robot arm has not yet reached the target velocity, giving a new
2830 * target velocity will cause the robot arm to immediately reach the new
2831 * target velocity.
2832 *
2833 * @param xd Tool velocity, unit: m/s
2834 * @param a Tool position acceleration, unit: m/s^2
2835 * @param t Time required for the function to return, unit: s \n
2836 * If t = 0, the function returns when the target velocity is reached;
2837 * otherwise, the function returns after t seconds, regardless of whether
2838 * the target velocity is reached. If the target velocity is not reached, it
2839 * will decelerate to zero. If the target velocity is reached, it will move
2840 * at a constant speed.
2841 * @retval 0 Success
2842 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2843 * ReducedMode, or Recovery
2844 * @retval AUBO_BUSY(3) The previous instruction is being executed
2845 * @retval -AUBO_BAD_STATE(-1)
2846 * Possible reasons include but are not limited to: thread has been
2847 * detached, thread terminated, task_id not found, or the current robot mode
2848 * is not Running
2849 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2850 *
2851 * @throws arcs::common_interface::AuboException
2852 *
2853 * @par Python function prototype
2854 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
2855 * arg2: float) -> int
2856 *
2857 * @par Lua function prototype
2858 * speedLine(pose: table, a: number, t: number) -> nil
2859 *
2860 * @par Lua example
2861 * speedLine({0.25,0,0,0,0,0},1.2,100)
2862 *
2863 * @par JSON-RPC request example
2864 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2865 *
2866 * @par JSON-RPC response example
2867 * {"id":1,"jsonrpc":"2.0","result":0}
2868 *
2869 * \endenglish
2870 */
2871 int speedLine(const std::vector<double> &xd, double a, double t);
2872
2873 /**
2874 * @ingroup MotionControl
2875 * \chinese
2876 * 笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
2877 *
2878 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2879 *
2880 * @param xd 工具速度, 单位 m/s
2881 * @param a 工具位置加速度, 单位 m/s^2
2882 * @param t 函数返回所需要的时间, 单位 s \n
2883 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2884 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
2885 * 如果没有达到目标速度,会减速到零。
2886 * 如果达到了目标速度就是按照目标速度匀速运动。
2887 * @return 成功返回0; 失败返回错误码
2888 * -AUBO_BAD_STATE
2889 *
2890 * @throws arcs::common_interface::AuboException
2891 *
2892 * @par Python函数原型
2893 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2894 * float, arg2: float) -> int
2895 *
2896 * @par Lua函数原型
2897 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
2898 *
2899 * @par Lua示例
2900 * resumeSpeedLine({0.25,0,0,0,0,0},1.2,100)
2901 *
2902 * @par JSON-RPC请求示例
2903 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2904 *
2905 * @par JSON-RPC响应示例
2906 * {"id":1,"jsonrpc":"2.0","result":-1}
2907 * \endchinese
2908 * \english
2909 * Cartesian space velocity following (used to move to a safe position after
2910 * a collision during process execution)
2911 *
2912 * When the robot arm has not yet reached the target velocity, giving a new
2913 * target velocity will cause the robot arm to immediately reach the new
2914 * target velocity.
2915 *
2916 * @param xd Tool velocity, unit: m/s
2917 * @param a Tool position acceleration, unit: m/s^2
2918 * @param t Time required for the function to return, unit: s \n
2919 * If t = 0, the function returns when the target velocity is reached;
2920 * otherwise, the function returns after t seconds, regardless of whether
2921 * the target velocity is reached. If the target velocity is not reached, it
2922 * will decelerate to zero. If the target velocity is reached, it will move
2923 * at a constant speed.
2924 * @return Returns 0 on success; otherwise returns error code
2925 * -AUBO_BAD_STATE
2926 *
2927 * @throws arcs::common_interface::AuboException
2928 *
2929 * @par Python function prototype
2930 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2931 * float, arg2: float) -> int
2932 *
2933 * @par Lua function prototype
2934 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
2935 *
2936 * @par Lua example
2937 * resumeSpeedLine({0.25,0,0,0,0,0},1.2,100)
2938 *
2939 * @par JSON-RPC request example
2940 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2941 *
2942 * @par JSON-RPC response example
2943 * {"id":1,"jsonrpc":"2.0","result":-1}
2944 * \endenglish
2945 */
2946 int resumeSpeedLine(const std::vector<double> &xd, double a, double t);
2947
2948 /**
2949 * @ingroup MotionControl
2950 * \chinese
2951 * 在关节空间做样条插值
2952 *
2953 * @param q 关节角度,如果传入参数维度为0,表示样条运动结束
2954 * @param a 加速度, 单位 rad/s^2,
2955 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
2956 * @param v 速度, 单位 rad/s,
2957 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
2958 * @param duration
2959 * @return 成功返回0; 失败返回错误码
2960 * AUBO_BUSY
2961 * AUBO_BAD_STATE
2962 * -AUBO_BAD_STATE
2963 *
2964 * @throws arcs::common_interface::AuboException
2965 *
2966 * @par Python函数原型
2967 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2968 * float, arg2: float, arg3: float) -> int
2969 *
2970 * @par Lua函数原型
2971 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
2972 *
2973 * @par Lua示例
2974 * moveSpline({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033,
2975 * -2.28774},1.3,1.0,0)
2976 *
2977 * @par JSON-RPC请求示例
2978 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
2979 *
2980 * @par JSON-RPC响应示例
2981 * {"id":1,"jsonrpc":"2.0","result":0}
2982 * \endchinese
2983 * \english
2984 * Perform spline interpolation in joint space
2985 *
2986 * @param q Joint angles. If the input vector is of size 0, it indicates the
2987 * end of the spline motion.
2988 * @param a Acceleration, unit: rad/s^2. The maximum value can be obtained
2989 * via RobotConfig::getJointMaxAccelerations().
2990 * @param v Velocity, unit: rad/s. The maximum value can be obtained via
2991 * RobotConfig::getJointMaxSpeeds().
2992 * @param duration
2993 * @return Returns 0 on success; otherwise returns an error code:
2994 * AUBO_BUSY
2995 * AUBO_BAD_STATE
2996 * -AUBO_BAD_STATE
2997 *
2998 * @throws arcs::common_interface::AuboException
2999 *
3000 * @par Python function prototype
3001 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3002 * float, arg2: float, arg3: float) -> int
3003 *
3004 * @par Lua function prototype
3005 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
3006 *
3007 * @par Lua example
3008 * moveSpline({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033,
3009 * -2.28774},1.3,1.0,0)
3010 *
3011 * @par JSON-RPC request example
3012 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
3013 *
3014 * @par JSON-RPC response example
3015 * {"id":1,"jsonrpc":"2.0","result":0}
3016 * \endenglish
3017 */
3018 int moveSpline(const std::vector<double> &q, double a, double v,
3019 double duration);
3020
3021 /**
3022 * @ingroup MotionControl
3023 * \chinese
3024 * 添加关节运动
3025 *
3026 * @param q 关节角, 单位 rad
3027 * @param a 加速度, 单位 rad/s^2,
3028 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
3029 * @param v 速度, 单位 rad/s,
3030 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
3031 * @param blend_radius 交融半径, 单位 m
3032 * @param duration 运行时间,单位 s \n
3033 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3034 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3035 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3036 * 当 duration = 0的时候,
3037 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3038 * 如果duration不等于0,a 和 v 的值将被忽略。
3039 * @retval 0 成功
3040 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
3041 * Normal、ReducedMode、Recovery 状态
3042 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
3043 * @retval AUBO_BUSY(3) 上一条指令正在执行中
3044 * @retval -AUBO_BAD_STATE(-1)
3045 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
3046 * 未找到,或者当前机器人模式非 Running
3047 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
3048 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组q的长度小于当前机器臂的自由度
3049 * @retval AUBO_REQUEST_IGNORE(13) 参数数组q的长度太短且无需在该点停留
3050 *
3051 * @throws arcs::common_interface::AuboException
3052 *
3053 * @par Python函数原型
3054 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
3055 * arg2: float, arg3: float, arg4: float) -> int
3056 *
3057 * @par Lua函数原型
3058 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
3059 * number) -> nil
3060 *
3061 * @par Lua示例
3062 * moveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033,
3063 * -2.28774},0.3,0.3,0,0)
3064 *
3065 * @par JSON-RPC请求示例
3066 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
3067 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
3068 *
3069 * @par JSON-RPC响应示例
3070 * {"id":1,"jsonrpc":"2.0","result":0}
3071 *
3072 * \endchinese
3073 * \english
3074 * Add joint motion
3075 *
3076 * @param q Joint angles, unit: rad
3077 * @param a Acceleration, unit: rad/s^2,
3078 * The maximum value can be obtained via
3079 * RobotConfig::getJointMaxAccelerations()
3080 * @param v Velocity, unit: rad/s,
3081 * The maximum value can be obtained via RobotConfig::getJointMaxSpeeds()
3082 * @param blend_radius Blend radius, unit: m
3083 * @param duration Execution time, unit: s \n
3084 * Normally, when speed and acceleration are given, the trajectory duration
3085 * can be determined. If you want to extend the trajectory duration, set the
3086 * duration parameter. Duration can extend the trajectory time, but cannot
3087 * shorten it.\n When duration = 0, it means the execution time is not
3088 * specified, and the time will be calculated based on speed and
3089 * acceleration. If duration is not 0, a and v values will be ignored.
3090 * @retval 0 Success
3091 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
3092 * ReducedMode, or Recovery
3093 * @retval AUBO_QUEUE_FULL(2) Planning queue is full
3094 * @retval AUBO_BUSY(3) The previous instruction is being executed
3095 * @retval -AUBO_BAD_STATE(-1)
3096 * Possible reasons include but are not limited to: thread has been
3097 * detached, thread terminated, task_id not found, or the current robot mode
3098 * is not Running
3099 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
3100 * @retval -AUBO_INVL_ARGUMENT(-5) The length of q is less than the degrees
3101 * of freedom of the current robot arm
3102 * @retval AUBO_REQUEST_IGNORE(13) The length of q is too short and there is
3103 * no need to stop at that point
3104 *
3105 * @throws arcs::common_interface::AuboException
3106 *
3107 * @par Python function prototype
3108 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
3109 * arg2: float, arg3: float, arg4: float) -> int
3110 *
3111 * @par Lua function prototype
3112 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
3113 * number) -> nil
3114 *
3115 * @par Lua example
3116 * moveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033,
3117 * -2.28774},0.3,0.3,0,0)
3118 *
3119 * @par JSON-RPC request example
3120 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
3121 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
3122 *
3123 * @par JSON-RPC response example
3124 * {"id":1,"jsonrpc":"2.0","result":0}
3125 *
3126 * \endenglish
3127 */
3128 int moveJoint(const std::vector<double> &q, double a, double v,
3129 double blend_radius, double duration);
3130
3131 /**
3132 * @ingroup MotionControl
3133 * \chinese
3134 * 机器人与外部轴同步运动
3135 *
3136 * @param group_name
3137 * @param q
3138 * @param a
3139 * @param v
3140 * @param blend_radius
3141 * @param duration
3142 * @return
3143 * \endchinese
3144 * \english
3145 * Synchronous motion of robot and external axes
3146 *
3147 * @param group_name
3148 * @param q
3149 * @param a
3150 * @param v
3151 * @param blend_radius
3152 * @param duration
3153 * @return
3154 * \endenglish
3155 */
3156 int moveJointWithAxisGroup(const std::vector<double> &q, double a, double v,
3157 double blend_radius, double duration,
3158 const std::string &group_name,
3159 const std::vector<double> &extq);
3160
3161 /**
3162 * @ingroup MotionControl
3163 * \chinese
3164 * 通过关节运动移动到暂停点的位置
3165 *
3166 * @param q 关节角, 单位 rad
3167 * @param a 加速度, 单位 rad/s^2
3168 * @param v 速度, 单位 rad/s
3169 * @param duration 运行时间,单位 s \n
3170 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3171 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3172 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3173 * 当 duration = 0的时候,
3174 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3175 * 如果duration不等于0,a 和 v 的值将被忽略。
3176 * @return 成功返回0;失败返回错误码
3177 * -AUBO_INVL_ARGUMENT
3178 * -AUBO_BAD_STATE
3179 *
3180 * @throws arcs::common_interface::AuboException
3181 *
3182 * @par Python函数原型
3183 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3184 * float, arg2: float, arg3: float) -> int
3185 *
3186 * @par Lua函数原型
3187 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
3188 *
3189 * @par Lua示例
3190 * resumeMoveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033,
3191 * -2.28774},1.3,1.0,0)
3192 *
3193 * @par JSON-RPC请求示例
3194 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
3195 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
3196 *
3197 * @par JSON-RPC响应示例
3198 * {"id":1,"jsonrpc":"2.0","result":-1}
3199 * \endchinese
3200 * \english
3201 * Move to the pause point using joint motion.
3202 *
3203 * @param q Joint angles, unit: rad
3204 * @param a Acceleration, unit: rad/s^2
3205 * @param v Velocity, unit: rad/s
3206 * @param duration Execution time, unit: s \n
3207 * Normally, when speed and acceleration are given, the trajectory duration
3208 * can be determined. If you want to extend the trajectory duration, set the
3209 * duration parameter. Duration can extend the trajectory time, but cannot
3210 * shorten it.\n When duration = 0, it means the execution time is not
3211 * specified, and the time will be calculated based on speed and
3212 * acceleration. If duration is not 0, a and v values will be ignored.
3213 * @return Returns 0 on success; otherwise returns error code
3214 * -AUBO_INVL_ARGUMENT
3215 * -AUBO_BAD_STATE
3216 *
3217 * @throws arcs::common_interface::AuboException
3218 *
3219 * @par Python function prototype
3220 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3221 * float, arg2: float, arg3: float) -> int
3222 *
3223 * @par Lua function prototype
3224 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
3225 *
3226 * @par Lua example
3227 * resumeMoveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033,
3228 * -2.28774},1.3,1.0,0)
3229 *
3230 * @par JSON-RPC request example
3231 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
3232 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
3233 *
3234 * @par JSON-RPC response example
3235 * {"id":1,"jsonrpc":"2.0","result":-1}
3236 * \endenglish
3237 */
3238 int resumeMoveJoint(const std::vector<double> &q, double a, double v,
3239 double duration);
3240
3241 /**
3242 * @ingroup MotionControl
3243 * \chinese
3244 * 添加直线运动
3245 *
3246 * @param pose 目标位姿
3247 * @param a 加速度(如果位置变化小于1mm,姿态变化大于 1e-4
3248 * rad,此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
3249 * 最大值可通过RobotConfig类中的接口getTcpMaxAccelerations()来获取
3250 * @param v 速度(如果位置变化小于1mm,姿态变化大于 1e-4
3251 * rad,此速度会被作为角速度,单位 rad/s.否则为线速度,单位 m/s)
3252 * 最大值可通过RobotConfig类中的接口getTcpMaxSpeeds()来获取
3253 * @param blend_radius 交融半径,单位 m,值介于0.001和1之间
3254 * @param duration 运行时间,单位 s \n
3255 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3256 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3257 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3258 * 当 duration = 0的时候,
3259 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3260 * 如果duration不等于0,a 和 v 的值将被忽略。
3261 * @retval 0 成功
3262 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
3263 * Normal、ReducedMode、Recovery 状态
3264 * @retval AUBO_QUEUE_FULL(2) 轨迹队列已满
3265 * @retval AUBO_BUSY(3) 上一条指令正在执行中
3266 * @retval -AUBO_BAD_STATE(-1)
3267 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
3268 * 未找到,或者当前机器人模式非 Running
3269 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
3270 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组 pose
3271 * 的长度小于当前机器臂的自由度
3272 * @retval AUBO_REQUEST_IGNORE(13) 参数数组 pose
3273 * 路径长度太短且无需在该点停留
3274 *
3275 * @throws arcs::common_interface::AuboException
3276 *
3277 * @par Python函数原型
3278 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
3279 * arg2: float, arg3: float, arg4: float) -> int
3280 *
3281 * @par Lua函数原型
3282 * moveLine(pose: table, a: number, v: number, blend_radius: number,
3283 * duration: number) -> nil
3284 *
3285 * @par Lua示例
3286 * moveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.3,1.0,0)
3287 *
3288 * @par JSON-RPC请求示例
3289 * {"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}
3290 *
3291 * @par JSON-RPC响应示例
3292 * {"id":1,"jsonrpc":"2.0","result":0}
3293 *
3294 * \endchinese
3295 * \english
3296 * Add linear motion
3297 *
3298 * @param pose Target pose
3299 * @param a Acceleration (if the position change is less than 1mm and the
3300 * posture change is greater than 1e-4 rad, this acceleration is treated as
3301 * angular acceleration in rad/s^2; otherwise, as linear acceleration in
3302 * m/s^2). The maximum value can be obtained via
3303 * RobotConfig::getTcpMaxAccelerations().
3304 * @param v Velocity (if the position change is less than 1mm and the
3305 * posture change is greater than 1e-4 rad, this velocity is treated as
3306 * angular velocity in rad/s; otherwise, as linear velocity in m/s). The
3307 * maximum value can be obtained via RobotConfig::getTcpMaxSpeeds().
3308 * @param blend_radius Blend radius, unit: m, value between 0.001 and 1
3309 * @param duration Execution time, unit: s \n
3310 * Normally, when speed and acceleration are given, the trajectory duration
3311 * can be determined. If you want to extend the trajectory duration, set the
3312 * duration parameter. Duration can extend the trajectory time, but cannot
3313 * shorten it.\n When duration = 0, it means the execution time is not
3314 * specified, and the time will be calculated based on speed and
3315 * acceleration. If duration is not 0, a and v values will be ignored.
3316 * @retval 0 Success
3317 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
3318 * ReducedMode, or Recovery
3319 * @retval AUBO_QUEUE_FULL(2) Trajectory queue is full
3320 * @retval AUBO_BUSY(3) The previous instruction is being executed
3321 * @retval -AUBO_BAD_STATE(-1) Possible reasons include but are not limited
3322 * to: thread has been detached, thread terminated, task_id not found, or
3323 * the current robot mode is not Running
3324 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
3325 * @retval -AUBO_INVL_ARGUMENT(-5) The length of the pose array is less than
3326 * the degrees of freedom of the current robot arm
3327 * @retval AUBO_REQUEST_IGNORE(13) The length of the pose array is too short
3328 * and there is no need to stop at that point
3329 *
3330 * @throws arcs::common_interface::AuboException
3331 *
3332 * @par Python function prototype
3333 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
3334 * arg2: float, arg3: float, arg4: float) -> int
3335 *
3336 * @par Lua function prototype
3337 * moveLine(pose: table, a: number, v: number, blend_radius: number,
3338 * duration: number) -> nil
3339 *
3340 * @par Lua example
3341 * moveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.3,1.0,0)
3342 *
3343 * @par JSON-RPC request example
3344 * {"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}
3345 *
3346 * @par JSON-RPC response example
3347 * {"id":1,"jsonrpc":"2.0","result":0}
3348 *
3349 * \endenglish
3350 */
3351 int moveLine(const std::vector<double> &pose, double a, double v,
3352 double blend_radius, double duration);
3353
3354 /**
3355 * @ingroup MotionControl
3356 * \chinese
3357 * 直线运动与外部轴同步运动
3358 *
3359 * @param group_name 外部轴组名称
3360 * @param pose 目标位姿
3361 * @param a 加速度
3362 * @param v 速度
3363 * @param blend_radius 交融半径
3364 * @param duration 运行时间
3365 * @return
3366 * \endchinese
3367 * \english
3368 * Linear motion synchronized with external axes
3369 *
3370 * @param group_name Name of the external axis group
3371 * @param pose Target pose
3372 * @param a Acceleration
3373 * @param v Velocity
3374 * @param blend_radius Blend radius
3375 * @param duration Execution time
3376 * @return
3377 * \endenglish
3378 */
3379 int moveLineWithAxisGroup(const std::vector<double> &pose, double a,
3380 double v, double blend_radius, double duration,
3381 const std::string &group_name,
3382 const std::vector<double> &extq);
3383
3384 /**
3385 * @ingroup MotionControl
3386 * \chinese
3387 * 添加工艺运动
3388 *
3389 * @param pose
3390 * @param a
3391 * @param v
3392 * @param blend_radius
3393 * @return 成功返回0;失败返回错误码
3394 * AUBO_BAD_STATE
3395 * AUBO_BUSY
3396 * -AUBO_INVL_ARGUMENT
3397 * -AUBO_BAD_STATE
3398 *
3399 * @throws arcs::common_interface::AuboException
3400 *
3401 * @par Lua函数原型
3402 * moveProcess(pose: table, a: number, v: number, blend_radius: number,
3403 * duration: number) -> nil
3404 *
3405 * @par Lua示例
3406 * moveProcess({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3407 *
3408 * @par JSON-RPC请求示例
3409 * {"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}
3410 *
3411 * @par JSON-RPC响应示例
3412 * {"id":1,"jsonrpc":"2.0","result":0}
3413 * \endchinese
3414 * \english
3415 * Add process motion
3416 *
3417 * @param pose
3418 * @param a
3419 * @param v
3420 * @param blend_radius
3421 * @return Returns 0 on success; otherwise returns an error code:
3422 * AUBO_BAD_STATE
3423 * AUBO_BUSY
3424 * -AUBO_INVL_ARGUMENT
3425 * -AUBO_BAD_STATE
3426 *
3427 * @throws arcs::common_interface::AuboException
3428 *
3429 * @par Lua function prototype
3430 * moveProcess(pose: table, a: number, v: number, blend_radius: number,
3431 * duration: number) -> nil
3432 *
3433 * @par Lua example
3434 * moveProcess({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3435 *
3436 * @par JSON-RPC request example
3437 * {"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}
3438 *
3439 * @par JSON-RPC response example
3440 * {"id":1,"jsonrpc":"2.0","result":0}
3441 * \endenglish
3442 */
3443 int moveProcess(const std::vector<double> &pose, double a, double v,
3444 double blend_radius);
3445
3446 /**
3447 * @ingroup MotionControl
3448 * \chinese
3449 * 通过直线运动移动到暂停点的位置
3450 *
3451 * @param pose 目标位姿
3452 * @param a 加速度, 单位 m/s^2
3453 * @param v 速度, 单位 m/s
3454 * @param duration 运行时间,单位 s \n
3455 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3456 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3457 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3458 * 当 duration = 0的时候,
3459 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3460 * 如果duration不等于0,a 和 v 的值将被忽略。
3461 * @return 成功返回0;失败返回错误码
3462 * -AUBO_INVL_ARGUMENT
3463 * -AUBO_BAD_STATE
3464 *
3465 * @throws arcs::common_interface::AuboException
3466 *
3467 * @par Python函数原型
3468 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3469 * float, arg2: float, arg3: float) -> int
3470 *
3471 * @par Lua函数原型
3472 * resumeMoveLine(pose: table, a: number, v: number,duration: number) -> nil
3473 *
3474 * @par Lua示例
3475 * resumeMoveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3476 *
3477 * @par JSON-RPC请求示例
3478 * {"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}
3479 *
3480 * @par JSON-RPC响应示例
3481 * {"id":1,"jsonrpc":"2.0","result":0}
3482 *
3483 * \endchinese
3484 * \english
3485 * Move to the pause point using linear motion.
3486 *
3487 * @param pose Target pose
3488 * @param a Acceleration, unit: m/s^2
3489 * @param v Velocity, unit: m/s
3490 * @param duration Execution time, unit: s \n
3491 * Normally, when speed and acceleration are given, the trajectory duration
3492 * can be determined. If you want to extend the trajectory duration, set the
3493 * duration parameter. Duration can extend the trajectory time, but cannot
3494 * shorten it.\n When duration = 0, it means the execution time is not
3495 * specified, and the time will be calculated based on speed and
3496 * acceleration. If duration is not 0, a and v values will be ignored.
3497 * @return Returns 0 on success; otherwise returns error code
3498 * -AUBO_INVL_ARGUMENT
3499 * -AUBO_BAD_STATE
3500 *
3501 * @throws arcs::common_interface::AuboException
3502 *
3503 * @par Python function prototype
3504 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3505 * float, arg2: float, arg3: float) -> int
3506 *
3507 * @par Lua function prototype
3508 * resumeMoveLine(pose: table, a: number, v: number, duration: number) ->
3509 * nil
3510 *
3511 * @par Lua example
3512 * resumeMoveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3513 *
3514 * @par JSON-RPC request example
3515 * {"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}
3516 *
3517 * @par JSON-RPC response example
3518 * {"id":1,"jsonrpc":"2.0","result":0}
3519 *
3520 * \endenglish
3521 */
3522 int resumeMoveLine(const std::vector<double> &pose, double a, double v,
3523 double duration);
3524
3525 /**
3526 * @ingroup MotionControl
3527 * \chinese
3528 * 添加圆弧运动
3529 *
3530 * @todo 可以由多段圆弧组成圆周运动
3531 *
3532 * @param via_pose 圆弧运动途中点的位姿
3533 * @param end_pose 圆弧运动结束点的位姿
3534 * @param a 加速度(如果via_pose与上一个路点位置变化小于1mm,姿态变化大于 1e-4
3535 * rad, 此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
3536 * @param v 速度(如果via_pose与上一个路点位置变化小于1mm, 姿态变化大于 1e-4
3537 * rad, 此速度会被作为角速度, 单位 rad / s.否则为线速度, 单位 m / s)
3538 * @param blend_radius 交融半径,单位: m
3539 * @param duration 运行时间,单位: s \n
3540 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3541 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3542 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3543 * 当 duration = 0 的时候,
3544 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3545 * 如果duration不等于0,a 和 v 的值将被忽略。
3546 * @return 成功返回0;失败返回错误码
3547 * AUBO_BAD_STATE
3548 * AUBO_BUSY
3549 * -AUBO_INVL_ARGUMENT
3550 * -AUBO_BAD_STATE
3551 *
3552 * @throws arcs::common_interface::AuboException
3553 *
3554 * @par Python函数原型
3555 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3556 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
3557 *
3558 * @par Lua函数原型
3559 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
3560 * blend_radius: number, duration: number) -> nil
3561 *
3562 * @par Lua示例
3563 * moveCircle({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)
3564 *
3565 * @par JSON-RPC请求示例
3566 * {"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}
3567 *
3568 * @par JSON-RPC响应示例
3569 * {"id":1,"jsonrpc":"2.0","result":0}
3570 * \endchinese
3571 * \english
3572 * Add circular arc motion
3573 *
3574 * @todo Can be composed of multiple arcs to form a circular motion
3575 *
3576 * @param via_pose The pose of the via point during the arc motion
3577 * @param end_pose The pose of the end point of the arc motion
3578 * @param a Acceleration (if the position change between via_pose and the
3579 * previous waypoint is less than 1mm and the posture change is greater than
3580 * 1e-4 rad, this acceleration is treated as angular acceleration in
3581 * rad/s^2; otherwise, as linear acceleration in m/s^2)
3582 * @param v Velocity (if the position change between via_pose and the
3583 * previous waypoint is less than 1mm and the posture change is greater than
3584 * 1e-4 rad, this velocity is treated as angular velocity in rad/s;
3585 * otherwise, as linear velocity in m/s)
3586 * @param blend_radius Blend radius, unit: m
3587 * @param duration Execution time, unit: s \n
3588 * Normally, when speed and acceleration are given, the trajectory duration
3589 * can be determined. If you want to extend the trajectory duration, set the
3590 * duration parameter. Duration can extend the trajectory time, but cannot
3591 * shorten it.\n When duration = 0, it means the execution time is not
3592 * specified, and the time will be calculated based on speed and
3593 * acceleration. If duration is not 0, a and v values will be ignored.
3594 * @return Returns 0 on success; otherwise returns error code
3595 * AUBO_BAD_STATE
3596 * AUBO_BUSY
3597 * -AUBO_INVL_ARGUMENT
3598 * -AUBO_BAD_STATE
3599 *
3600 * @throws arcs::common_interface::AuboException
3601 *
3602 * @par Python function prototype
3603 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3604 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
3605 *
3606 * @par Lua function prototype
3607 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
3608 * blend_radius: number, duration: number) -> nil
3609 *
3610 * @par Lua example
3611 * moveCircle({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)
3612 *
3613 * @par JSON-RPC request example
3614 * {"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}
3615 *
3616 * @par JSON-RPC response example
3617 * {"id":1,"jsonrpc":"2.0","result":0}
3618 * \endenglish
3619 */
3620 int moveCircle(const std::vector<double> &via_pose,
3621 const std::vector<double> &end_pose, double a, double v,
3622 double blend_radius, double duration);
3623
3624 /**
3625 * @ingroup MotionControl
3626 * \chinese
3627 * moveCircle 与外部轴同步运动
3628 *
3629 * @param group_name 外部轴组名称
3630 * @param via_pose 圆弧运动途中点的位姿
3631 * @param end_pose 圆弧运动结束点的位姿
3632 * @param a 加速度
3633 * @param v 速度
3634 * @param blend_radius 交融半径
3635 * @param duration 运行时间
3636 * @return
3637 * \endchinese
3638 * \english
3639 * moveCircle with external axes synchronized motion
3640 *
3641 * @param group_name Name of the external axis group
3642 * @param via_pose The pose of the via point during the arc motion
3643 * @param end_pose The pose of the end point of the arc motion
3644 * @param a Acceleration
3645 * @param v Velocity
3646 * @param blend_radius Blend radius
3647 * @param duration Execution time
3648 * @return
3649 * \endenglish
3650 */
3651 int moveCircleWithAxisGroup(const std::vector<double> &via_pose,
3652 const std::vector<double> &end_pose, double a,
3653 double v, double blend_radius, double duration,
3654 const std::string &group_name,
3655 const std::vector<double> &extq);
3656
3657 /**
3658 * @ingroup MotionControl
3659 * \chinese
3660 * 设置圆弧路径模式
3661 *
3662 * @param mode 模式 \n
3663 * 0:工具姿态相对于圆弧路径点坐标系保持不变 \n
3664 * 1:姿态线性变化,绕着空间定轴转动,从起始点姿态变化到目标点姿态 \n
3665 * 2:从起点姿态开始经过中间点姿态,变化到目标点姿态
3666 * @return 成功返回0;失败返回错误码
3667 * AUBO_BAD_STATE
3668 * AUBO_BUSY
3669 * -AUBO_INVL_ARGUMENT
3670 * -AUBO_BAD_STATE
3671 *
3672 * @throws arcs::common_interface::AuboException
3673 *
3674 * @par Python函数原型
3675 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
3676 *
3677 * @par Lua函数原型
3678 * setCirclePathMode(mode: number) -> nil
3679 *
3680 * @par Lua示例
3681 * setCirclePathMode(1)
3682 *
3683 * @par JSON-RPC请求示例
3684 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
3685 *
3686 * @par JSON-RPC响应示例
3687 * {"id":1,"jsonrpc":"2.0","result":0}
3688 *
3689 * \endchinese
3690 * \english
3691 * Set circle path mode
3692 *
3693 * @param mode Mode \n
3694 * 0: Tool orientation remains unchanged relative to the arc path point
3695 * coordinate system \n 1: Orientation changes linearly, rotating around a
3696 * fixed axis in space, from the start orientation to the target orientation
3697 * \n 2: Orientation changes from the start orientation, through the via
3698 * point orientation, to the target orientation
3699 * @return Returns 0 on success; otherwise returns an error code
3700 * AUBO_BAD_STATE
3701 * AUBO_BUSY
3702 * -AUBO_INVL_ARGUMENT
3703 * -AUBO_BAD_STATE
3704 *
3705 * @throws arcs::common_interface::AuboException
3706 *
3707 * @par Python function prototype
3708 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
3709 *
3710 * @par Lua function prototype
3711 * setCirclePathMode(mode: number) -> nil
3712 *
3713 * @par Lua example
3714 * setCirclePathMode(1)
3715 *
3716 * @par JSON-RPC request example
3717 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
3718 *
3719 * @par JSON-RPC response example
3720 * {"id":1,"jsonrpc":"2.0","result":0}
3721 *
3722 * \endenglish
3723 */
3724 int setCirclePathMode(int mode);
3725
3726 /**
3727 * @ingroup MotionControl
3728 * \chinese
3729 * 高级圆弧或者圆周运动
3730 *
3731 * @param param 圆周运动参数
3732 * @return 成功返回0;失败返回错误码
3733 * AUBO_BAD_STATE
3734 * AUBO_BUSY
3735 * -AUBO_INVL_ARGUMENT
3736 * -AUBO_BAD_STATE
3737 *
3738 * @throws arcs::common_interface::AuboException
3739 *
3740 * @par Python函数原型
3741 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
3742 * arcs::common_interface::CircleParameters) -> int
3743 *
3744 * @par Lua函数原型
3745 * moveCircle2(param: table) -> nil
3746 *
3747 * @par Lua示例
3748 * moveCircle2({0.440164,-0.00249391,0.398658,2.45651,0,1.570},{0.440164,0.166256,0.297599,2.45651,0,1.5708},1.2,0.25,0,0,0,0,0,0)
3749 *
3750 * @par JSON-RPC请求示例
3751 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
3752 * "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,
3753 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
3754 *
3755 * @par JSON-RPC响应示例
3756 * {"id":1,"jsonrpc":"2.0","result":0}
3757 * \endchinese
3758 * \english
3759 * Advanced arc or circular motion
3760 *
3761 * @param param Circular motion parameters
3762 * @return Returns 0 on success; otherwise returns an error code:
3763 * AUBO_BAD_STATE
3764 * AUBO_BUSY
3765 * -AUBO_INVL_ARGUMENT
3766 * -AUBO_BAD_STATE
3767 *
3768 * @throws arcs::common_interface::AuboException
3769 *
3770 * @par Python function prototype
3771 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
3772 * arcs::common_interface::CircleParameters) -> int
3773 *
3774 * @par Lua function prototype
3775 * moveCircle2(param: table) -> nil
3776 *
3777 * @par Lua example
3778 * moveCircle2({0.440164,-0.00249391,0.398658,2.45651,0,1.570},{0.440164,0.166256,0.297599,2.45651,0,1.5708},1.2,0.25,0,0,0,0,0,0)
3779 *
3780 * @par JSON-RPC request example
3781 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
3782 * "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,
3783 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
3784 *
3785 * @par JSON-RPC response example
3786 * {"id":1,"jsonrpc":"2.0","result":0}
3787 * \endenglish
3788 */
3790
3791 /**
3792 * @ingroup MotionControl
3793 * \chinese
3794 * 新建一个路径点缓存
3795 *
3796 * @param name 指定路径的名字
3797 * @param type 路径的类型 \n
3798 * 1: toppra 时间最优路径规划 \n
3799 * 2: cubic_spline(录制的轨迹) \n
3800 * 3: 关节B样条插值,最少三个点
3801 * @param size 缓存区大小
3802 * @return 新建成功返回 AUBO_OK(0)
3803 *
3804 * @throws arcs::common_interface::AuboException
3805 *
3806 * @par Python函数原型
3807 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
3808 * arg2: int) -> int
3809 *
3810 * @par Lua函数原型
3811 * pathBufferAlloc(name: string, type: number, size: number) -> nil
3812 *
3813 * @par Lua示例
3814 * pathBufferAlloc("traje_name",5,100)
3815 *
3816 * @par JSON-RPC请求示例
3817 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
3818 *
3819 * @par JSON-RPC响应示例
3820 * {"id":1,"jsonrpc":"2.0","result":0}
3821 *
3822 * \endchinese
3823 * \english
3824 * Create a new path point buffer
3825 *
3826 * @param name Name of the path
3827 * @param type Type of the path \n
3828 * 1: toppra time-optimal path planning \n
3829 * 2: cubic_spline (recorded trajectory) \n
3830 * 3: Joint B-spline interpolation, at least three points
3831 * @param size Buffer size
3832 * @return Returns AUBO_OK(0) on success
3833 *
3834 * @throws arcs::common_interface::AuboException
3835 *
3836 * @par Python function prototype
3837 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
3838 * arg2: int) -> int
3839 *
3840 * @par Lua function prototype
3841 * pathBufferAlloc(name: string, type: number, size: number) -> nil
3842 *
3843 * @par Lua exmaple
3844 * pathBufferAlloc("traje_name",5,100)
3845 *
3846 * @par JSON-RPC request example
3847 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
3848 *
3849 * @par JSON-RPC response example
3850 * {"id":1,"jsonrpc":"2.0","result":0}
3851 *
3852 * \endenglish
3853 */
3854 int pathBufferAlloc(const std::string &name, int type, int size);
3855
3856 /**
3857 * @ingroup MotionControl
3858 * \chinese
3859 * 向路径缓存添加路点
3860 *
3861 * @param name 路径缓存的名字
3862 * @param waypoints 路点
3863 * @return 成功返回0;失败返回错误码
3864 * -AUBO_INVL_ARGUMENT
3865 * -AUBO_BAD_STATE
3866 *
3867 * @throws arcs::common_interface::AuboException
3868 *
3869 * @par Python函数原型
3870 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3871 * List[List[float]]) -> int
3872 *
3873 * @par Lua函数原型
3874 * pathBufferAppend(name: string, waypoints: table) -> nil
3875 *
3876 * @par Lua示例
3877 * pathBufferAppend("traje_name",{{-0.000000,0.000009,-0.000001,0.000002,0.000002,0.000000},{-0.000001,0.000010,-0.000002,0.000000,0.000003,0.000002}})
3878 *
3879 * @par JSON-RPC请求示例
3880 * {"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}
3881 *
3882 * @par JSON-RPC响应示例
3883 * {"id":1,"jsonrpc":"2.0","result":0}
3884 * \endchinese
3885 * \english
3886 * Add waypoints to the path buffer
3887 *
3888 * @param name Name of the path buffer
3889 * @param waypoints Waypoints
3890 * @return Returns 0 on success; otherwise returns an error code
3891 * -AUBO_INVL_ARGUMENT
3892 * -AUBO_BAD_STATE
3893 *
3894 * @throws arcs::common_interface::AuboException
3895 *
3896 * @par Python function prototype
3897 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3898 * List[List[float]]) -> int
3899 *
3900 * @par Lua function prototype
3901 * pathBufferAppend(name: string, waypoints: table) -> nil
3902 *
3903 * @par Lua example
3904 * pathBufferAppend("traje_name",{{-0.000000,0.000009,-0.000001,0.000002,0.000002,0.000000},{-0.000001,0.000010,-0.000002,0.000000,0.000003,0.000002}})
3905 *
3906 * @par JSON-RPC request example
3907 * {"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}
3908 *
3909 * @par JSON-RPC response example
3910 * {"id":1,"jsonrpc":"2.0","result":0}
3911 * \endenglish
3912 */
3913 int pathBufferAppend(const std::string &name,
3914 const std::vector<std::vector<double>> &waypoints);
3915
3916 /**
3917 * @ingroup MotionControl
3918 * \chinese
3919 * 计算、优化等耗时操作,传入的参数相同时不会重新计算
3920 *
3921 * @param name 通过pathBufferAlloc新建的路径点缓存的名字
3922 * @param a 关节加速度限制,需要和机器人自由度大小相同,单位 rad/s^2
3923 * @param v 关节速度限制,需要和机器人自由度大小相同,单位 rad/s
3924 * @param t 时间 \n
3925 * pathBufferAlloc 这个接口分配内存的时候要指定类型,
3926 * 根据pathBufferAlloc这个接口的类型:\n
3927 * 类型为1时,表示运动持续时间\n
3928 * 类型为2时,表示采样时间间隔\n
3929 * 类型为3时:t表示运动持续时间\n
3930 * 若 t=0, 则由使用软件内部默认的时间(推荐使用)\n
3931 * 若 t!=0, t需要设置为 路径点数*相邻点时间间隔(points *
3932 * interval,interval >= 0.01)
3933 * @return 成功返回0;失败返回错误码
3934 * -AUBO_INVL_ARGUMENT
3935 * -AUBO_BAD_STATE
3936 *
3937 * @throws arcs::common_interface::AuboException
3938 *
3939 * @par Python函数原型
3940 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3941 * List[float], arg2: List[float], arg3: float) -> int
3942 *
3943 * @par Lua函数原型
3944 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
3945 *
3946 * @par Lua示例
3947 * pathBufferEval("traje_name",{1,1,1,1,1,1},{1,1,1,1,1,1},0.02)
3948 *
3949 * @par JSON-RPC请求示例
3950 * {"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}
3951 *
3952 * @par JSON-RPC响应示例
3953 * {"id":1,"jsonrpc":"2.0","result":0}
3954 * \endchinese
3955 * \english
3956 * Perform computation and optimization (time-consuming operations). If the
3957 * input parameters are the same, the calculation will not be repeated.
3958 *
3959 * @param name Name of the path point buffer created by pathBufferAlloc
3960 * @param a Joint acceleration limits, must match the robot DOF, unit:
3961 * rad/s^2
3962 * @param v Joint velocity limits, must match the robot DOF, unit: rad/s
3963 * @param t Time \n
3964 * When allocating memory with pathBufferAlloc, the type must be specified.
3965 * According to the type in pathBufferAlloc:\n
3966 * Type 1: t means motion duration\n
3967 * Type 2: t means sampling interval\n
3968 * Type 3: t means motion duration\n
3969 * If t=0, the internal default time is used (recommended)\n
3970 * If t!=0, t should be set to number_of_points *
3971 * interval_between_points (interval >= 0.01)
3972 * @return Returns 0 on success; otherwise returns an error code
3973 * -AUBO_INVL_ARGUMENT
3974 * -AUBO_BAD_STATE
3975 *
3976 * @throws arcs::common_interface::AuboException
3977 *
3978 * @par Python function prototype
3979 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3980 * List[float], arg2: List[float], arg3: float) -> int
3981 *
3982 * @par Lua function prototype
3983 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
3984 *
3985 * @par Lua example
3986 * pathBufferEval("traje_name",{1,1,1,1,1,1},{1,1,1,1,1,1},0.02)
3987 *
3988 * @par JSON-RPC request example
3989 * {"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}
3990 *
3991 * @par JSON-RPC response example
3992 * {"id":1,"jsonrpc":"2.0","result":0}
3993 * \endenglish
3994 */
3995 int pathBufferEval(const std::string &name, const std::vector<double> &a,
3996 const std::vector<double> &v, double t);
3997
3998 /**
3999 * @ingroup MotionControl
4000 * \chinese
4001 * 指定名字的buffer是否有效
4002 *
4003 * buffer需要满足三个条件有效: \n
4004 * 1、buffer存在,已经分配过内存 \n
4005 * 2、传进buffer的点要大于等于buffer的大小 \n
4006 * 3、要执行一次pathBufferEval
4007 *
4008 * @param name buffer的名字
4009 * @return 有效返回true; 无效返回false
4010 *
4011 * @throws arcs::common_interface::AuboException
4012 *
4013 * @par Python函数原型
4014 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
4015 *
4016 * @par Lua函数原型
4017 * pathBufferValid(name: string) -> boolean
4018 *
4019 * @par Lua示例
4020 * buffer_status = pathBufferValid("traje_name")
4021 *
4022 * @par JSON-RPC请求示例
4023 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
4024 *
4025 * @par JSON-RPC响应示例
4026 * {"id":1,"jsonrpc":"2.0","result":false}
4027 * \endchinese
4028 * \english
4029 * Whether the buffer with the specified name is valid
4030 *
4031 * The buffer must meet three conditions to be valid: \n
4032 * 1. The buffer exists and memory has been allocated \n
4033 * 2. The number of points passed into the buffer must be greater than or
4034 * equal to the buffer size \n
4035 * 3. pathBufferEval must be executed once
4036 *
4037 * @param name Name of the buffer
4038 * @return Returns true if valid; false otherwise
4039 *
4040 * @throws arcs::common_interface::AuboException
4041 *
4042 * @par Python function prototype
4043 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
4044 *
4045 * @par Lua function prototype
4046 * pathBufferValid(name: string) -> boolean
4047 *
4048 * @par Lua example
4049 * buffer_status = pathBufferValid("traje_name")
4050 *
4051 * @par JSON-RPC request example
4052 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
4053 *
4054 * @par JSON-RPC response example
4055 * {"id":1,"jsonrpc":"2.0","result":false}
4056 * \endenglish
4057 */
4058 bool pathBufferValid(const std::string &name);
4059
4060 /**
4061 * @ingroup MotionControl
4062 * \chinese
4063 * 释放路径缓存
4064 *
4065 * @param name 缓存路径的名字
4066 * @return 成功返回0;失败返回错误码
4067 * -AUBO_INVL_ARGUMENT
4068 * -AUBO_BAD_STATE
4069 *
4070 * @throws arcs::common_interface::AuboException
4071 *
4072 * @par Python函数原型
4073 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4074 *
4075 * @par Lua函数原型
4076 * pathBufferFree(name: string) -> nil
4077 *
4078 * @par Lua示例
4079 * pathBufferFree("traje_name")
4080 *
4081 * @par JSON-RPC请求示例
4082 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
4083 *
4084 * @par JSON-RPC响应示例
4085 * {"id":1,"jsonrpc":"2.0","result":-5}
4086 *
4087 * \endchinese
4088 * \english
4089 * Release path buffer
4090 *
4091 * @param name Name of the path buffer
4092 * @return Returns 0 on success; otherwise returns an error code
4093 * -AUBO_INVL_ARGUMENT
4094 * -AUBO_BAD_STATE
4095 *
4096 * @throws arcs::common_interface::AuboException
4097 *
4098 * @par Python function prototype
4099 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4100 *
4101 * @par Lua function prototype
4102 * pathBufferFree(name: string) -> nil
4103 *
4104 * @par Lua example
4105 * pathBufferFree("traje_name")
4106 *
4107 * @par JSON-RPC request example
4108 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
4109 *
4110 * @par JSON-RPC response example
4111 * {"id":1,"jsonrpc":"2.0","result":-5}
4112 *
4113 * \endenglish
4114 */
4115 int pathBufferFree(const std::string &name);
4116
4117 /**
4118 * @ingroup MotionControl
4119 * \chinese
4120 * 关节空间路径滤波器
4121 *
4122 * @brief pathBufferFilter
4123 *
4124 * @param name 缓存路径的名称
4125 * @param order 滤波器阶数(一般取2)
4126 * @param fd 截止频率,越小越光滑,但是延迟会大(一般取3-20)
4127 * @param fs 离散数据的采样频率(一般取20-500)
4128 *
4129 * @return 成功返回0
4130 *
4131 * @throws arcs::common_interface::AuboException
4132 *
4133 * @par Python函数原型
4134 * pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
4135 * arg2: float, arg3: float) -> int
4136 *
4137 * @par Lua函数原型
4138 * pathBufferFilter(name: string, order: number, fd: number, fs:number) ->
4139 * nil
4140 *
4141 * @par Lua示例
4142 * pathBufferFilter("traje_name",2,5,125)
4143 *
4144 * \endchinese
4145 * \english
4146 * Joint space path filter
4147 *
4148 * @brief pathBufferFilter
4149 *
4150 * @param name Name of the path buffer
4151 * @param order Filter order (usually 2)
4152 * @param fd Cutoff frequency, the smaller the smoother but with more delay
4153 * (usually 3-20)
4154 * @param fs Sampling frequency of discrete data (usually 20-500)
4155 *
4156 * @return Returns 0 on success
4157 *
4158 * @throws arcs::common_interface::AuboException
4159 *
4160 * @par Python function prototype
4161 * pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
4162 * arg2: float, arg3: float) -> int
4163 *
4164 * @par Lua function prototype
4165 * pathBufferFilter(name: string, order: number, fd: number, fs:number) ->
4166 * nil
4167 *
4168 * @par Lua example
4169 * pathBufferFilter("traje_name",2,5,125)
4170 *
4171 * \endenglish
4172 */
4173 int pathBufferFilter(const std::string &name, int order, double fd,
4174 double fs);
4175
4176 /**
4177 * @ingroup MotionControl
4178 * \chinese
4179 * 列出所有缓存路径的名字
4180 *
4181 * @return 返回所有缓存路径的名字
4182 *
4183 * @throws arcs::common_interface::AuboException
4184 *
4185 * @par Python函数原型
4186 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
4187 *
4188 * @par Lua函数原型
4189 * pathBufferList() -> table
4190 *
4191 * @par Lua示例
4192 * Buffer_table = pathBufferList()
4193 *
4194 * @par JSON-RPC请求示例
4195 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
4196 *
4197 * @par JSON-RPC响应示例
4198 * {"id":1,"jsonrpc":"2.0","result":[]}
4199 *
4200 * \endchinese
4201 * \english
4202 * List all cached path names
4203 *
4204 * @return Returns all cached path names
4205 *
4206 * @throws arcs::common_interface::AuboException
4207 *
4208 * @par Python function prototype
4209 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
4210 *
4211 * @par Lua function prototype
4212 * pathBufferList() -> table
4213 *
4214 * @par Lua example
4215 * Buffer_table = pathBufferList()
4216 *
4217 * @par JSON-RPC request example
4218 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
4219 *
4220 * @par JSON-RPC response example
4221 * {"id":1,"jsonrpc":"2.0","result":[]}
4222 *
4223 * \endenglish
4224 */
4225 std::vector<std::string> pathBufferList();
4226
4227 /**
4228 * @ingroup MotionControl
4229 * \chinese
4230 * 执行缓存的路径
4231 *
4232 * @param name 缓存路径的名字
4233 * @return 成功返回0;失败返回错误码
4234 * -AUBO_INVL_ARGUMENT
4235 * -AUBO_BAD_STATE
4236 *
4237 * @throws arcs::common_interface::AuboException
4238 *
4239 * @par Python函数原型
4240 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4241 *
4242 * @par Lua函数原型
4243 * movePathBuffer(name: string) -> nil
4244 *
4245 * @par Lua示例
4246 * movePathBuffer("traje_name")
4247 *
4248 * @par JSON-RPC请求示例
4249 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
4250 *
4251 * @par JSON-RPC响应示例
4252 * {"id":1,"jsonrpc":"2.0","result":0}
4253 * \endchinese
4254 * \english
4255 * Execute the cached path
4256 *
4257 * @param name Name of the cached path
4258 * @return Returns 0 on success; otherwise returns an error code
4259 * -AUBO_INVL_ARGUMENT
4260 * -AUBO_BAD_STATE
4261 *
4262 * @throws arcs::common_interface::AuboException
4263 *
4264 * @par Python function prototype
4265 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4266 *
4267 * @par Lua function prototype
4268 * movePathBuffer(name: string) -> nil
4269 *
4270 * @par Lua example
4271 * movePathBuffer("traje_name")
4272 *
4273 * @par JSON-RPC request example
4274 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
4275 *
4276 * @par JSON-RPC response example
4277 * {"id":1,"jsonrpc":"2.0","result":0}
4278 * \endenglish
4279 */
4280 int movePathBuffer(const std::string &name);
4281
4282 /**
4283 * @ingroup MotionControl
4284 * \chinese
4285 * 相贯线接口
4286 *
4287 * @param pose 由三个示教位姿组成(首先需要运动到起始点,起始点的要求:过主圆柱
4288 * 柱体轴心且与子圆柱体轴线平行的平面与子圆柱体在底部的交点)
4289 * p1:过子圆柱体轴线且与大圆柱体轴线平行的平面,与小圆柱体在左侧顶部的交点
4290 * p2:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在左侧底部的交点
4291 * p3:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在右侧底部的交点
4292 * @param v 速度
4293 * @param a 加速度
4294 * @param main_pipe_radius 主圆柱体半径
4295 * @param sub_pipe_radius 子圆柱体半径
4296 * @param normal_distance 两圆柱体轴线距离
4297 * @param normal_alpha 两圆柱体轴线的夹角
4298 *
4299 * @return 成功返回0;失败返回错误码
4300 * AUBO_BUSY
4301 * AUBO_BAD_STATE
4302 * -AUBO_INVL_ARGUMENT
4303 * -AUBO_BAD_STATE
4304 *
4305 * @throws arcs::common_interface::AuboException
4306 *
4307 * @par Python函数原型
4308 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
4309 * float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float)
4310 * -> int
4311 *
4312 * @par Lua函数原型
4313 * moveIntersection(poses: table, a: number, v: number,
4314 * main_pipe_radius: number, sub_pipe_radius: number, normal_distance:
4315 * number, normal_alpha: number) -> nil \endchinese \english Intersection
4316 * interface
4317 *
4318 * @param poses Consists of three taught poses (first, move to the starting
4319 * point. The starting point requirement: the intersection of the plane
4320 * passing through the main cylinder axis and parallel to the sub-cylinder
4321 * axis with the sub-cylinder at the bottom) p1: Intersection of the plane
4322 * passing through the sub-cylinder axis and parallel to the main cylinder
4323 * axis with the sub-cylinder at the left top p2: Intersection of the plane
4324 * passing through the sub-cylinder axis and parallel to the main cylinder
4325 * axis with the main cylinder at the left bottom p3: Intersection of the
4326 * plane passing through the sub-cylinder axis and parallel to the main
4327 * cylinder axis with the main cylinder at the right bottom
4328 * @param v Velocity
4329 * @param a Acceleration
4330 * @param main_pipe_radius Main cylinder radius
4331 * @param sub_pipe_radius Sub cylinder radius
4332 * @param normal_distance Distance between the two cylinder axes
4333 * @param normal_alpha Angle between the two cylinder axes
4334 *
4335 * @return Returns 0 on success; otherwise returns an error code
4336 * AUBO_BUSY
4337 * AUBO_BAD_STATE
4338 * -AUBO_INVL_ARGUMENT
4339 * -AUBO_BAD_STATE
4340 *
4341 * @throws arcs::common_interface::AuboException
4342 *
4343 * @par Python function prototype
4344 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
4345 * float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float)
4346 * -> int
4347 *
4348 * @par Lua function prototype
4349 * moveIntersection(poses: table, a: number, v: number,
4350 * main_pipe_radius: number, sub_pipe_radius: number, normal_distance:
4351 * number, normal_alpha: number) -> nil \endenglish
4352 */
4353 int moveIntersection(const std::vector<std::vector<double>> &poses,
4354 double a, double v, double main_pipe_radius,
4355 double sub_pipe_radius, double normal_distance,
4356 double normal_alpha);
4357 /**
4358 * @ingroup MotionControl
4359 * \chinese
4360 * 关节空间停止运动
4361 *
4362 * @param acc 关节加速度,单位: rad/s^2
4363 * @return 成功返回0;失败返回错误码
4364 * AUBO_BUSY
4365 * AUBO_BAD_STATE
4366 * -AUBO_INVL_ARGUMENT
4367 * -AUBO_BAD_STATE
4368 *
4369 * @throws arcs::common_interface::AuboException
4370 *
4371 * @par Python函数原型
4372 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4373 *
4374 * @par Lua函数原型
4375 * stopJoint(acc: number) -> nil
4376 *
4377 * @par Lua示例
4378 * stopJoint(2)
4379 *
4380 * @par JSON-RPC请求示例
4381 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
4382 *
4383 * @par JSON-RPC响应示例
4384 * {"id":1,"jsonrpc":"2.0","result":0}
4385 *
4386 * \endchinese
4387 * \english
4388 * Stop motion in joint space
4389 *
4390 * @param acc Joint acceleration, unit: rad/s^2
4391 * @return Returns 0 on success; otherwise returns an error code
4392 * AUBO_BUSY
4393 * AUBO_BAD_STATE
4394 * -AUBO_INVL_ARGUMENT
4395 * -AUBO_BAD_STATE
4396 *
4397 * @throws arcs::common_interface::AuboException
4398 *
4399 * @par Python function prototype
4400 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4401 *
4402 * @par Lua function prototype
4403 * stopJoint(acc: number) -> nil
4404 *
4405 * @par Lua example
4406 * stopJoint(2)
4407 *
4408 * @par JSON-RPC request example
4409 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
4410 *
4411 * @par JSON-RPC response example
4412 * {"id":1,"jsonrpc":"2.0","result":0}
4413 *
4414 * \endenglish
4415 */
4416 int stopJoint(double acc);
4417
4418 /**
4419 * @ingroup MotionControl
4420 * \chinese
4421 * 关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
4422 *
4423 * @param acc 关节加速度,单位: rad/s^2
4424 * @return 成功返回0;失败返回错误码
4425 * AUBO_BUSY
4426 * AUBO_BAD_STATE
4427 * -AUBO_INVL_ARGUMENT
4428 * -AUBO_BAD_STATE
4429 *
4430 * @throws arcs::common_interface::AuboException
4431 *
4432 * @par Python函数原型
4433 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4434 *
4435 * @par Lua函数原型
4436 * resumeStopJoint(acc: number) -> nil
4437 *
4438 * @par Lua示例
4439 * resumeStopJoint(31)
4440 *
4441 * @par JSON-RPC请求示例
4442 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
4443 *
4444 * @par JSON-RPC响应示例
4445 * {"id":1,"jsonrpc":"2.0","result":-1}
4446 *
4447 * \endchinese
4448 * \english
4449 * Stop motion in joint space (used after moving to a safe position via
4450 * resumeSpeedJoint following a collision during process execution)
4451 *
4452 * @param acc Joint acceleration, unit: rad/s^2
4453 * @return Returns 0 on success; otherwise returns an error code
4454 * AUBO_BUSY
4455 * AUBO_BAD_STATE
4456 * -AUBO_INVL_ARGUMENT
4457 * -AUBO_BAD_STATE
4458 *
4459 * @throws arcs::common_interface::AuboException
4460 *
4461 * @par Python function prototype
4462 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4463 *
4464 * @par Lua function prototype
4465 * resumeStopJoint(acc: number) -> nil
4466 *
4467 * @par Lua example
4468 * resumeStopJoint(31)
4469 *
4470 * @par JSON-RPC request example
4471 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
4472 *
4473 * @par JSON-RPC response example
4474 * {"id":1,"jsonrpc":"2.0","result":-1}
4475 *
4476 * \endenglish
4477 */
4478 int resumeStopJoint(double acc);
4479
4480 /**
4481 * @ingroup MotionControl
4482 * \chinese
4483 * 停止 moveLine/moveCircle 等在笛卡尔空间的运动
4484 *
4485 * @param acc 工具加速度, 单位: m/s^2
4486 * @param acc_rot
4487 * @return 成功返回0;失败返回错误码
4488 * AUBO_BUSY
4489 * AUBO_BAD_STATE
4490 * -AUBO_INVL_ARGUMENT
4491 * -AUBO_BAD_STATE
4492 *
4493 * @throws arcs::common_interface::AuboException
4494 *
4495 * @par Python函数原型
4496 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
4497 *
4498 * @par Lua函数原型
4499 * stopLine(acc: number, acc_rot: number) -> nil
4500 *
4501 * @par Lua示例
4502 * stopLine(10,10)
4503 *
4504 * @par JSON-RPC请求示例
4505 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
4506 *
4507 * @par JSON-RPC响应示例
4508 * {"id":1,"jsonrpc":"2.0","result":0}
4509 *
4510 * \endchinese
4511 * \english
4512 * Stop motions in Cartesian space such as moveLine/moveCircle.
4513 *
4514 * @param acc Tool acceleration, unit: m/s^2
4515 * @param acc_rot
4516 * @return Returns 0 on success; otherwise returns an error code
4517 * AUBO_BUSY
4518 * AUBO_BAD_STATE
4519 * -AUBO_INVL_ARGUMENT
4520 * -AUBO_BAD_STATE
4521 *
4522 * @throws arcs::common_interface::AuboException
4523 *
4524 * @par Python function prototype
4525 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
4526 *
4527 * @par Lua function prototype
4528 * stopLine(acc: number, acc_rot: number) -> nil
4529 *
4530 * @par Lua example
4531 * stopLine(10,10)
4532 *
4533 * @par JSON-RPC request example
4534 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
4535 *
4536 * @par JSON-RPC response example
4537 * {"id":1,"jsonrpc":"2.0","result":0}
4538 *
4539 * \endenglish
4540 */
4541 int stopLine(double acc, double acc_rot);
4542
4543 /**
4544 * @ingroup MotionControl
4545 * \chinese
4546 * 笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
4547 *
4548 * @param acc 位置加速度, 单位: m/s^2
4549 * @param acc_rot 姿态加速度,单位: rad/s^2
4550 * @return 成功返回0;失败返回错误码
4551 * AUBO_BUSY
4552 * AUBO_BAD_STATE
4553 * -AUBO_INVL_ARGUMENT
4554 * -AUBO_BAD_STATE
4555 *
4556 * @throws arcs::common_interface::AuboException
4557 *
4558 * @par Python函数原型
4559 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
4560 * -> int
4561 *
4562 * @par Lua函数原型
4563 * resumeStopLine(acc: number, acc_rot: number) -> nil
4564 *
4565 * @par Lua示例
4566 * resumeStopLine(10,10)
4567 *
4568 * @par JSON-RPC请求示例
4569 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
4570 *
4571 * @par JSON-RPC响应示例
4572 * {"id":1,"jsonrpc":"2.0","result":-1}
4573 *
4574 * \endchinese
4575 * \english
4576 * Stop motion in Cartesian space (used after moving to a safe position via
4577 * resumeSpeedLine following a collision during process execution)
4578 *
4579 * @param acc Position acceleration, unit: m/s^2
4580 * @param acc_rot Orientation acceleration, unit: rad/s^2
4581 * @return Returns 0 on success; otherwise returns an error code
4582 * AUBO_BUSY
4583 * AUBO_BAD_STATE
4584 * -AUBO_INVL_ARGUMENT
4585 * -AUBO_BAD_STATE
4586 *
4587 * @throws arcs::common_interface::AuboException
4588 *
4589 * @par Python function prototype
4590 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
4591 * -> int
4592 *
4593 * @par Lua function prototype
4594 * resumeStopLine(acc: number, acc_rot: number) -> nil
4595 *
4596 * @par Lua example
4597 * resumeStopLine(10,10)
4598 *
4599 * @par JSON-RPC request example
4600 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
4601 *
4602 * @par JSON-RPC response example
4603 * {"id":1,"jsonrpc":"2.0","result":-1}
4604 *
4605 * \endenglish
4606 */
4607 int resumeStopLine(double acc, double acc_rot);
4608
4609 /**
4610 * @ingroup MotionControl
4611 * \chinese
4612 *
4613 * \warning 调用 weaveStart 前,需提前开启 RuntimeMachine 规划器 start。
4614 *
4615 * 开始摆动:在 weaveStart 与 weaveEnd 之间的
4616 * moveLine/moveCircle/moveProcess 根据 params 执行摆动。
4617 *
4618 * @param params Json 字符串。
4619 *
4620 * @par 自 v0.29 起的字段
4621 * - "type": <string> —— 波形类型:"SINE" |
4622 * "SPIRAL" | "TRIANGLE" | "TRAPEZOIDAL"(区分大小写)。
4623 * - "step": <number> ——
4624 * 相邻摆动采样的弧长步长,单位 m。
4625 * - "amplitude": [<number>,<number>] —— 摆弧幅度左右侧,单位 m。
4626 * - "hold_distance": [<number>,<number>] ——
4627 * 在幅度峰值处沿路径的停留距离,单位 m。
4628 * - "hold_time": [<number>,<number>] ——
4629 * 在幅度峰值处的停留时间,单位 s。
4630 * - "angle": <number> ——
4631 * 叠加方向与法平面的夹角,单位 rad。
4632 * - "direction": <integer> ——
4633 * 起始摆动方向:0=上方,1=下方。
4634 * - "movep_uniform_vel": <bool> —— moveProcess
4635 * 匀速规划,布尔量。
4636 *
4637 * @par 自 v0.31 起
4638 * - 与 v0.29 相同。
4639 *
4640 * @par 自 v0.32 起新增/变更
4641 * - "angle": [<number>,<number>] ——运动叠加方向与法平面的夹角,单位 rad。
4642 * - "frequency": <number> —— 摆动频率,单位 Hz(范围[0.1, 5])。
4643 * - "ori_weave_range": [<number>,<number>,<number>] —— 姿态摆动范围
4644 * [x,y,z],单位 rad;常与阿基米德螺旋用于力控搜孔。
4645 * - "ori_weave_frequency": [<number>,<number>,<number>] —— 姿态摆动频率
4646 * [x,y,z],单位 m^-1(按路径弧长计;范围 [0, 1])。
4647 * - "adjust_cycle_num": <integer> ——
4648 * 动态调节频率/幅值的过渡段数量。
4649 * - "azimuth": <number> —— 摆焊波形方位角,单位 rad。
4650 * - "ridge_height": <number> —— 中心上升高度,单位 m。
4651 *
4652 * \warning 可使用关系 **frequency = vel / step** 与外部速度 vel 关联(vel
4653 * 单位 m·s^-1)。
4654 * \warning **hold_time** 仅在 **SINE**下可用,且可左右不对称。
4655 * \warning "hold_distance"/"hold_time" 互斥,仅一个生效
4656 *
4657 * \note
4658 * - 数组约定:"amplitude"/"hold_distance"/"hold_time" 为
4659 * [left,right];"ori_weave_*" 为姿态 [x,y,z]。
4660 * - 所有角度均为弧度(rad)。
4661 *
4662 * @return 成功返回0; 失败返回错误码
4663 * - AUBO_BUSY
4664 * - AUBO_BAD_STATE
4665 * - -AUBO_INVL_ARGUMENT
4666 * - -AUBO_BAD_STATE
4667 *
4668 * @throws arcs::common_interface::AuboException
4669 *
4670 * @par 示例 v0.29/v0.31
4671 * \code{.json}
4672 * params = {
4673 * "type": "SINE",
4674 * "step": 0.005,
4675 * "amplitude": [0.01, 0.01],
4676 * "hold_distance": [0.001, 0.001],
4677 * "hold_time": [0, 0],
4678 * "angle": 0,
4679 * "direction": 0,
4680 * "movep_uniform_vel": false
4681 * }
4682 * \endcode
4683 *
4684 * @par 示例 v0.32
4685 * \code{.json}
4686 * params = {
4687 * "type" : "SINE", // "SINE" "SPIRAL" "TRIANGLE" "SAWTOOTH" "CRESCENT"
4688 * "step" : 0.0, // 可用 frequency = vel / step(vel: m·s^-1)
4689 * "frequency" : 0.0, // [0.1, 5] Hz
4690 * "amplitude" : [0.01, 0.01], // m
4691 * "hold_distance" : [0.001, 0.001], // m
4692 * "hold_time" : [0, 0], // s(仅 SINE)
4693 * "angle" : [0, 0], // rad
4694 * "direction" : 0,
4695 * "ori_weave_range" : [0.001, 0.001, 0.001], // rad
4696 * "ori_weave_frequency": [0.001, 0.001, 0.001], // m^-1
4697 * "adjust_cycle_num": 0,
4698 * "azimuth" : 0, // rad
4699 * "ridge_height" : 0 // m
4700 * }
4701 * \endcode
4702 *
4703 * @par Python 函数原型
4704 * \code{.py}
4705 * weaveStart(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4706 * \endcode
4707 *
4708 * @par Python 示例
4709 * \code{.py}
4710 * robot_name = rpc_cli.getRobotNames()[0]
4711 * robot_interface = rpc_cli.getRobotInterface(robot_name)
4712 * robot_interface.getMotionControl().weaveStart(params)
4713 * \endcode
4714 *
4715 * @par Lua 函数原型
4716 * \code{.lua}
4717 * weaveStart(params: string) -> nil
4718 * \endcode
4719 *
4720 * @par Lua 示例(v0.29/0.31)
4721 * \code{.lua}
4722 * weaveStart("{\"type\":\"SINE\",\"step\":0.005,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"movep_uniform_vel\":false}")
4723 * \endcode
4724 *
4725 * @par Lua 示例(v0.32)
4726 * \code{.lua}
4727 * weaveStart("{\"type\":\"SINE\",\"step\":0.0,\"frequency\":2.0,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"ori_weave_range\":[0.001,0.001,0.001],\"ori_weave_frequency\":[0.001,0.001,0.001],\"adjust_cycle_num\":0,\"azimuth\":0,\"ridge_height\":0}")
4728 * \endcode
4729 *
4730 * @par JSON-RPC 请求示例(v0.29/0.31)
4731 * \code{.json}
4732 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveStart","params":["{\"type\":\"SINE\",\"step\":0.005,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"movep_uniform_vel\":false}"],"id":1}
4733 * \endcode
4734 *
4735 * @par JSON-RPC 请求示例(v0.32)
4736 * \code{.json}
4737 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveStart","params":["{\"type\":\"SINE\",\"step\":0.0,\"frequency\":2.0,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"ori_weave_range\":[0.001,0.001,0.001],\"ori_weave_frequency\":[0.001,0.001,0.001],\"adjust_cycle_num\":0,\"azimuth\":0,\"ridge_height\":0}"],"id":1}
4738 * \endcode
4739 *
4740 * @par JSON-RPC 响应示例
4741 * \code{.json}
4742 * {"id":1,"jsonrpc":"2.0","result":0}
4743 * \endcode
4744 * \endchinese
4745 *
4746 * \english
4747 * Start weaving: between weaveStart and weaveEnd,
4748 * moveLine/moveCircle/moveProcess follows params.
4749 *
4750 * \warning Start RuntimeMachine before calling weaveStart.
4751 *
4752 * @param params Json string.
4753 *
4754 * @par Since v0.29
4755 * - "type": <string> — Waveform: "SINE" | "SPIRAL"
4756 * | "TRIANGLE" | "TRAPEZOIDAL" (case-sensitive).
4757 * - "step": <number> — Arc-length sampling step,
4758 * m.
4759 * - "amplitude": [<number>,<number>] — Left/right weave amplitude,
4760 * m.
4761 * - "hold_distance": [<number>,<number>] — Dwell distance at peak
4762 * amplitude along path, m.
4763 * - "hold_time": [<number>,<number>] — Dwell time at peak
4764 * amplitude, s.
4765 * - "angle": <number> — Angle to normal plane, rad.
4766 * - "direction": <integer> — Initial direction: 0=above
4767 * path, 1=below path.
4768 * - "movep_uniform_vel": <bool> — Uniform-velocity planning
4769 * (boolean value).
4770 *
4771 * @par Since v0.31
4772 * - Same as v0.29.
4773 *
4774 * @par New/changed in v0.32
4775 * - "frequency": <number> — Weave frequency, Hz (range
4776 * [0.1, 5]).
4777 * - "ori_weave_range": [<number>,<number>,<number>] — Attitude weave
4778 * range [x,y,z], rad; often used with Archimedean spiral for force-guided
4779 * hole finding.
4780 * - "ori_weave_frequency": [<number>,<number>,<number>] — Attitude weave
4781 * frequency [x,y,z], m^-1 (per unit arc; range [0, 1]).
4782 * - "adjust_cycle_num": <integer> — Number of transition
4783 * cycles.
4784 * - "azimuth": <number> — Waveform azimuth, rad.
4785 * - "ridge_height": <number> — Center raise height, m.
4786 *
4787 * \warning **hold_time** is supported for **SINE** only and may be
4788 * asymmetric. \warning You may relate **frequency = vel / step** when an
4789 * external path speed vel (m·s^-1) is available.
4790 *
4791 * \note
4792 * - Two-element arrays are [left,right]; three-element arrays are attitude
4793 * [x,y,z].
4794 * - All angles are in radians (rad).
4795 *
4796 * @return Returns 0 on success; otherwise returns an error code:
4797 * - AUBO_BUSY
4798 * - AUBO_BAD_STATE
4799 * - -AUBO_INVL_ARGUMENT
4800 * - -AUBO_BAD_STATE
4801 *
4802 * @throws arcs::common_interface::AuboException
4803 *
4804 * @par Example v0.29/v0.31
4805 * \code{.json}
4806 * params = {
4807 * "type": "SINE",
4808 * "step": 0.005,
4809 * "amplitude": [0.01, 0.01],
4810 * "hold_distance": [0.001, 0.001],
4811 * "hold_time": [0, 0],
4812 * "angle": 0,
4813 * "direction": 0,
4814 * "movep_uniform_vel": false
4815 * }
4816 * \endcode
4817 *
4818 * @par Example v0.32
4819 * \code{.json}
4820 * params = {
4821 * "type" : "SINE", // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
4822 * "step" : 0.0, // frequency = vel / step (vel: m·s^-1)
4823 * "frequency" : 0.0, // [0.1, 5] Hz
4824 * "amplitude" : [0.01, 0.01], // m
4825 * "hold_distance" : [0.001, 0.001], // m
4826 * "hold_time" : [0, 0], // s (SINE only)
4827 * "angle" : 0, // rad
4828 * "direction" : 0,
4829 * "ori_weave_range" : [0.001, 0.001, 0.001], // rad
4830 * "ori_weave_frequency": [0.001, 0.001, 0.001], // m^-1
4831 * "adjust_cycle_num": 0,
4832 * "azimuth" : 0, // rad
4833 * "ridge_height" : 0 // m
4834 * }
4835 * \endcode
4836 *
4837 * @par Python function prototype
4838 * \code{.py}
4839 * weaveStart(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4840 * \endcode
4841 *
4842 * @par Python example
4843 * \code{.py}
4844 * robot_name = rpc_cli.getRobotNames()[0]
4845 * robot_interface = rpc_cli.getRobotInterface(robot_name)
4846 * robot_interface.getMotionControl().weaveStart(params)
4847 * \endcode
4848 *
4849 * @par Lua function prototype
4850 * \code{.lua}
4851 * weaveStart(params: string) -> nil
4852 * \endcode
4853 *
4854 * @par Lua example (v0.29/0.31)
4855 * \code{.lua}
4856 * weaveStart("{\"type\":\"SINE\",\"step\":0.005,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"movep_uniform_vel\":false}")
4857 * \endcode
4858 *
4859 * @par Lua example (v0.32)
4860 * \code{.lua}
4861 * weaveStart("{\"type\":\"SINE\",\"step\":0.0,\"frequency\":2.0,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"ori_weave_range\":[0.001,0.001,0.001],\"ori_weave_frequency\":[0.001,0.001,0.001],\"adjust_cycle_num\":0,\"azimuth\":0,\"ridge_height\":0}")
4862 * \endcode
4863 *
4864 * @par JSON-RPC request example (v0.29/0.31)
4865 * \code{.json}
4866 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveStart","params":["{\"type\":\"SINE\",\"step\":0.005,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"movep_uniform_vel\":false}"],"id":1}
4867 * \endcode
4868 *
4869 * @par JSON-RPC request example (v0.32)
4870 * \code{.json}
4871 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveStart","params":["{\"type\":\"SINE\",\"step\":0.0,\"frequency\":2.0,\"amplitude\":[0.01,0.01],\"hold_distance\":[0.001,0.001],\"hold_time\":[0,0],\"angle\":0,\"direction\":0,\"ori_weave_range\":[0.001,0.001,0.001],\"ori_weave_frequency\":[0.001,0.001,0.001],\"adjust_cycle_num\":0,\"azimuth\":0,\"ridge_height\":0}"],"id":1}
4872 * \endcode
4873 *
4874 * @par JSON-RPC response example
4875 * \code{.json}
4876 * {"id":1,"jsonrpc":"2.0","result":0}
4877 * \endcode
4878 * \endenglish
4879 */
4880 int weaveStart(const std::string &params);
4881
4882 /**
4883 * @ingroup MotionControl
4884 * \chinese
4885 * 结束摆动
4886 *
4887 * @return 成功返回0;失败返回错误码
4888 * AUBO_BUSY
4889 * AUBO_BAD_STATE
4890 * -AUBO_BAD_STATE
4891 *
4892 * @throws arcs::common_interface::AuboException
4893 *
4894 * @par JSON-RPC请求示例
4895 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
4896 *
4897 * @par JSON-RPC响应示例
4898 * {"id":1,"jsonrpc":"2.0","result":0}
4899 *
4900 * \endchinese
4901 * \english
4902 * End weaving
4903 *
4904 * @return Returns 0 on success; otherwise returns an error code
4905 * AUBO_BUSY
4906 * AUBO_BAD_STATE
4907 * -AUBO_BAD_STATE
4908 *
4909 * @throws arcs::common_interface::AuboException
4910 *
4911 * @par JSON-RPC request example
4912 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
4913 *
4914 * @par JSON-RPC response example
4915 * {"id":1,"jsonrpc":"2.0","result":0}
4916 *
4917 * \endenglish
4918 */
4920
4921 /**
4922 * @ingroup MotionControl
4923 * \chinese
4924 * 设置未来路径上点的采样时间间隔
4925 *
4926 * @param sample_time 采样时间间隔 单位: m/s^2
4927 * @return 成功返回0;失败返回错误码
4928 * AUBO_BUSY
4929 * AUBO_BAD_STATE
4930 * -AUBO_INVL_ARGUMENT
4931 * -AUBO_BAD_STATE
4932 *
4933 * @throws arcs::common_interface::AuboException
4934 * \endchinese
4935 * \english
4936 * Set the sampling interval for points on the future path
4937 *
4938 * @param sample_time Sampling interval, unit: m/s^2
4939 * @return Returns 0 on success; otherwise returns an error code
4940 * AUBO_BUSY
4941 * AUBO_BAD_STATE
4942 * -AUBO_INVL_ARGUMENT
4943 * -AUBO_BAD_STATE
4944 *
4945 * @throws arcs::common_interface::AuboException
4946 * \endenglish
4947 */
4948 int setFuturePointSamplePeriod(double sample_time);
4949
4950 /**
4951 * @ingroup MotionControl
4952 * \chinese
4953 * 获取未来路径上的轨迹点
4954 *
4955 * @return 路点(100ms * 10)
4956 *
4957 * @throws arcs::common_interface::AuboException
4958 *
4959 * @par JSON-RPC请求示例
4960 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
4961 *
4962 * @par JSON-RPC响应示例
4963 * {"id":1,"jsonrpc":"2.0","result":[]}
4964 *
4965 * \endchinese
4966 * \english
4967 * Get trajectory points on the future path
4968 *
4969 * @return Waypoints (100ms * 10)
4970 *
4971 * @throws arcs::common_interface::AuboException
4972 *
4973 * @par JSON-RPC request example
4974 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
4975 *
4976 * @par JSON-RPC response example
4977 * {"id":1,"jsonrpc":"2.0","result":[]}
4978 *
4979 * \endenglish
4980 */
4981 std::vector<std::vector<double>> getFuturePathPointsJoint();
4982
4983 /**
4984 * @ingroup MotionControl
4985 * \chinese
4986 * 设置传送带编码器参数
4987 *
4988 * @param encoder_id 预留
4989 * @param tick_per_meter
4990 * 线性传送带===>一米的脉冲值
4991 * 环形传送带===>一圈的脉冲值
4992 * @return
4993 *
4994 * @throws arcs::common_interface::AuboException
4995 *
4996 * @par Python函数原型
4997 * setConveyorTrackEncoder(self: pyaubo_sdk.MotionControl) -> int
4998 *
4999 * @par Lua函数原型
5000 * setConveyorTrackEncoder(encoder_id: bumber,tick_per_meter: number) -> int
5001 *
5002 * @par Lua示例
5003 * num = setConveyorTrackEncoder(1,40000)
5004 *
5005 * @par JSON-RPC请求示例
5006 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackEncoder","params":[1,40000],"id":1}
5007 *
5008 * @par JSON-RPC响应示例
5009 * {"id":1,"jsonrpc":"2.0","result":0}
5010 *
5011 * \endchinese
5012 * \english
5013 * Set conveyor encoder parameters
5014 *
5015 * @param encoder_id Reserved
5016 * @param tick_per_meter
5017 * Linear conveyor: pulses per meter
5018 * Circular conveyor: pulses per revolution
5019 * @return
5020 *
5021 * @throws arcs::common_interface::AuboException
5022 *
5023 * @par Python function prototype
5024 * setConveyorTrackEncoder(self: pyaubo_sdk.MotionControl) -> int
5025 *
5026 * @par Lua function prototype
5027 * setConveyorTrackEncoder(encoder_id: bumber,tick_per_meter: number) -> int
5028 *
5029 * @par Lua example
5030 * num = setConveyorTrackEncoder(1,40000)
5031 *
5032 * @par JSON-RPC request example
5033 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackEncoder","params":[1,40000],"id":1}
5034 *
5035 * @par JSON-RPC response example
5036 * {"id":1,"jsonrpc":"2.0","result":0}
5037 *
5038 * \endenglish
5039 */
5040 int setConveyorTrackEncoder(int encoder_id, int tick_per_meter);
5041 /**
5042 * @ingroup MotionControl
5043 * \chinese
5044 * 圆形传送带跟随
5045 *
5046 * @note 暂未实现
5047 *
5048 * @param encoder_id
5049 * 0-集成传感器
5050 * @param rotate_tool
5051 * @return
5052 *
5053 * @throws arcs::common_interface::AuboException
5054 * \endchinese
5055 * \english
5056 * Circular conveyor tracking
5057 *
5058 * @note Not implemented yet
5059 *
5060 * @param encoder_id
5061 * 0 - integrated sensor
5062 * @param rotate_tool
5063 * @return
5064 *
5065 * @throws arcs::common_interface::AuboException
5066 * \endenglish
5067 */
5068 int conveyorTrackCircle(int encoder_id, const std::vector<double> &center,
5069 bool rotate_tool);
5070
5071 /**
5072 * @ingroup MotionControl
5073 * \chinese
5074 * 线性传送带跟随
5075 *
5076 * @param encoder_id 预留
5077 * @param direction 传送带相对机器人基坐标系的移动方向
5078 * @return
5079 *
5080 * @throws arcs::common_interface::AuboException
5081 *
5082 * @par Python函数原型
5083 * conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
5084 *
5085 * @par Lua函数原型
5086 * conveyorTrackLine -> int
5087 *
5088 * @par JSON-RPC请求示例
5089 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
5090 *
5091 * @par JSON-RPC响应示例
5092 * {"id":1,"jsonrpc":"2.0","result":0}
5093 *
5094 * \endchinese
5095 * \english
5096 * Linear conveyor tracking
5097 *
5098 * @param encoder_id Reserved
5099 * @param direction The movement direction of the conveyor relative to the
5100 * robot base coordinate system
5101 * @return
5102 *
5103 * @throws arcs::common_interface::AuboException
5104 *
5105 * @par Python function prototype
5106 * conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
5107 *
5108 * @par Lua function prototype
5109 * conveyorTrackLine -> int
5110 *
5111 * @par JSON-RPC request example
5112 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
5113 *
5114 * @par JSON-RPC response example
5115 * {"id":1,"jsonrpc":"2.0","result":0}
5116 *
5117 * \endenglish
5118 */
5119 int conveyorTrackLine(int encoder_id, const std::vector<double> &direction);
5120
5121 /**
5122 * @ingroup MotionControl
5123 * \chinese
5124 * 终止传送带跟随
5125 *
5126 * @param encoder_id 预留
5127 * @param a 预留
5128 * @return
5129 *
5130 * @throws arcs::common_interface::AuboException
5131 *
5132 * @par Python函数原型
5133 * conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
5134 *
5135 * @par Lua函数原型
5136 * conveyorTrackStop -> int
5137 *
5138 * @par JSON-RPC请求示例
5139 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":[0,1.0],"id":1}
5140 *
5141 * @par JSON-RPC响应示例
5142 * {"id":1,"jsonrpc":"2.0","result":0}
5143 * \endchinese
5144 * \english
5145 * Stop conveyor tracking
5146 *
5147 * @param encoder_id Reserved
5148 * @param a Reserved
5149 * @return
5150 *
5151 * @throws arcs::common_interface::AuboException
5152 *
5153 * @par Python function prototype
5154 * conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
5155 *
5156 * @par Lua function prototype
5157 * conveyorTrackStop -> int
5158 *
5159 * @par JSON-RPC request example
5160 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":[0,1.0],"id":1}
5161 *
5162 * @par JSON-RPC response example
5163 * {"id":1,"jsonrpc":"2.0","result":0}
5164 * \endenglish
5165 */
5166 int conveyorTrackStop(int encoder_id, double a);
5167
5168 /**
5169 * @ingroup MotionControl
5170 * \chinese
5171 * 切换传送带追踪物品
5172 * 如果当前物品正在处于跟踪状态,则将该物品出队,不再跟踪,返回true
5173 * 如果没有物品正在处于跟踪状态,返回false
5174 *
5175 * @return
5176 *
5177 * @throws arcs::common_interface::AuboException
5178 *
5179 * @param encoder_id 预留
5180 *
5181 * @par Python函数原型
5182 * conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
5183 *
5184 * @par Lua函数原型
5185 * conveyorTrackSwitch() -> boolean
5186 *
5187 * @par JSON-RPC请求示例
5188 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
5189 *
5190 * @par JSON-RPC响应示例
5191 * {"id":1,"jsonrpc":"2.0","result":true}
5192 *
5193 * \endchinese
5194 * \english
5195 * Switch conveyor tracking item.
5196 * If the current item is being tracked, it will be dequeued and no longer
5197 * tracked, returning true. If no item is currently being tracked, returns
5198 * false.
5199 *
5200 * @return
5201 *
5202 * @throws arcs::common_interface::AuboException
5203 *
5204 * @param encoder_id Reserved
5205 *
5206 * @par Python function prototype
5207 * conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
5208 *
5209 * @par Lua function prototype
5210 * conveyorTrackSwitch() -> boolean
5211 *
5212 * @par JSON-RPC request example
5213 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
5214 *
5215 * @par JSON-RPC response example
5216 * {"id":1,"jsonrpc":"2.0","result":true}
5217 *
5218 * \endenglish
5219 */
5220 bool conveyorTrackSwitch(int encoder_id);
5221
5222 /**
5223 * @ingroup MotionControl
5224 * \chinese
5225 * 传送带上是否有物品可以跟踪
5226 * @param encoder_id 预留
5227 * @return
5228 * 如果队列第一个物品为跟踪状态,返回true
5229 * 如果队列第一个物品不为跟踪状态,则对队列中其余物品进行是否在启动窗口内的判断
5230 * 超出启动窗口则出队,直到有物品处于启动窗口内,使其变为跟踪状态返回true,
5231 * 队列中没有一个物品在启动窗口内返回false
5232 *
5233 * @throws arcs::common_interface::AuboException
5234 *
5235 * @par Python函数原型
5236 * hasItemOnConveyorToTrack(self: pyaubo_sdk.MotionControl) -> bool
5237 *
5238 * @par Lua函数原型
5239 * hasItemOnConveyorToTrack() -> boolean
5240 *
5241 * @par JSON-RPC请求示例
5242 * {"jsonrpc":"2.0","method":"rob1.MotionControl.hasItemOnConveyorToTrack","params":[0],"id":1}
5243 *
5244 * @par JSON-RPC响应示例
5245 * {"id":1,"jsonrpc":"2.0","result":{true}}
5246 * \endchinese
5247 * \english
5248 * Whether there is an item on the conveyor that can be tracked
5249 * @param encoder_id Reserved
5250 * @return
5251 * If the first item in the queue is in tracking state, returns true.
5252 * If the first item is not in tracking state, checks the rest of the queue
5253 * for items within the start window. Items outside the start window are
5254 * dequeued until an item is found within the window, which is then set to
5255 * tracking state and returns true. If no item in the queue is within the
5256 * start window, returns false.
5257 *
5258 * @throws arcs::common_interface::AuboException
5259 *
5260 * @par Python function prototype
5261 * hasItemOnConveyorToTrack(self: pyaubo_sdk.MotionControl) -> bool
5262 *
5263 * @par Lua function prototype
5264 * hasItemOnConveyorToTrack() -> boolean
5265 *
5266 * @par JSON-RPC request example
5267 * {"jsonrpc":"2.0","method":"rob1.MotionControl.hasItemOnConveyorToTrack","params":[0],"id":1}
5268 *
5269 * @par JSON-RPC response example
5270 * {"id":1,"jsonrpc":"2.0","result":{true}}
5271 * \endenglish
5272 */
5273 bool hasItemOnConveyorToTrack(int encoder_id);
5274
5275 /**
5276 * @ingroup MotionControl
5277 * \chinese
5278 * 增加传送带队列
5279 *
5280 * @param encoder_id 预留
5281 * @param item_id 物品ID
5282 * @param offset 当前物品点位相对于模板物品点位的偏移值
5283 * @return
5284 *
5285 * @throws arcs::common_interface::AuboException
5286 *
5287 * @par Python函数原型
5288 * conveyorTrackCreatItem(self: pyaubo_sdk.MotionControl, arg0: int,
5289 * arg1:int, arg2: List[float]) -> int
5290 *
5291 * @par Lua函数原型
5292 * conveyorTrackCreatItem(encoder_id: number, item_id: number, offset:
5293 * table) -> number
5294 *
5295 * @par JSON-RPC请求示例
5296 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackCreatItem","params":[0,2,
5297 * {0.0,0.0,0.0,0.0,0.0,0.0}],"id":1}
5298 *
5299 * @par JSON-RPC响应示例
5300 * {"id":1,"jsonrpc":"2.0","result":0.0}
5301 * \endchinese
5302 * \english
5303 * Add an item to the conveyor queue
5304 *
5305 * @param encoder_id Reserved
5306 * @param item_id Item ID
5307 * @param offset Offset of the current item position relative to the
5308 * template item position
5309 * @return
5310 *
5311 * @throws arcs::common_interface::AuboException
5312 *
5313 * @par Python function prototype
5314 * conveyorTrackCreatItem(self: pyaubo_sdk.MotionControl, arg0: int,
5315 * arg1:int, arg2: List[float]) -> int
5316 *
5317 * @par Lua function prototype
5318 * conveyorTrackCreatItem(encoder_id: number, item_id: number, offset:
5319 * table) -> number
5320 *
5321 * @par JSON-RPC request example
5322 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackCreatItem","params":[0,2,
5323 * {0.0,0.0,0.0,0.0,0.0,0.0}],"id":1}
5324 *
5325 * @par JSON-RPC response example
5326 * {"id":1,"jsonrpc":"2.0","result":0.0}
5327 * \endenglish
5328 */
5329 int conveyorTrackCreatItem(int encoder_id, int item_id,
5330 const std::vector<double> &offset);
5331 /**
5332 * @ingroup MotionControl
5333 * \chinese
5334 * 设置传送带跟踪的补偿值
5335 *
5336 * @param encoder_id 预留
5337 * @param comp 传送带补偿值
5338 * @return
5339 *
5340 * @throws arcs::common_interface::AuboException
5341 *
5342 * @par Python函数原型
5343 * setConveyorTrackCompensate(self: pyaubo_sdk.MotionControl, arg0: int,
5344 * arg1: float) -> int
5345 *
5346 * @par Lua函数原型
5347 * setConveyorTrackCompensate(comp: number) -> number
5348 *
5349 * @par JSON-RPC请求示例
5350 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackCompensate","params":[0,
5351 * 0.1],"id":1}
5352 *
5353 * @par JSON-RPC响应示例
5354 * {"id":1,"jsonrpc":"2.0","result":0}
5355 * \endchinese
5356 * \english
5357 * Set the compensation value for conveyor tracking
5358 *
5359 * @param encoder_id Reserved
5360 * @param comp Conveyor compensation value
5361 * @return
5362 *
5363 * @throws arcs::common_interface::AuboException
5364 *
5365 * @par Python function prototype
5366 * setConveyorTrackCompensate(self: pyaubo_sdk.MotionControl, arg0: int,
5367 * arg1: float) -> int
5368 *
5369 * @par Lua function prototype
5370 * setConveyorTrackCompensate(comp: number) -> number
5371 *
5372 * @par JSON-RPC request example
5373 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackCompensate","params":[0,
5374 * 0.1],"id":1}
5375 *
5376 * @par JSON-RPC response example
5377 * {"id":1,"jsonrpc":"2.0","result":0}
5378 * \endenglish
5379 */
5380 int setConveyorTrackCompensate(int encoder_id, double comp);
5381
5382 /**
5383 * @ingroup MotionControl
5384 * \chinese
5385 * 判断传送带与机械臂之间是否达到相对静止
5386 *
5387 * @param encoder_id 预留
5388 * @return
5389 *
5390 * @throws arcs::common_interface::AuboException
5391 *
5392 * @par Python函数原型
5393 * isConveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5394 *
5395 * @par Lua函数原型
5396 * isConveyorTrackSync(encoder_id: number) -> bool
5397 *
5398 * @par JSON-RPC请求示例
5399 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackSync","params":[0],"id":1}
5400 *
5401 * @par JSON-RPC响应示例
5402 * {"id":1,"jsonrpc":"2.0","result":false}
5403 *
5404 * \endchinese
5405 * \english
5406 * Determine whether the conveyor and the robot arm have reached relative
5407 * rest
5408 *
5409 * @param encoder_id Reserved
5410 * @return
5411 *
5412 * @throws arcs::common_interface::AuboException
5413 *
5414 * @par Python function prototype
5415 * isConveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5416 *
5417 * @par Lua function prototype
5418 * isConveyorTrackSync(encoder_id: number) -> bool
5419 *
5420 * @par JSON-RPC request example
5421 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackSync","params":[0],"id":1}
5422 *
5423 * @par JSON-RPC response example
5424 * {"id":1,"jsonrpc":"2.0","result":false}
5425 *
5426 * \endenglish
5427 */
5428 bool isConveyorTrackSync(int encoder_id);
5429
5430 /**
5431 * @ingroup MotionControl
5432 * \chinese
5433 * 设置传送带跟踪的最大距离限制
5434 *
5435 * @param encoder_id 预留
5436 * @param limit
5437 * 传送带跟踪的最大距离限制,单位:米
5438 * @return
5439 *
5440 * @throws arcs::common_interface::AuboException
5441 *
5442 * @par Python函数原型
5443 * setConveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
5444 * double) -> int
5445 *
5446 * @par Lua函数原型
5447 * setConveyorTrackLimit(encoder_id: number, limit: number) -> int
5448 *
5449 * @par JSON-RPC请求示例
5450 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackLimit","params":[0,
5451 * 1.5],"id":1}
5452 *
5453 * @par JSON-RPC响应示例
5454 * {"id":1,"jsonrpc":"2.0","result":0}
5455 * \endchinese
5456 * \english
5457 * Set the maximum distance limit for conveyor tracking
5458 *
5459 * @param encoder_id Reserved
5460 * @param limit
5461 * Maximum distance limit for conveyor tracking, unit: meter
5462 * @return
5463 *
5464 * @throws arcs::common_interface::AuboException
5465 *
5466 * @par Python function prototype
5467 * setConveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
5468 * double) -> int
5469 *
5470 * @par Lua function prototype
5471 * setConveyorTrackLimit(encoder_id: number, limit: number) -> int
5472 *
5473 * @par JSON-RPC request example
5474 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackLimit","params":[0,
5475 * 1.5],"id":1}
5476 *
5477 * @par JSON-RPC response example
5478 * {"id":1,"jsonrpc":"2.0","result":0}
5479 * \endenglish
5480 */
5481 int setConveyorTrackLimit(int encoder_id, double limit);
5482
5483 /**
5484 * @ingroup MotionControl
5485 * \chinese
5486 * 设置传送带跟踪的启动窗口
5487 *
5488 * @param encoder_id 预留
5489 * @param min_window
5490 * 启动窗口的起始位置,单位:米
5491 * @param max_window
5492 * 启动窗口的结束位置,单位:米
5493 * @return
5494 *
5495 * @throws arcs::common_interface::AuboException
5496 *
5497 * @par Python函数原型
5498 * setConveyorTrackStartWindow(self: pyaubo_sdk.MotionControl, arg0: int,
5499 * arg1: double, arg2: double) -> int
5500 *
5501 * @par Lua函数原型
5502 * setConveyorTrackStartWindow(encoder_id: number, min_window: number,
5503 * max_window: number) -> int
5504 *
5505 * @par JSON-RPC请求示例
5506 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackStartWindow","params":[0,
5507 * 0.2, 1.0],"id":1}
5508 *
5509 * @par JSON-RPC响应示例
5510 * {"id":1,"jsonrpc":"2.0","result":0}
5511 *
5512 * \endchinese
5513 * \english
5514 * Set the start window for conveyor tracking
5515 *
5516 * @param encoder_id Reserved
5517 * @param min_window
5518 * Start position of the window, unit: meter
5519 * @param max_window
5520 * End position of the window, unit: meter
5521 * @return
5522 *
5523 * @throws arcs::common_interface::AuboException
5524 *
5525 * @par Python function prototype
5526 * setConveyorTrackStartWindow(self: pyaubo_sdk.MotionControl, arg0: int,
5527 * arg1: double, arg2: double) -> int
5528 *
5529 * @par Lua function prototype
5530 * setConveyorTrackStartWindow(encoder_id: number, min_window: number,
5531 * max_window: number) -> int
5532 *
5533 * @par JSON-RPC request example
5534 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackStartWindow","params":[0,
5535 * 0.2, 1.0],"id":1}
5536 *
5537 * @par JSON-RPC response example
5538 * {"id":1,"jsonrpc":"2.0","result":0}
5539 *
5540 * \endenglish
5541 */
5542 int setConveyorTrackStartWindow(int encoder_id, double window_min,
5543 double window_max);
5544
5545 /**
5546 * @ingroup MotionControl
5547 * \chinese
5548 * 设置传送带示教位置到同步开关之间的距离
5549 *
5550 * @param encoder_id 预留
5551 * @param offset
5552 * 传送带示教位置到同步开关之间的距离,单位:米
5553 * @return
5554 *
5555 * @throws arcs::common_interface::AuboException
5556 *
5557 * @par Python函数原型
5558 * setConveyorTrackSensorOffset(self: pyaubo_sdk.MotionControl, arg0: int,
5559 * arg1: double) -> int
5560 *
5561 * @par Lua函数原型
5562 * setConveyorTrackSensorOffset(encoder_id: number, offset: number) -> int
5563 *
5564 * @par JSON-RPC请求示例
5565 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSensorOffset","params":[0,
5566 * 0.2],"id":1}
5567 *
5568 * @par JSON-RPC响应示例
5569 * {"id":1,"jsonrpc":"2.0","result":0}
5570 *
5571 * \endchinese
5572 * \english
5573 * Set the distance from the conveyor teaching position to the sync switch
5574 *
5575 * @param encoder_id Reserved
5576 * @param offset
5577 * Distance from the conveyor teaching position to the sync switch, unit:
5578 * meter
5579 * @return
5580 *
5581 * @throws arcs::common_interface::AuboException
5582 *
5583 * @par Python function prototype
5584 * setConveyorTrackSensorOffset(self: pyaubo_sdk.MotionControl, arg0: int,
5585 * arg1: double) -> int
5586 *
5587 * @par Lua function prototype
5588 * setConveyorTrackSensorOffset(encoder_id: number, offset: number) -> int
5589 *
5590 * @par JSON-RPC request example
5591 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSensorOffset","params":[0,
5592 * 0.2],"id":1}
5593 *
5594 * @par JSON-RPC response example
5595 * {"id":1,"jsonrpc":"2.0","result":0}
5596 *
5597 * \endenglish
5598 */
5599 int setConveyorTrackSensorOffset(int encoder_id, double offset);
5600
5601 /**
5602 * @ingroup MotionControl
5603 * \chinese
5604 * 设置传送带同步分离,用于过滤掉同步开关中不需要的信号
5605 *
5606 * @param encoder_id 预留
5607 * @param distance
5608 * 从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短距离,单位:米
5609 * @param time
5610 * 从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短时间,单位:秒
5611 *
5612 * distance和time设置数值大于0即为生效
5613 * 当distance与time同时设置时,优先生效distance
5614 * @return
5615 *
5616 * @throws arcs::common_interface::AuboException
5617 *
5618 * @par Python函数原型
5619 * setConveyorTrackSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int,
5620 * arg1: double, arg2: double) -> int
5621 *
5622 * @par Lua函数原型
5623 * setConveyorTrackSyncSeparation(encoder_id: number, distance: number,
5624 * time: number) -> int
5625 *
5626 * @par JSON-RPC请求示例
5627 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSyncSeparation","params":[0,
5628 * 0.05, 0.2],"id":1}
5629 *
5630 * @par JSON-RPC响应示例
5631 * {"id":1,"jsonrpc":"2.0","result":0}
5632 * \endchinese
5633 * \english
5634 * Set conveyor sync separation, used to filter out unwanted signals from
5635 * the sync switch.
5636 *
5637 * @param encoder_id Reserved
5638 * @param distance
5639 * The minimum distance to travel after a sync signal appears before
5640 * accepting a new sync signal as a valid object, unit: meter
5641 * @param time
5642 * The minimum time to elapse after a sync signal appears before accepting a
5643 * new sync signal as a valid object, unit: second
5644 *
5645 * If distance and time are both set greater than 0, the setting takes
5646 * effect. If both distance and time are set, distance takes precedence.
5647 * @return
5648 *
5649 * @throws arcs::common_interface::AuboException
5650 *
5651 * @par Python function prototype
5652 * setConveyorTrackSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int,
5653 * arg1: double, arg2: double) -> int
5654 *
5655 * @par Lua function prototype
5656 * setConveyorTrackSyncSeparation(encoder_id: number, distance: number,
5657 * time: number) -> int
5658 *
5659 * @par JSON-RPC request example
5660 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSyncSeparation","params":[0,
5661 * 0.05, 0.2],"id":1}
5662 *
5663 * @par JSON-RPC response example
5664 * {"id":1,"jsonrpc":"2.0","result":0}
5665 * \endenglish
5666 */
5667 int setConveyorTrackSyncSeparation(int encoder_id, double distance,
5668 double time);
5669
5670 /**
5671 * @ingroup MotionControl
5672 * \chinese
5673 * 设置传送带运行速度阈值,用于过滤掉编码器突变值导致的位置突变
5674 *
5675 * @param encoder_id 预留
5676 * @param threshold
5677 * 传送带运行时期望容许的最大速度(默认为0.2),单位:米/秒
5678 *
5679 *
5680 * @return
5681 *
5682 * @throws arcs::common_interface::AuboException
5683 *
5684 * @par Python函数原型
5685 * setConveyorTrackVelThreshold(self: pyaubo_sdk.MotionControl, arg0: int,
5686 * arg1: double) -> int
5687 *
5688 * @par Lua函数原型
5689 * setConveyorTrackVelThreshold(encoder_id: number, threshold: number) ->
5690 * int
5691 *
5692 * @par JSON-RPC请求示例
5693 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackVelThreshold","params":[0,
5694 * 0.2],"id":1}
5695 *
5696 * @par JSON-RPC响应示例
5697 * {"id":1,"jsonrpc":"2.0","result":0}
5698 * \endchinese
5699 * \english
5700 * Set the conveyor velocity threshold used to suppress position jumps
5701 * caused by abnormal encoder spikes.
5702 *
5703 * @param encoder_id Reserved
5704 * @param threshold
5705 * The maximum allowable conveyor speed during operation, unit:
5706 * meter/second. Default: 0.2 m/s.
5707 *
5708 * @return
5709 * 0 on success; otherwise a non-zero error code.
5710 *
5711 * @throws arcs::common_interface::AuboException
5712 *
5713 * @par Python function prototype
5714 * setConveyorTrackVelThreshold(self: pyaubo_sdk.MotionControl, arg0: int,
5715 * arg1: double) -> int
5716 *
5717 * @par Lua function prototype
5718 * setConveyorTrackVelThreshold(encoder_id: number, threshold: number) ->
5719 * int
5720 *
5721 * @par JSON-RPC request example
5722 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackVelThreshold","params":[0,
5723 * 0.2],"id":1}
5724 *
5725 * @par JSON-RPC response example
5726 * {"id":1,"jsonrpc":"2.0","result":0}
5727 * \endenglish
5728 */
5729 int setConveyorTrackVelThreshold(int encoder_id, double threshold);
5730
5731 /**
5732 * \chinese
5733 * 传送带上工件的移动距离是否超过最大限值
5734 *
5735 * @param encoder_id 预留
5736 * @return
5737 * true : 移动距离超过了最大限值
5738 * false : 移动距离没有超过了最大限值
5739 *
5740 * @throws arcs::common_interface::AuboException
5741 *
5742 * @par Python函数原型
5743 * isConveyorTrackExceed(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5744 *
5745 * @par Lua函数原型
5746 * isConveyorTrackExceed(encoder_id: number) -> bool
5747 *
5748 * @par JSON-RPC请求示例
5749 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackExceed","params":[0],"id":1}
5750 *
5751 * @par JSON-RPC响应示例
5752 * {"id":1,"jsonrpc":"2.0","result":false}
5753 * \endchinese
5754 * \english
5755 * Whether the workpiece on the conveyor has moved beyond the maximum limit
5756 *
5757 * @param encoder_id Reserved
5758 * @return
5759 * true : The movement distance exceeds the maximum limit
5760 * false : The movement distance does not exceed the maximum limit
5761 *
5762 * @throws arcs::common_interface::AuboException
5763 *
5764 * @par Python function prototype
5765 * isConveyorTrackExceed(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5766 *
5767 * @par Lua function prototype
5768 * isConveyorTrackExceed(encoder_id: number) -> bool
5769 *
5770 * @par JSON-RPC request example
5771 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackExceed","params":[0],"id":1}
5772 *
5773 * @par JSON-RPC response example
5774 * {"id":1,"jsonrpc":"2.0","result":false}
5775 * \endenglish
5776 */
5777 bool isConveyorTrackExceed(int encoder_id);
5778
5779 /**
5780 * @ingroup MotionControl
5781 * \chinese
5782 * 清空传动带队列中的所有对象
5783 *
5784 * @param encoder_id 预留
5785 * @return
5786 *
5787 * @throws arcs::common_interface::AuboException
5788 *
5789 * @par Python函数原型
5790 * conveyorTrackClearItems(self: pyaubo_sdk.MotionControl, arg0: int) -> int
5791 *
5792 * @par Lua函数原型
5793 * conveyorTrackClearItems(encoder_id: number) -> int
5794 *
5795 * @par JSON-RPC请求示例
5796 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackClearItems","params":[0],"id":1}
5797 *
5798 * @par JSON-RPC响应示例
5799 * {"id":1,"jsonrpc":"2.0","result":0}
5800 *
5801 * \endchinese
5802 * \english
5803 * Clear all items in the conveyor queue
5804 *
5805 * @param encoder_id Reserved
5806 * @return
5807 *
5808 * @throws arcs::common_interface::AuboException
5809 *
5810 * @par Python function prototype
5811 * conveyorTrackClearItems(self: pyaubo_sdk.MotionControl, arg0: int) -> int
5812 *
5813 * @par Lua function prototype
5814 * conveyorTrackClearItems(encoder_id: number) -> int
5815 *
5816 * @par JSON-RPC request example
5817 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackClearItems","params":[0],"id":1}
5818 *
5819 * @par JSON-RPC response example
5820 * {"id":1,"jsonrpc":"2.0","result":0}
5821 *
5822 * \endenglish
5823 */
5824 int conveyorTrackClearItems(int encoder_id);
5825
5826 /**
5827 * @ingroup MotionControl
5828 * \chinese
5829 * 获取传送带队列的编码器值
5830 *
5831 * @param encoder_id 预留
5832 * @return
5833 *
5834 * @throws arcs::common_interface::AuboException
5835 *
5836 * @par Python函数原型
5837 * getConveyorTrackQueue(self: pyaubo_sdk.MotionControl, arg0: int) ->
5838 * List[int]
5839 * @par Lua函数原型
5840 * getConveyorTrackQueue(encoder_id: number) -> table
5841 *
5842 * @par JSON-RPC请求示例
5843 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackQueue","params":[0],"id":1}
5844 *
5845 * @par JSON-RPC响应示例
5846 * {"id":1,"jsonrpc":"2.0","result":{[-500,-200,150,-50]}}
5847 * \endchinese
5848 * \english
5849 * Get encoder values of the conveyor queue
5850 *
5851 * @param encoder_id Reserved
5852 * @return
5853 *
5854 * @throws arcs::common_interface::AuboException
5855 *
5856 * @par Python function prototype
5857 * getConveyorTrackQueue(self: pyaubo_sdk.MotionControl, arg0: int) ->
5858 * List[int]
5859 * @par Lua function prototype
5860 * getConveyorTrackQueue(encoder_id: number) -> table
5861 *
5862 * @par JSON-RPC request example
5863 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackQueue","params":[0],"id":1}
5864 *
5865 * @par JSON-RPC response example
5866 * {"id":1,"jsonrpc":"2.0","result":{[-500,-200,150,-50]}}
5867 * \endenglish
5868 */
5869 std::vector<int> getConveyorTrackQueue(int encoder_id);
5870 /**
5871 * \chinese
5872 * 获取下一个跟踪的传送带物品的id
5873 *
5874 * @param encoder_id 预留
5875 * @return
5876 * 返回物品id,没有next item返回 -1
5877 *
5878 * @throws arcs::common_interface::AuboException
5879 *
5880 * @par Python函数原型
5881 * getConveyorTrackNextItem(self: pyaubo_sdk.MotionControl, arg0: int) ->
5882 * int
5883 * @par Lua函数原型
5884 * getConveyorTrackNextItem(encoder_id: number) -> int
5885 *
5886 * @par JSON-RPC请求示例
5887 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackNextItem","params":[0],"id":1}
5888 *
5889 * @par JSON-RPC响应示例
5890 * {"id":1,"jsonrpc":"2.0","result":{10}}
5891 * \endchinese
5892 * \english
5893 * Get the ID of the next item on the conveyor to be tracked
5894 *
5895 * @param encoder_id Reserved
5896 * @return
5897 * Returns the item ID; returns -1 if there is no next item
5898 *
5899 * @throws arcs::common_interface::AuboException
5900 *
5901 * @par Python function prototype
5902 * getConveyorTrackNextItem(self: pyaubo_sdk.MotionControl, arg0: int) ->
5903 * int
5904 * @par Lua function prototype
5905 * getConveyorTrackNextItem(encoder_id: number) -> int
5906 *
5907 * @par JSON-RPC Request Example
5908 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackNextItem","params":[0],"id":1}
5909 *
5910 * @par JSON-RPC Response Example
5911 * {"id":1,"jsonrpc":"2.0","result":{10}}
5912 * \endenglish
5913 */
5914
5915 int getConveyorTrackNextItem(int encoder_id);
5916
5917 /**
5918 * @ingroup MotionControl
5919 * \chinese
5920 * 螺旋线运动
5921 *
5922 * @param param 封装的参数
5923 * @param blend_radius
5924 * @param v
5925 * @param a
5926 * @param t
5927 * @return 成功返回0;失败返回错误码
5928 * AUBO_BUSY
5929 * AUBO_BAD_STATE
5930 * -AUBO_INVL_ARGUMENT
5931 * -AUBO_BAD_STATE
5932 *
5933 * @throws arcs::common_interface::AuboException
5934 *
5935 * @par JSON-RPC请求示例
5936 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
5937 * "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}
5938 *
5939 * @par JSON-RPC响应示例
5940 * {"id":1,"jsonrpc":"2.0","result":0}
5941 * \endchinese
5942 * \english
5943 * Spiral motion
5944 *
5945 * @param param Encapsulated parameters
5946 * @param blend_radius
5947 * @param v
5948 * @param a
5949 * @param t
5950 * @return Returns 0 on success; otherwise returns an error code
5951 * AUBO_BUSY
5952 * AUBO_BAD_STATE
5953 * -AUBO_INVL_ARGUMENT
5954 * -AUBO_BAD_STATE
5955 *
5956 * @throws arcs::common_interface::AuboException
5957 *
5958 * @par JSON-RPC request example
5959 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
5960 * "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}
5961 *
5962 * @par JSON-RPC response example
5963 * {"id":1,"jsonrpc":"2.0","result":0}
5964 * \endenglish
5965 */
5966 int moveSpiral(const SpiralParameters &param, double blend_radius, double v,
5967 double a, double t);
5968
5969 /**
5970 * @ingroup MotionControl
5971 * \chinese
5972 * 获取前瞻段数
5973 *
5974 * @return 返回前瞻段数
5975 *
5976 * @throws arcs::common_interface::AuboException
5977 *
5978 * @par Python函数原型
5979 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
5980 *
5981 * @par Lua函数原型
5982 * getLookAheadSize() -> number
5983 *
5984 * @par JSON-RPC请求示例
5985 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
5986 *
5987 * @par JSON-RPC响应示例
5988 * {"id":1,"jsonrpc":"2.0","result":1}
5989 *
5990 * \endchinese
5991 * \english
5992 * Get look-ahead segment size
5993 *
5994 * @return Returns the look-ahead segment size
5995 *
5996 * @throws arcs::common_interface::AuboException
5997 *
5998 * @par Python function prototype
5999 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
6000 *
6001 * @par Lua function prototype
6002 * getLookAheadSize() -> number
6003 *
6004 * @par JSON-RPC request example
6005 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
6006 *
6007 * @par JSON-RPC response example
6008 * {"id":1,"jsonrpc":"2.0","result":1}
6009 *
6010 * \endenglish
6011 */
6013
6014 /**
6015 * @ingroup MotionControl
6016 * \chinese
6017 * 设置前瞻段数
6018 * 1.对于有较高速度平稳性要求的任务,如数控加工,涂胶,焊接等匀速需求,较长的前瞻段数可以提供更优的速度规划,产生的运动会更加平滑;
6019 * 2.对于快速响应的抓取类任务,更倾向于较短的前瞻段数,以提高反应速度,但可能因为进给的路径不够及时导致速度波动很大.
6020 *
6021 * @return 成功返回0
6022 *
6023 * @throws arcs::common_interface::AuboException
6024 *
6025 * @par Python函数原型
6026 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
6027 *
6028 * @par Lua函数原型
6029 * setLookAheadSize(eqradius: number) -> number
6030 *
6031 * @par JSON-RPC请求示例
6032 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
6033 *
6034 * @par JSON-RPC响应示例
6035 * {"id":1,"jsonrpc":"2.0","result":0}
6036 * \endchinese
6037 * \english
6038 * Set look-ahead segment size
6039 * 1. For tasks requiring high speed smoothness, such as CNC machining,
6040 * gluing, welding, etc., a longer look-ahead segment size can provide
6041 * better speed planning and smoother motion.
6042 * 2. For fast-response tasks such as picking, a shorter look-ahead segment
6043 * size is preferred to improve response speed, but may cause large speed
6044 * fluctuations due to insufficiently timely path feeding.
6045 *
6046 * @return Returns 0 on success
6047 *
6048 * @throws arcs::common_interface::AuboException
6049 *
6050 * @par Python function prototype
6051 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
6052 *
6053 * @par Lua function prototype
6054 * setLookAheadSize(eqradius: number) -> number
6055 *
6056 * @par JSON-RPC request example
6057 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
6058 *
6059 * @par JSON-RPC response example
6060 * {"id":1,"jsonrpc":"2.0","result":0}
6061 * \endenglish
6062 */
6063 int setLookAheadSize(int size);
6064
6065 /**
6066 * @ingroup MotionControl
6067 * \chinese
6068 * 更新摆动过程中的频率和振幅
6069 *
6070 * @param params Json字符串用于定义摆动参数
6071 * {
6072 * "frequency": <num>,
6073 * "amplitude": {<num>,<num>}
6074 * }
6075 *
6076 * @return 成功返回0
6077 *
6078 * @throws arcs::common_interface::AuboException
6079 * \endchinese
6080 * \english
6081 * Update frequency and amplitude during weaving process
6082 *
6083 * @param params Json string used to define weaving parameters
6084 * {
6085 * "frequency": <num>,
6086 * "amplitude": {<num>,<num>}
6087 * }
6088 *
6089 * @return Returns 0 on success
6090 *
6091 * @throws arcs::common_interface::AuboException
6092 * \endenglish
6093 */
6094 int weaveUpdateParameters(const std::string &params);
6095
6096 /**
6097 * @ingroup MotionControl
6098 * \chinese
6099 * 设置关节电流环刚度系数
6100 *
6101 * @param stiffness 各个关节刚度系数,百分比。[0 -> 1],值越大,表现为越硬。
6102 * @return
6103 *
6104 * @throws arcs::common_interface::AuboException
6105 *
6106 * @par Python函数原型
6107 * enableJointSoftServo(self: pyaubo_sdk.RobotConfig, arg0: List[float]) ->
6108 * int
6109 *
6110 * @par Lua函数原型
6111 * enableJointSoftServo(stiffness: table) -> int
6112 *
6113 * @par JSON-RPC请求示例
6114 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.enableJointSoftServo","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
6115 *
6116 * @par JSON-RPC响应示例
6117 * {"id":1,"jsonrpc":"2.0","result":0}
6118 * \endchinese
6119 * \english
6120 * Set joint current loop stiffness coefficient
6121 *
6122 * @param stiffness Stiffness coefficient for each joint, as a percentage [0
6123 * -> 1]. The larger the value, the stiffer the joint.
6124 * @return
6125 *
6126 * @throws arcs::common_interface::AuboException
6127 *
6128 * @par Python function prototype
6129 * enableJointSoftServo(self: pyaubo_sdk.RobotConfig, arg0: List[float]) ->
6130 * int
6131 *
6132 * @par Lua function prototype
6133 * enableJointSoftServo(stiffness: table) -> int
6134 *
6135 * @par JSON-RPC request example
6136 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.enableJointSoftServo","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
6137 *
6138 * @par JSON-RPC response example
6139 * {"id":1,"jsonrpc":"2.0","result":0}
6140 * \endenglish
6141 */
6142 int enableJointSoftServo(const std::vector<double> &stiffness);
6143
6144 /**
6145 * @ingroup MotionControl
6146 * \chinese
6147 * 关闭关节电流环刚度系数
6148 *
6149 * @return 返回0表示成功,其他为错误码
6150 *
6151 * @throws arcs::common_interface::AuboException
6152 *
6153 * @par Python函数原型
6154 * disableJointSoftServo(self: pyaubo_sdk.MotionControl) -> int
6155 *
6156 * @par Lua函数原型
6157 * disableJointSoftServo() -> number
6158 *
6159 * @par JSON-RPC请求示例
6160 * {"jsonrpc":"2.0","method":"rob1.MotionControl.disableJointSoftServo","params":[],"id":1}
6161 *
6162 * @par JSON-RPC响应示例
6163 * {"id":1,"jsonrpc":"2.0","result":1}
6164 * \endchinese
6165 * \english
6166 * Disable joint current loop stiffness coefficient
6167 *
6168 * @return Returns 0 on success, otherwise error code
6169 *
6170 * @throws arcs::common_interface::AuboException
6171 *
6172 * @par Python function prototype
6173 * disableJointSoftServo(self: pyaubo_sdk.MotionControl) -> int
6174 *
6175 * @par Lua function prototype
6176 * disableJointSoftServo() -> number
6177 *
6178 * @par JSON-RPC request example
6179 * {"jsonrpc":"2.0","method":"rob1.MotionControl.disableJointSoftServo","params":[],"id":1}
6180 *
6181 * @par JSON-RPC response example
6182 * {"id":1,"jsonrpc":"2.0","result":1}
6183 * \endenglish
6184 */
6186
6187 /**
6188 * @ingroup MotionControl
6189 * \chinese
6190 * 判断关节电流环刚度系数是否使能
6191 *
6192 * @return 已使能返回true,反之则返回false
6193 *
6194 * @throws arcs::common_interface::AuboException
6195 *
6196 * @par Python函数原型
6197 * isJointSoftServoEnabled(self: pyaubo_sdk.MotionControl) -> bool
6198 *
6199 * @par Lua函数原型
6200 * isJointSoftServoEnabled() -> boolean
6201 *
6202 * @par JSON-RPC请求示例
6203 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isJointSoftServoEnabled","params":[],"id":1}
6204 *
6205 * @par JSON-RPC响应示例
6206 * {"id":1,"jsonrpc":"2.0","result":1}
6207 * \endchinese
6208 * \english
6209 * Determine whether the joint current loop stiffness coefficient is
6210 * enabled.
6211 *
6212 * @return Returns true if enabled, otherwise returns false.
6213 *
6214 * @throws arcs::common_interface::AuboException
6215 *
6216 * @par Python function prototype
6217 * isJointSoftServoEnabled(self: pyaubo_sdk.MotionControl) -> bool
6218 *
6219 * @par Lua function prototype
6220 * isJointSoftServoEnabled() -> boolean
6221 *
6222 * @par JSON-RPC request example
6223 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isJointSoftServoEnabled","params":[],"id":1}
6224 *
6225 * @par JSON-RPC response example
6226 * {"id":1,"jsonrpc":"2.0","result":1}
6227 * \endenglish
6228 */
6230
6231 /**
6232 * @ingroup MotionControl
6233 * \chinese
6234 * 打开振动抑制
6235 *
6236 * @param omega 振动抑制频率,长度一般为笛卡尔维度或关节自由度.为0时关闭抑制
6237 * \n
6238 * @param zeta 振动抑制阻尼比,长度一般为笛卡尔维度或关节自由度.为0时关闭抑制
6239 * \n
6240 * @param level
6241 * 振动抑制等级(1~3),等级越高抑制效果越明显响应速度相应变慢.等级0关闭振动抑制
6242 * \n
6243 * @retval 0 成功
6244 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
6245 * Normal、ReducedMode、Recovery 状态
6246 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
6247 * @retval AUBO_BUSY(3) 上一条指令正在执行中
6248 * @retval -AUBO_BAD_STATE(-1)
6249 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
6250 * 未找到,或者当前机器人模式非 Running
6251 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
6252 *
6253 * @throws arcs::common_interface::AuboException
6254 *
6255 * @par Python函数原型
6256 * enableVibrationSuppress(self: pyaubo_sdk.MotionControl, arg0:
6257 * list[float], arg1: list[float], arg2: int) -> int
6258 *
6259 * @par Lua函数原型
6260 * enableVibrationSuppress(omega: table, zeta: table, level: number) -> nil
6261 *
6262 * @par JSON-RPC请求示例
6263 * {"jsonrpc":"2.0","method":"rob1.MotionControl.enableVibrationSuppress","params":[[0.5,0.5,0.5,0.5,0.5,0.5],[0.5,0.5,0.5,0.5,0.5,0.5],2],"id":1}
6264 *
6265 * @par JSON-RPC响应示例
6266 * {"id":1,"jsonrpc":"2.0","result":0}
6267 *
6268 * \endchinese
6269 */
6270 int enableVibrationSuppress(const std::vector<double> &omega,
6271 const std::vector<double> &zeta, int level);
6272 /**
6273 * @ingroup MotionControl
6274 * \chinese
6275 * 关闭振动抑制
6276 *
6277 * @return 已使能返回true,反之则返回false
6278 *
6279 * @throws arcs::common_interface::AuboException
6280 *
6281 * @par Python函数原型
6282 * disbaleVibrationSuppress(self: pyaubo_sdk.MotionControl) -> int
6283 *
6284 * @par Lua函数原型
6285 * disbaleVibrationSuppress() -> number
6286 *
6287 * @par JSON-RPC请求示例
6288 * {"jsonrpc":"2.0","method":"rob1.MotionControl.disbaleVibrationSuppress","params":[],"id":1}
6289 *
6290 * @par JSON-RPC响应示例
6291 * {"id":1,"jsonrpc":"2.0","result":1}
6292 * \endchinese
6293 */
6295
6296 /**
6297 * @ingroup MotionControl
6298 * \chinese
6299 * 设置时间最优算法 默认关闭
6300 *
6301 * @param enable
6302 *
6303 * @throws arcs::common_interface::AuboException
6304 *
6305 * @par Lua函数原型
6306 * setTimeOptimalEnable() -> bool
6307 *
6308 * @par Lua示例
6309 * setTimeOptimalEnable(true)
6310 *
6311 * @par JSON-RPC请求示例
6312 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setTimeOptimalEnable","params":[true],"id":1}
6313 *
6314 * @par JSON-RPC响应示例
6315 * {"id":1,"jsonrpc":"2.0","result":0}
6316 * \endchinese
6317 * \english
6318 *
6319 * @param enable
6320 *
6321 * @throws arcs::common_interface::AuboException
6322 *
6323 * @par Lua function prototype
6324 * setTimeOptimalEnable() -> number
6325 *
6326 * @par Lua example
6327 * setTimeOptimalEnable(true)
6328 *
6329 * @par JSON-RPC request example
6330 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setTimeOptimalEnable","params":[true],"id":1}
6331 *
6332 * @par JSON-RPC response example
6333 * {"id":1,"jsonrpc":"2.0","result":0}
6334 * \endenglish
6335 */
6336 int setTimeOptimalEnable(bool enable);
6337
6338 /**
6339 * @ingroup MotionControl
6340 * \chinese
6341 * 获取时间最优算法状态:
6342 * true - 开启
6343 * false - 关闭
6344 *
6345 * @return 返回时间最优算法状态
6346 *
6347 * @throws arcs::common_interface::AuboException
6348 *
6349 * @par Python函数原型
6350 * isTimeOptimalEnabled(self: pyaubo_sdk.MotionControl) -> float
6351 *
6352 * @par Lua函数原型
6353 * isTimeOptimalEnabled() -> number
6354 *
6355 * @par Lua 示例
6356 * num = isTimeOptimalEnabled()
6357 *
6358 * @par JSON-RPC请求示例
6359 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isTimeOptimalEnabled","params":[],"id":1}
6360 *
6361 * @par JSON-RPC响应示例
6362 * {"id":1,"jsonrpc":"2.0","result":1.0}
6363 * \endchinese
6364 * \english
6365 * Get the time optimal algorithm state:
6366 * true - enable
6367 * false - disable
6368 *
6369 * @return Returns the time optimal algorithm state
6370 *
6371 * @throws arcs::common_interface::AuboException
6372 *
6373 * @par Python function prototype
6374 * isTimeOptimalEnabled(self: pyaubo_sdk.MotionControl) -> bool
6375 *
6376 * @par Lua function prototype
6377 * isTimeOptimalEnabled() -> boolean
6378 *
6379 * @par Lua example
6380 * flag = isTimeOptimalEnabled()
6381 *
6382 * @par JSON-RPC request example
6383 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isTimeOptimalEnabled","params":[],"id":1}
6384 *
6385 * @par JSON-RPC response example
6386 * {"id":1,"jsonrpc":"2.0","result":true}
6387 * \endenglish
6388 */
6390
6391 /**
6392 * @ingroup MotionControl
6393 * \chinese
6394 * 获取是否支持时间最优算法:
6395 * true - 支持
6396 * false - 不支持
6397 *
6398 * @return 返回是否支持时间最优算法
6399 *
6400 * @throws arcs::common_interface::AuboException
6401 *
6402 * @par Python函数原型
6403 * isTimeOptimalEnabled(self: pyaubo_sdk.MotionControl) -> bool
6404 *
6405 * @par Lua函数原型
6406 * isSupportedTimeOptimal() -> boolean
6407 *
6408 * @par Lua 示例
6409 * num = isSupportedTimeOptimal()
6410 *
6411 * @par JSON-RPC请求示例
6412 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isSupportedTimeOptimal","params":[],"id":1}
6413 *
6414 * @par JSON-RPC响应示例
6415 * {"id":1,"jsonrpc":"2.0","result":1.0}
6416 * \endchinese
6417 * \english
6418 * Check whether the time optimal algorithm is supported
6419 * true - supported
6420 * false - not supported
6421 *
6422 * @return Return whether the time-optimal algorithm is supported
6423 *
6424 * @throws arcs::common_interface::AuboException
6425 *
6426 * @par Python function prototype
6427 * isSupportedTimeOptimal(self: pyaubo_sdk.MotionControl) -> bool
6428 *
6429 * @par Lua function prototype
6430 * isSupportedTimeOptimal() -> boolean
6431 *
6432 * @par Lua example
6433 * flag = isSupportedTimeOptimal()
6434 *
6435 * @par JSON-RPC request example
6436 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isSupportedTimeOptimal","params":[],"id":1}
6437 *
6438 * @par JSON-RPC response example
6439 * {"id":1,"jsonrpc":"2.0","result":true}
6440 * \endenglish
6441 */
6443
6444 /**
6445 * @ingroup MotionControl
6446 * \chinese
6447 * 设置TCP最大线速度
6448 *
6449 * @param v TCP最大线速度值,单位为m/s(米/秒)
6450 *
6451 * @throws arcs::common_interface::AuboException
6452 *
6453 * @par Lua函数原型
6454 * setTcpMaxLinearVelocity(number) -> number
6455 *
6456 * @par Lua示例
6457 * setTcpMaxLinearVelocity(0.5) -- 设置TCP最大线速度为0.5米/秒
6458 *
6459 * @par Python函数原型
6460 * setTcpMaxLinearVelocity(v: float) -> int
6461 *
6462 * @par Python示例
6463 * setTcpMaxLinearVelocity(0.5) -- 设置TCP最大线速度为0.5米/秒
6464 *
6465 * @par JSON-RPC请求示例
6466 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setTcpMaxLinearVelocity","params":[0.5],"id":1}
6467 *
6468 * @par JSON-RPC响应示例
6469 * {"id":1,"jsonrpc":"2.0","result":0}
6470 * \endchinese
6471 * \english
6472 * Set TCP maximum linear velocity
6473 *
6474 * @param v TCP maximum linear velocity value, unit is m/s
6475 *
6476 * @throws arcs::common_interface::AuboException
6477 *
6478 * @par Lua function prototype
6479 * setTcpMaxLinearVelocity(number) -> number
6480 *
6481 * @par Lua example
6482 * setTcpMaxLinearVelocity(0.5) -- Set TCP maximum linear velocity to 0.5
6483 * meters per second
6484 *
6485 * @par Python function prototype
6486 * setTcpMaxLinearVelocity(v: float) -> int
6487 *
6488 * @par Python example
6489 * setTcpMaxLinearVelocity(0.5) -- Set TCP maximum linear velocity to 0.5
6490 *
6491 * @par JSON-RPC request example
6492 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setTcpMaxLinearVelocity","params":[0.5],"id":1}
6493 *
6494 * @par JSON-RPC response example
6495 * {"id":1,"jsonrpc":"2.0","result":0}
6496 * \endenglish
6497 */
6499
6500 /**
6501 * @ingroup MotionControl
6502 * \chinese
6503 * 获取TCP最大线速度
6504 *
6505 * @return 当前TCP最大线速度值,单位为m/s(米/秒)
6506 *
6507 * @throws arcs::common_interface::AuboException
6508 *
6509 * @par Lua函数原型
6510 * getTcpMaxLinearVelocity() -> number
6511 *
6512 * @par Lua示例
6513 * local v = getTcpMaxLinearVelocity() -- 获取TCP最大线速度
6514 *
6515 * @par Python函数原型
6516 * getTcpMaxLinearVelocity() -> float
6517 *
6518 * @par Python示例
6519 * v = getTcpMaxLinearVelocity() # 获取TCP最大线速度
6520 *
6521 * @par JSON-RPC请求示例
6522 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getTcpMaxLinearVelocity","params":[],"id":1}
6523 *
6524 * @par JSON-RPC响应示例
6525 * {"id":1,"jsonrpc":"2.0","result":0.5}
6526 * \endchinese
6527 * \english
6528 * Get TCP maximum linear velocity
6529 *
6530 * @return Current TCP maximum linear velocity value, unit is m/s
6531 *
6532 * @throws arcs::common_interface::AuboException
6533 *
6534 * @par Lua function prototype
6535 * getTcpMaxLinearVelocity() -> number
6536 *
6537 * @par Lua example
6538 * local v = getTcpMaxLinearVelocity() -- Get TCP maximum linear velocity
6539 *
6540 * @par Python function prototype
6541 * getTcpMaxLinearVelocity() -> float
6542 *
6543 * @par Python example
6544 * v = getTcpMaxLinearVelocity() # Get TCP maximum linear velocity
6545 *
6546 * @par JSON-RPC request example
6547 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getTcpMaxLinearVelocity","params":[],"id":1}
6548 *
6549 * @par JSON-RPC response example
6550 * {"id":1,"jsonrpc":"2.0","result":0.5}
6551 * \endenglish
6552 */
6554
6555 /**
6556 * @ingroup MotionControl
6557 * \chinese
6558 * 重置 TCP 最大线速度
6559 *
6560 * 清除通过 setTcpMaxLinearVelocity 接口设置的 TCP 最大线速度覆盖值
6561 *
6562 * @return 成功返回 0;失败返回错误码
6563 *
6564 * @throws arcs::common_interface::AuboException
6565 *
6566 * @par Lua函数原型
6567 * resetTcpMaxLinearVelocity() -> number
6568 *
6569 * @par Lua示例
6570 * resetTcpMaxLinearVelocity() -- 重置 TCP 最大线速度为安全配置中的值
6571 *
6572 * @par Python函数原型
6573 * resetTcpMaxLinearVelocity() -> int
6574 *
6575 * @par Python示例
6576 * resetTcpMaxLinearVelocity() -- 重置 TCP 最大线速度为安全配置中的值
6577 *
6578 * @par JSON-RPC请求示例
6579 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resetTcpMaxLinearVelocity","params":[],"id":1}
6580 *
6581 * @par JSON-RPC响应示例
6582 * {"id":1,"jsonrpc":"2.0","result":0}
6583 * \endchinese
6584 *
6585 * \english
6586 * Reset TCP maximum linear velocity
6587 *
6588 * Clear the TCP maximum linear velocity override set by
6589 * setTcpMaxLinearVelocity
6590 *
6591 * @return Returns 0 on success; error code on failure.
6592 *
6593 * @throws arcs::common_interface::AuboException
6594 *
6595 * @par Lua function prototype
6596 * resetTcpMaxLinearVelocity() -> number
6597 *
6598 * @par Lua example
6599 * resetTcpMaxLinearVelocity() -- Reset TCP maximum linear velocity to
6600 * the value in the safety configuration
6601 *
6602 * @par Python function prototype
6603 * resetTcpMaxLinearVelocity() -> int
6604 *
6605 * @par Python example
6606 * resetTcpMaxLinearVelocity() -- Reset TCP maximum linear velocity
6607 *
6608 * @par JSON-RPC request example
6609 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resetTcpMaxLinearVelocity","params":[],"id":1}
6610 *
6611 * @par JSON-RPC response example
6612 * {"id":1,"jsonrpc":"2.0","result":0}
6613 * \endenglish
6614 */
6616
6617 /**
6618 * @ingroup MotionControl
6619 * \chinese
6620 * 设置轨迹终止点(以当前轨迹段为界)
6621 *
6622 * 显式指定以当前正在执行的轨迹段为边界,终止后续轨迹段的交融(blending)。
6623 * 当前轨迹段将完整执行完毕,但不会与后续轨迹进行速度或位置上的平滑过渡,
6624 * 后续轨迹段将被视为新的独立轨迹起点。
6625 *
6626 * 该接口不会触发急停,也不会中断当前轨迹段的执行,仅影响轨迹段之间的交融行为。
6627 *
6628 * @return 成功返回 0;失败返回错误码
6629 *
6630 * @throws arcs::common_interface::AuboException
6631 *
6632 * @par Lua函数原型
6633 * setEndPath() -> number
6634 *
6635 * @par Lua示例
6636 * setEndPath() -- 以当前轨迹段为界,终止后续轨迹交融
6637 *
6638 * @par Python函数原型
6639 * setEndPath() -> int
6640 *
6641 * @par Python示例
6642 * setEndPath() # 以当前轨迹段为界,终止后续轨迹交融
6643 *
6644 * @par JSON-RPC请求示例
6645 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setEndPath","params":[],"id":1}
6646 *
6647 * @par JSON-RPC响应示例
6648 * {"id":1,"jsonrpc":"2.0","result":0}
6649 * \endchinese
6650 *
6651 * \english
6652 * Set end path (terminate blending at current trajectory segment)
6653 *
6654 * Explicitly specifies the currently executing trajectory segment as the
6655 * boundary at which trajectory blending is terminated. The current
6656 * trajectory segment will be executed completely, but no velocity or
6657 * position blending will be applied with subsequent trajectory segments.
6658 *
6659 * This interface does not trigger an emergency stop and does not interrupt
6660 * the execution of the current trajectory segment. It only affects the
6661 * blending behavior between trajectory segments.
6662 *
6663 * @return Returns 0 on success; error code on failure.
6664 *
6665 * @throws arcs::common_interface::AuboException
6666 *
6667 * @par Lua function prototype
6668 * setEndPath() -> number
6669 *
6670 * @par Lua example
6671 * setEndPath() -- Terminate trajectory blending at the current segment
6672 *
6673 * @par Python function prototype
6674 * setEndPath() -> int
6675 *
6676 * @par Python example
6677 * setEndPath() # Terminate trajectory blending at the current segment
6678 *
6679 * @par JSON-RPC request example
6680 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setEndPath","params":[],"id":1}
6681 *
6682 * @par JSON-RPC response example
6683 * {"id":1,"jsonrpc":"2.0","result":0}
6684 * \endenglish
6685 */
6687
6688 /**
6689 * @ingroup MotionControl
6690 * \chinese
6691 * 获取当前摆焊轨迹点方向
6692 *
6693 * 获取机器人当前执行轨迹点在摆焊(Weave)运动中的方向状态,
6694 * 用于指示该点位于摆焊坐标系 Y 轴的正半轴或负半轴区域。
6695 *
6696 * 当机器人正在执行摆焊轨迹时,该接口返回当前摆焊点所属的摆动方向,
6697 * 可用于判断摆焊运动处于正向摆动阶段或反向摆动阶段。
6698 *
6699 * 当机器人未执行摆焊轨迹时,该接口返回 0。
6700 *
6701 * 该接口为状态查询接口,不会影响当前轨迹执行,也不会改变机器人运动状态。
6702 *
6703 * @return 返回当前摆焊方向,对应 WeaveDirection 枚举值:
6704 * - 0 : NONE 当前未执行摆焊轨迹
6705 * - 1 : POSITIVE 当前位于摆焊坐标系 Y 轴正半轴区域
6706 * - 2 : NEGATIVE 当前位于摆焊坐标系 Y 轴负半轴区域
6707 *
6708 * @throws arcs::common_interface::AuboException
6709 *
6710 * @par Lua函数原型
6711 * getWeaveDirection() -> number
6712 *
6713 * @par Lua示例
6714 * local dir = getWeaveDirection()
6715 * if dir == 1 then
6716 * -- 正方向摆动
6717 * elseif dir == 2 then
6718 * -- 负方向摆动
6719 * end
6720 *
6721 * @par Python函数原型
6722 * getWeaveDirection() -> int
6723 *
6724 * @par Python示例
6725 * dir = getWeaveDirection()
6726 * if dir == 1:
6727 * # positive direction
6728 * pass
6729 * elif dir == 2:
6730 * # negative direction
6731 * pass
6732 *
6733 * @par JSON-RPC请求示例
6734 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getWeaveDirection","params":[],"id":1}
6735 *
6736 * @par JSON-RPC响应示例
6737 * {"id":1,"jsonrpc":"2.0","result":1}
6738 *
6739 * \endchinese
6740 *
6741 * \english
6742 * Get current weave trajectory direction
6743 *
6744 * Retrieves the directional state of the current trajectory point during
6745 * weave motion, indicating whether the point is located on the positive or
6746 * negative side of the weave coordinate system Y-axis.
6747 *
6748 * When no weave trajectory is active, this interface returns 0.
6749 *
6750 * This is a state query interface and does not affect trajectory execution
6751 * or robot motion.
6752 *
6753 * @return Returns current weave direction corresponding to WeaveDirection
6754 * enum:
6755 * - 0 : NONE No active weave trajectory
6756 * - 1 : POSITIVE Positive Y-axis side
6757 * - 2 : NEGATIVE Negative Y-axis side
6758 *
6759 * @throws arcs::common_interface::AuboException
6760 *
6761 * @par Lua function prototype
6762 * getWeaveDirection() -> number
6763 *
6764 * @par Lua example
6765 * local dir = getWeaveDirection()
6766 *
6767 * @par Python function prototype
6768 * getWeaveDirection() -> int
6769 *
6770 * @par Python example
6771 * dir = getWeaveDirection()
6772 *
6773 * @par JSON-RPC request example
6774 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getWeaveDirection","params":[],"id":1}
6775 *
6776 * @par JSON-RPC response example
6777 * {"id":1,"jsonrpc":"2.0","result":1}
6778 *
6779 * \endenglish
6780 */
6782
6783protected:
6784 void *d_;
6785};
6786using MotionControlPtr = std::shared_ptr<MotionControl>;
6787} // namespace common_interface
6788} // namespace arcs
6789
6790#endif // AUBO_SDK_MOTION_CONTROL_INTERFACE_H
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)
bool isConveyorTrackExceed(int encoder_id)
传送带上工件的移动距离是否超过最大限值
int getConveyorTrackNextItem(int encoder_id)
获取下一个跟踪的传送带物品的id
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 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 getResumeMode()
获取继续运动模式
int stopJoint(double acc)
关节空间停止运动
int conveyorTrackStop(int encoder_id, double a)
终止传送带跟随
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 setConveyorTrackLimit(int encoder_id, double limit)
设置传送带跟踪的最大距离限制
int clearPath()
ClearPath (清除路径) 清除当前运动路径层级(基础层级或 StorePath 层级)上的所有运动路径。
bool conveyorTrackSwitch(int encoder_id)
切换传送带追踪物品 如果当前物品正在处于跟踪状态,则将该物品出队,不再跟踪,返回true 如果没有物品正在处于跟踪状态,返回false
std::vector< std::vector< double > > getFuturePathPointsJoint()
获取未来路径上的轨迹点
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 setConveyorTrackVelThreshold(int encoder_id, double threshold)
设置传送带运行速度阈值,用于过滤掉编码器突变值导致的位置突变
int pathBufferAlloc(const std::string &name, int type, int size)
新建一个路径点缓存
std::vector< int > getConveyorTrackQueue(int encoder_id)
获取传送带队列的编码器值
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()
int startMove()
StartMove 用于在以下情况下恢复机器人、外部轴的运动以及相关工艺进程: • 通过 StopMove 指令停止后。 • 执行 StorePath ... RestoPath 序列后。 • 发生异步...
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)
停止 moveLine/moveCircle 等在笛卡尔空间的运动
double getTcpMaxLinearVelocity()
获取TCP最大线速度
int setConveyorTrackStartWindow(int encoder_id, double window_min, double window_max)
设置传送带跟踪的启动窗口
int resumeStopLine(double acc, double acc_rot)
笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
std::tuple< std::string, std::vector< double > > 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 resetTcpMaxLinearVelocity()
重置 TCP 最大线速度
int stopMove(bool quick, bool all_tasks)
StopMove 用于临时停止机器人和外部轴的运动以及相关工艺进程。如果调用 StartMove 指令,则运动和工艺进程将恢复。
int speedFractionCritical1(bool enable)
速度比例设置临界区,使能之后速度比例被强制设定为当前生效的比例, 失能之后恢复之前的速度比例
int conveyorTrackCreatItem(int encoder_id, int item_id, const std::vector< double > &offset)
增加传送带队列
int jointOffsetEnable()
关节偏移使能
ARCS_DEPRECATED bool isServoModeEnabled()
判断伺服模式是否使能 使用 getServoModeSelect 替代
int pathOffsetDisable()
路径偏移失能
int setConveyorTrackSyncSeparation(int encoder_id, double distance, double time)
设置传送带同步分离,用于过滤掉同步开关中不需要的信号
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 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 enableJointSoftServo(const std::vector< double > &stiffness)
设置关节电流环刚度系数
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 disableJointSoftServo()
关闭关节电流环刚度系数
int moveProcess(const std::vector< double > &pose, double a, double v, double blend_radius)
添加工艺运动
int getWeaveDirection()
获取当前摆焊轨迹点方向
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 setEndPath()
设置轨迹终止点(以当前轨迹段为界)
int setCirclePathMode(int mode)
设置圆弧路径模式
int setTcpMaxLinearVelocity(double v)
设置TCP最大线速度
int setTimeOptimalEnable(bool enable)
设置时间最优算法 默认关闭
int setServoModeSelect(int mode)
设置伺服运动模式
int setConveyorTrackEncoder(int encoder_id, int tick_per_meter)
设置传送带编码器参数
int setConveyorTrackSensorOffset(int encoder_id, double offset)
设置传送带示教位置到同步开关之间的距离
int speedLine(const std::vector< double > &xd, double a, double t)
笛卡尔空间速度跟随
bool isSupportedTimeOptimal()
获取是否支持时间最优算法: true - 支持 false - 不支持
bool hasItemOnConveyorToTrack(int encoder_id)
传送带上是否有物品可以跟踪
int conveyorTrackCircle(int encoder_id, const std::vector< double > &center, bool rotate_tool)
圆形传送带跟随
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 conveyorTrackClearItems(int encoder_id)
清空传动带队列中的所有对象
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)
int enableVibrationSuppress(const std::vector< double > &omega, const std::vector< double > &zeta, int level)
打开振动抑制
int pathBufferFree(const std::string &name)
释放路径缓存
int setFuturePointSamplePeriod(double sample_time)
设置未来路径上点的采样时间间隔
int conveyorTrackLine(int encoder_id, const std::vector< double > &direction)
线性传送带跟随
double getEqradius()
获取等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动 可以通过 setEqradius 设置,默认为1
int setWorkObjectHold(const std::string &module_name, const std::vector< double > &mounting_pose)
当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
bool isConveyorTrackSync(int encoder_id)
判断传送带与机械臂之间是否达到相对静止
int setConveyorTrackCompensate(int encoder_id, double comp)
设置传送带跟踪的补偿值
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)
关节空间伺服
bool isTimeOptimalEnabled()
获取时间最优算法状态: true - 开启 false - 关闭
int pathBufferEval(const std::string &name, const std::vector< double > &a, const std::vector< double > &v, double t)
计算、优化等耗时操作,传入的参数相同时不会重新计算
bool isJointSoftServoEnabled()
判断关节电流环刚度系数是否使能
int servoCartesianWithAxes(const std::vector< double > &pose, const std::vector< double > &extq, double a, double v, double t, double lookahead_time, double gain)
伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度 (由软件内部直接做逆解)
int disbaleVibrationSuppress()
关闭振动抑制
@ PathBuffer_JointSpline
3: 关节B样条插值,最少三个点 废弃,建议用5替代,现在实际是关节空间 CUBIC_SPLINE
@ PathBuffer_CubicSpline
2: cubic_spline(录制的轨迹)
@ PathBuffer_TOPPRA
1: toppra 时间最优路径规划
@ PathBuffer_JointSplineC
4:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
@ PathBuffer_JointBSplineC
6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
std::shared_ptr< MotionControl > MotionControlPtr
数据类型的定义