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