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