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