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) -> nil
2329 *
2330 * @par Lua示例
2331 * trackJoint({0,0,0,0,0,0},0.01,0.5,1)
2332 *
2333 * @par JSON-RPC请求示例
2334 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
2335 *
2336 * @par JSON-RPC响应示例
2337 * {"id":1,"jsonrpc":"2.0","result":0}
2338 *
2339 * \endchinese
2340 * \english
2341 * Tracking motion, used for executing offline trajectories or passing
2342 * through user-planned trajectories, etc.
2343 *
2344 * @param q
2345 * @param smooth_scale
2346 * @param delay_sacle
2347 * @return
2348 *
2349 * @par Lua function prototype
2350 * trackJoint(q: table,t: number,smooth_scale: number,delay_sacle: number) -> nil
2351 *
2352 * @par Lua example
2353 * trackJoint({0,0,0,0,0,0},0.01,0.5,1)
2354 *
2355 * @par JSON-RPC request example
2356 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
2357 *
2358 * @par JSON-RPC response example
2359 * {"id":1,"jsonrpc":"2.0","result":0}
2360 *
2361 * \endenglish
2362 */
2363 int trackJoint(const std::vector<double> &q, double t, double smooth_scale,
2364 double delay_sacle);
2365
2366 /**
2367 * \chinese
2368 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
2369 * 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度
2370 * (由软件内部直接做逆解)
2371 *
2372 * @param pose
2373 * @param t
2374 * @param smooth_scale
2375 * @param delay_sacle
2376 * @return
2377 *
2378 * @par Lua函数原型
2379 * trackCartesian(pose: table,t: number,smooth_scale: number,delay_sacle: number) -> nil
2380 *
2381 * @par Lua示例
2382 * trackCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0.01,0.5,1)
2383 *
2384 * @par JSON-RPC请求示例
2385 * {"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}
2386 *
2387 * @par JSON-RPC响应示例
2388 * {"id":1,"jsonrpc":"2.0","result":0}
2389 * \endchinese
2390 * \english
2391 * Tracking motion, used for executing offline trajectories or passing
2392 * through user-planned trajectories, etc. The difference from trackJoint is
2393 * that it receives Cartesian poses instead of joint angles (inverse
2394 * kinematics is performed internally by the software).
2395 *
2396 * @param pose
2397 * @param t
2398 * @param smooth_scale
2399 * @param delay_sacle
2400 * @return
2401 *
2402 * @par Lua function prototype
2403 * trackCartesian(pose: table,t: number,smooth_scale: number,delay_sacle: number) -> nil
2404 *
2405 * @par Lua example
2406 * trackCartesian({0.58712,-0.15775,0.48703,2.76,0.344,1.432},0.01,0.5,1)
2407 *
2408 * @par JSON-RPC request example
2409 * {"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}
2410 *
2411 * @par JSON-RPC response example
2412 * {"id":1,"jsonrpc":"2.0","result":0}
2413 * \endenglish
2414 */
2415 int trackCartesian(const std::vector<double> &pose, double t,
2416 double smooth_scale, double delay_sacle);
2417
2418 /**
2419 * \chinese
2420 * 关节空间跟随
2421 *
2422 * @note 暂未实现
2423 *
2424 * @throws arcs::common_interface::AuboException
2425 *
2426 * @par Python函数原型
2427 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2428 *
2429 * @par Lua函数原型
2430 * followJoint(q: table) -> nil
2431 *
2432 * @par Lua示例
2433 * followJoint({0,0,0,0,0,0})
2434 *
2435 * \endchinese
2436 * \english
2437 * Joint space following
2438 *
2439 * @note Not implemented yet
2440 *
2441 * @throws arcs::common_interface::AuboException
2442 *
2443 * @par Python function prototype
2444 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2445 *
2446 * @par Lua function prototype
2447 * followJoint(q: table) -> nil
2448 *
2449 * @par Lua example
2450 * followJoint({0,0,0,0,0,0})
2451 *
2452 * \endenglish
2453 */
2454 int followJoint(const std::vector<double> &q);
2455
2456 /**
2457 * \chinese
2458 * 笛卡尔空间跟随
2459 *
2460 * @note 暂未实现
2461 *
2462 * @throws arcs::common_interface::AuboException
2463 *
2464 * @par Python函数原型
2465 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2466 *
2467 * @par Lua函数原型
2468 * followLine(pose: table) -> nil
2469 *
2470 * @par Lua示例
2471 * followLine({0.58712,-0.15775,0.48703,2.76,0.344,1.432})
2472 *
2473 * \endchinese
2474 * \english
2475 * Cartesian space following
2476 *
2477 * @note Not implemented yet
2478 *
2479 * @throws arcs::common_interface::AuboException
2480 *
2481 * @par Python function prototype
2482 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
2483 *
2484 * @par Lua function prototype
2485 * followLine(pose: table) -> nil
2486 *
2487 * @par Lua example
2488 * followLine({0.58712,-0.15775,0.48703,2.76,0.344,1.432})
2489 *
2490 * \endenglish
2491 */
2492 int followLine(const std::vector<double> &pose);
2493
2494 /**
2495 * \chinese
2496 * 关节空间速度跟随
2497 *
2498 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2499 *
2500 * @param qd 目标关节速度, 单位 rad/s
2501 * @param a 主轴的加速度, 单位 rad/s^2
2502 * @param t 函数返回所需要的时间, 单位 s \n
2503 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2504 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。\n
2505 * 如果没有达到目标速度,会减速到零。
2506 * 如果达到了目标速度就是按照目标速度匀速运动。
2507 * @retval 0 成功
2508 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2509 * Normal、ReducedMode、Recovery 状态
2510 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2511 * @retval -AUBO_BAD_STATE(-1)
2512 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2513 * 未找到,或者当前机器人模式非 Running
2514 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2515 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组qd的长度小于当前机器臂的自由度
2516 *
2517 * @throws arcs::common_interface::AuboException
2518 *
2519 * @par Python函数原型
2520 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2521 * float, arg2: float) -> int
2522 *
2523 * @par Lua函数原型
2524 * speedJoint(qd: table, a: number, t: number) -> nil
2525 *
2526 * @par Lua示例
2527 * speedJoint({0.2,0,0,0,0,0}, 1.5,10)
2528 *
2529 * @par JSON-RPC请求示例
2530 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2531 *
2532 * @par JSON-RPC响应示例
2533 * {"id":1,"jsonrpc":"2.0","result":0}
2534 *
2535 * \endchinese
2536 * \english
2537 * Joint space velocity following
2538 *
2539 * When the robot arm has not yet reached the target velocity, giving a new
2540 * target velocity will cause the robot arm to immediately reach the new
2541 * target velocity.
2542 *
2543 * @param qd Target joint velocity, unit: rad/s
2544 * @param a Main axis acceleration, unit: rad/s^2
2545 * @param t Time required for the function to return, unit: s \n
2546 * If t = 0, the function returns when the target velocity is reached;
2547 * otherwise, the function returns after t seconds, regardless of whether
2548 * the target velocity is reached.\n If the target velocity is not reached,
2549 * it will decelerate to zero. If the target velocity is reached, it will
2550 * move at a constant speed.
2551 * @retval 0 Success
2552 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2553 * ReducedMode, or Recovery
2554 * @retval AUBO_BUSY(3) The previous instruction is being executed
2555 * @retval -AUBO_BAD_STATE(-1)
2556 * Possible reasons include but are not limited to: thread has been
2557 * detached, thread terminated, task_id not found, or the current robot mode
2558 * is not Running
2559 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2560 * @retval -AUBO_INVL_ARGUMENT(-5) The length of the qd array is less than
2561 * the degrees of freedom of the current robot arm
2562 *
2563 * @throws arcs::common_interface::AuboException
2564 *
2565 * @par Python function prototype
2566 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2567 * float, arg2: float) -> int
2568 *
2569 * @par Lua function prototype
2570 * speedJoint(qd: table, a: number, t: number) -> nil
2571 *
2572 * @par Lua example
2573 * speedJoint({0.2,0,0,0,0,0}, 1.5,10)
2574 *
2575 * @par JSON-RPC request example
2576 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2577 *
2578 * @par JSON-RPC response example
2579 * {"id":1,"jsonrpc":"2.0","result":0}
2580 *
2581 * \endenglish
2582 */
2583 int speedJoint(const std::vector<double> &qd, double a, double t);
2584
2585 /**
2586 * \chinese
2587 * 关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
2588 *
2589 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2590 *
2591 * @param qd 目标关节速度, 单位 rad/s
2592 * @param a 主轴的加速度, 单位 rad/s^2
2593 * @param t 函数返回所需要的时间, 单位 s
2594 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2595 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
2596 * 如果没有达到目标速度,会减速到零。
2597 * 如果达到了目标速度就是按照目标速度匀速运动。
2598 * @return 成功返回0; 失败返回错误码
2599 * AUBO_BUSY
2600 * -AUBO_INVL_ARGUMENT
2601 * -AUBO_BAD_STATE
2602 *
2603 * @throws arcs::common_interface::AuboException
2604 *
2605 * @par Python函数原型
2606 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2607 * float, arg2: float) -> int
2608 *
2609 * @par Lua函数原型
2610 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
2611 *
2612 * @par Lua示例
2613 * resumeSpeedJoint({0.2,0,0,0,0,0},1.5,10)
2614 *
2615 * @par JSON-RPC请求示例
2616 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2617 *
2618 * @par JSON-RPC响应示例
2619 * {"id":1,"jsonrpc":"2.0","result":-1}
2620 * \endchinese
2621 * \english
2622 * Joint space velocity following (used to move to a safe position after a
2623 * collision during process execution)
2624 *
2625 * When the robot arm has not yet reached the target velocity, giving a new
2626 * target velocity will cause the robot arm to immediately reach the new
2627 * target velocity.
2628 *
2629 * @param qd Target joint velocity, unit: rad/s
2630 * @param a Main axis acceleration, unit: rad/s^2
2631 * @param t Time required for the function to return, unit: s
2632 * If t = 0, the function returns when the target velocity is reached;
2633 * otherwise, the function returns after t seconds, regardless of whether
2634 * the target velocity is reached. If the target velocity is not reached, it
2635 * will decelerate to zero. If the target velocity is reached, it will move
2636 * at a constant speed.
2637 * @return Returns 0 on success; otherwise returns error code
2638 * AUBO_BUSY
2639 * -AUBO_INVL_ARGUMENT
2640 * -AUBO_BAD_STATE
2641 *
2642 * @throws arcs::common_interface::AuboException
2643 *
2644 * @par Python function prototype
2645 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2646 * float, arg2: float) -> int
2647 *
2648 * @par Lua function prototype
2649 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
2650 *
2651 * @par Lua example
2652 * resumeSpeedJoint({0.2,0,0,0,0,0},1.5,10)
2653 *
2654 * @par JSON-RPC request example
2655 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
2656 *
2657 * @par JSON-RPC response example
2658 * {"id":1,"jsonrpc":"2.0","result":-1}
2659 * \endenglish
2660 */
2661 int resumeSpeedJoint(const std::vector<double> &qd, double a, double t);
2662
2663 /**
2664 * \chinese
2665 * 笛卡尔空间速度跟随
2666 *
2667 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2668 *
2669 * @param xd 工具速度, 单位 m/s
2670 * @param a 工具位置加速度, 单位 m/s^2
2671 * @param t 函数返回所需要的时间, 单位 s \n
2672 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2673 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
2674 * 如果没有达到目标速度,会减速到零。
2675 * 如果达到了目标速度就是按照目标速度匀速运动。
2676 * @retval 0 成功
2677 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2678 * Normal、ReducedMode、Recovery 状态
2679 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2680 * @retval -AUBO_BAD_STATE(-1)
2681 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2682 * 未找到,或者当前机器人模式非 Running
2683 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2684 *
2685 * @throws arcs::common_interface::AuboException
2686 *
2687 * @par Python函数原型
2688 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
2689 * arg2: float) -> int
2690 *
2691 * @par Lua函数原型
2692 * speedLine(pose: table, a: number, t: number) -> nil
2693 *
2694 * @par Lua示例
2695 * speedLine({0.25,0,0,0,0,0},1.2,100)
2696 *
2697 * @par JSON-RPC请求示例
2698 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2699 *
2700 * @par JSON-RPC响应示例
2701 * {"id":1,"jsonrpc":"2.0","result":0}
2702 *
2703 * \endchinese
2704 * \english
2705 * Cartesian space velocity following
2706 *
2707 * When the robot arm has not yet reached the target velocity, giving a new
2708 * target velocity will cause the robot arm to immediately reach the new
2709 * target velocity.
2710 *
2711 * @param xd Tool velocity, unit: m/s
2712 * @param a Tool position acceleration, unit: m/s^2
2713 * @param t Time required for the function to return, unit: s \n
2714 * If t = 0, the function returns when the target velocity is reached;
2715 * otherwise, the function returns after t seconds, regardless of whether
2716 * the target velocity is reached. If the target velocity is not reached, it
2717 * will decelerate to zero. If the target velocity is reached, it will move
2718 * at a constant speed.
2719 * @retval 0 Success
2720 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2721 * ReducedMode, or Recovery
2722 * @retval AUBO_BUSY(3) The previous instruction is being executed
2723 * @retval -AUBO_BAD_STATE(-1)
2724 * Possible reasons include but are not limited to: thread has been
2725 * detached, thread terminated, task_id not found, or the current robot mode
2726 * is not Running
2727 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2728 *
2729 * @throws arcs::common_interface::AuboException
2730 *
2731 * @par Python function prototype
2732 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
2733 * arg2: float) -> int
2734 *
2735 * @par Lua function prototype
2736 * speedLine(pose: table, a: number, t: number) -> nil
2737 *
2738 * @par Lua example
2739 * speedLine({0.25,0,0,0,0,0},1.2,100)
2740 *
2741 * @par JSON-RPC request example
2742 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2743 *
2744 * @par JSON-RPC response example
2745 * {"id":1,"jsonrpc":"2.0","result":0}
2746 *
2747 * \endenglish
2748 */
2749 int speedLine(const std::vector<double> &xd, double a, double t);
2750
2751 /**
2752 * \chinese
2753 * 笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
2754 *
2755 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
2756 *
2757 * @param xd 工具速度, 单位 m/s
2758 * @param a 工具位置加速度, 单位 m/s^2
2759 * @param t 函数返回所需要的时间, 单位 s \n
2760 * 如果 t = 0,当达到目标速度的时候,函数将返回;
2761 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
2762 * 如果没有达到目标速度,会减速到零。
2763 * 如果达到了目标速度就是按照目标速度匀速运动。
2764 * @return 成功返回0; 失败返回错误码
2765 * -AUBO_BAD_STATE
2766 *
2767 * @throws arcs::common_interface::AuboException
2768 *
2769 * @par Python函数原型
2770 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2771 * float, arg2: float) -> int
2772 *
2773 * @par Lua函数原型
2774 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
2775 *
2776 * @par Lua示例
2777 * resumeSpeedLine({0.25,0,0,0,0,0},1.2,100)
2778 *
2779 * @par JSON-RPC请求示例
2780 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2781 *
2782 * @par JSON-RPC响应示例
2783 * {"id":1,"jsonrpc":"2.0","result":-1}
2784 * \endchinese
2785 * \english
2786 * Cartesian space velocity following (used to move to a safe position after
2787 * a collision during process execution)
2788 *
2789 * When the robot arm has not yet reached the target velocity, giving a new
2790 * target velocity will cause the robot arm to immediately reach the new
2791 * target velocity.
2792 *
2793 * @param xd Tool velocity, unit: m/s
2794 * @param a Tool position acceleration, unit: m/s^2
2795 * @param t Time required for the function to return, unit: s \n
2796 * If t = 0, the function returns when the target velocity is reached;
2797 * otherwise, the function returns after t seconds, regardless of whether
2798 * the target velocity is reached. If the target velocity is not reached, it
2799 * will decelerate to zero. If the target velocity is reached, it will move
2800 * at a constant speed.
2801 * @return Returns 0 on success; otherwise returns error code
2802 * -AUBO_BAD_STATE
2803 *
2804 * @throws arcs::common_interface::AuboException
2805 *
2806 * @par Python function prototype
2807 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2808 * float, arg2: float) -> int
2809 *
2810 * @par Lua function prototype
2811 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
2812 *
2813 * @par Lua example
2814 * resumeSpeedLine({0.25,0,0,0,0,0},1.2,100)
2815 *
2816 * @par JSON-RPC request example
2817 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
2818 *
2819 * @par JSON-RPC response example
2820 * {"id":1,"jsonrpc":"2.0","result":-1}
2821 * \endenglish
2822 */
2823 int resumeSpeedLine(const std::vector<double> &xd, double a, double t);
2824
2825 /**
2826 * \chinese
2827 * 在关节空间做样条插值
2828 *
2829 * @param q 关节角度,如果传入参数维度为0,表示样条运动结束
2830 * @param a 加速度, 单位 rad/s^2,
2831 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
2832 * @param v 速度, 单位 rad/s,
2833 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
2834 * @param duration
2835 * @return 成功返回0; 失败返回错误码
2836 * AUBO_BUSY
2837 * AUBO_BAD_STATE
2838 * -AUBO_BAD_STATE
2839 *
2840 * @throws arcs::common_interface::AuboException
2841 *
2842 * @par Python函数原型
2843 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2844 * float, arg2: float, arg3: float) -> int
2845 *
2846 * @par Lua函数原型
2847 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
2848 *
2849 * @par Lua示例
2850 * moveSpline({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},1.3,1.0,0)
2851 *
2852 * @par JSON-RPC请求示例
2853 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
2854 *
2855 * @par JSON-RPC响应示例
2856 * {"id":1,"jsonrpc":"2.0","result":0}
2857 * \endchinese
2858 * \english
2859 * Perform spline interpolation in joint space
2860 *
2861 * @param q Joint angles. If the input vector is of size 0, it indicates the
2862 * end of the spline motion.
2863 * @param a Acceleration, unit: rad/s^2. The maximum value can be obtained
2864 * via RobotConfig::getJointMaxAccelerations().
2865 * @param v Velocity, unit: rad/s. The maximum value can be obtained via
2866 * RobotConfig::getJointMaxSpeeds().
2867 * @param duration
2868 * @return Returns 0 on success; otherwise returns an error code:
2869 * AUBO_BUSY
2870 * AUBO_BAD_STATE
2871 * -AUBO_BAD_STATE
2872 *
2873 * @throws arcs::common_interface::AuboException
2874 *
2875 * @par Python function prototype
2876 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
2877 * float, arg2: float, arg3: float) -> int
2878 *
2879 * @par Lua function prototype
2880 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
2881 *
2882 * @par Lua example
2883 * moveSpline({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},1.3,1.0,0)
2884 *
2885 * @par JSON-RPC request example
2886 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
2887 *
2888 * @par JSON-RPC response example
2889 * {"id":1,"jsonrpc":"2.0","result":0}
2890 * \endenglish
2891 */
2892 int moveSpline(const std::vector<double> &q, double a, double v,
2893 double duration);
2894
2895 /**
2896 * \chinese
2897 * 添加关节运动
2898 *
2899 * @param q 关节角, 单位 rad
2900 * @param a 加速度, 单位 rad/s^2,
2901 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
2902 * @param v 速度, 单位 rad/s,
2903 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
2904 * @param blend_radius 交融半径, 单位 m
2905 * @param duration 运行时间,单位 s \n
2906 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
2907 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
2908 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
2909 * 当 duration = 0的时候,
2910 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
2911 * 如果duration不等于0,a 和 v 的值将被忽略。
2912 * @retval 0 成功
2913 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
2914 * Normal、ReducedMode、Recovery 状态
2915 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
2916 * @retval AUBO_BUSY(3) 上一条指令正在执行中
2917 * @retval -AUBO_BAD_STATE(-1)
2918 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
2919 * 未找到,或者当前机器人模式非 Running
2920 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
2921 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组q的长度小于当前机器臂的自由度
2922 * @retval AUBO_REQUEST_IGNORE(13) 参数数组q的长度太短且无需在该点停留
2923 *
2924 * @throws arcs::common_interface::AuboException
2925 *
2926 * @par Python函数原型
2927 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
2928 * arg2: float, arg3: float, arg4: float) -> int
2929 *
2930 * @par Lua函数原型
2931 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
2932 * number) -> nil
2933 *
2934 * @par Lua示例
2935 * moveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},0.3,0.3,0,0)
2936 *
2937 * @par JSON-RPC请求示例
2938 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
2939 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
2940 *
2941 * @par JSON-RPC响应示例
2942 * {"id":1,"jsonrpc":"2.0","result":0}
2943 *
2944 * \endchinese
2945 * \english
2946 * Add joint motion
2947 *
2948 * @param q Joint angles, unit: rad
2949 * @param a Acceleration, unit: rad/s^2,
2950 * The maximum value can be obtained via
2951 * RobotConfig::getJointMaxAccelerations()
2952 * @param v Velocity, unit: rad/s,
2953 * The maximum value can be obtained via RobotConfig::getJointMaxSpeeds()
2954 * @param blend_radius Blend radius, unit: m
2955 * @param duration Execution time, unit: s \n
2956 * Normally, when speed and acceleration are given, the trajectory duration
2957 * can be determined. If you want to extend the trajectory duration, set the
2958 * duration parameter. Duration can extend the trajectory time, but cannot
2959 * shorten it.\n When duration = 0, it means the execution time is not
2960 * specified, and the time will be calculated based on speed and
2961 * acceleration. If duration is not 0, a and v values will be ignored.
2962 * @retval 0 Success
2963 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
2964 * ReducedMode, or Recovery
2965 * @retval AUBO_QUEUE_FULL(2) Planning queue is full
2966 * @retval AUBO_BUSY(3) The previous instruction is being executed
2967 * @retval -AUBO_BAD_STATE(-1)
2968 * Possible reasons include but are not limited to: thread has been
2969 * detached, thread terminated, task_id not found, or the current robot mode
2970 * is not Running
2971 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
2972 * @retval -AUBO_INVL_ARGUMENT(-5) The length of q is less than the degrees
2973 * of freedom of the current robot arm
2974 * @retval AUBO_REQUEST_IGNORE(13) The length of q is too short and there is
2975 * no need to stop at that point
2976 *
2977 * @throws arcs::common_interface::AuboException
2978 *
2979 * @par Python function prototype
2980 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
2981 * arg2: float, arg3: float, arg4: float) -> int
2982 *
2983 * @par Lua function prototype
2984 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
2985 * number) -> nil
2986 *
2987 * @par Lua example
2988 * moveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},0.3,0.3,0,0)
2989 *
2990 * @par JSON-RPC request example
2991 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
2992 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
2993 *
2994 * @par JSON-RPC response example
2995 * {"id":1,"jsonrpc":"2.0","result":0}
2996 *
2997 * \endenglish
2998 */
2999 int moveJoint(const std::vector<double> &q, double a, double v,
3000 double blend_radius, double duration);
3001
3002 /**
3003 * \chinese
3004 * 机器人与外部轴同步运动
3005 *
3006 * @param group_name
3007 * @param q
3008 * @param a
3009 * @param v
3010 * @param blend_radius
3011 * @param duration
3012 * @return
3013 * \endchinese
3014 * \english
3015 * Synchronous motion of robot and external axes
3016 *
3017 * @param group_name
3018 * @param q
3019 * @param a
3020 * @param v
3021 * @param blend_radius
3022 * @param duration
3023 * @return
3024 * \endenglish
3025 */
3026 int moveJointWithAxisGroup(const std::vector<double> &q, double a, double v,
3027 double blend_radius, double duration,
3028 const std::string &group_name,
3029 const std::vector<double> &extq);
3030
3031 /**
3032 * \chinese
3033 * 通过关节运动移动到暂停点的位置
3034 *
3035 * @param q 关节角, 单位 rad
3036 * @param a 加速度, 单位 rad/s^2
3037 * @param v 速度, 单位 rad/s
3038 * @param duration 运行时间,单位 s \n
3039 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3040 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3041 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3042 * 当 duration = 0的时候,
3043 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3044 * 如果duration不等于0,a 和 v 的值将被忽略。
3045 * @return 成功返回0;失败返回错误码
3046 * -AUBO_INVL_ARGUMENT
3047 * -AUBO_BAD_STATE
3048 *
3049 * @throws arcs::common_interface::AuboException
3050 *
3051 * @par Python函数原型
3052 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3053 * float, arg2: float, arg3: float) -> int
3054 *
3055 * @par Lua函数原型
3056 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
3057 *
3058 * @par Lua示例
3059 * resumeMoveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},1.3,1.0,0)
3060 *
3061 * @par JSON-RPC请求示例
3062 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
3063 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
3064 *
3065 * @par JSON-RPC响应示例
3066 * {"id":1,"jsonrpc":"2.0","result":-1}
3067 * \endchinese
3068 * \english
3069 * Move to the pause point using joint motion.
3070 *
3071 * @param q Joint angles, unit: rad
3072 * @param a Acceleration, unit: rad/s^2
3073 * @param v Velocity, unit: rad/s
3074 * @param duration Execution time, unit: s \n
3075 * Normally, when speed and acceleration are given, the trajectory duration
3076 * can be determined. If you want to extend the trajectory duration, set the
3077 * duration parameter. Duration can extend the trajectory time, but cannot
3078 * shorten it.\n When duration = 0, it means the execution time is not
3079 * specified, and the time will be calculated based on speed and
3080 * acceleration. If duration is not 0, a and v values will be ignored.
3081 * @return Returns 0 on success; otherwise returns error code
3082 * -AUBO_INVL_ARGUMENT
3083 * -AUBO_BAD_STATE
3084 *
3085 * @throws arcs::common_interface::AuboException
3086 *
3087 * @par Python function prototype
3088 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3089 * float, arg2: float, arg3: float) -> int
3090 *
3091 * @par Lua function prototype
3092 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
3093 *
3094 * @par Lua example
3095 * resumeMoveJoint({-2.05177,-0.400292, 1.19625, 0.0285152, 1.57033, -2.28774},1.3,1.0,0)
3096 *
3097 * @par JSON-RPC request example
3098 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
3099 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
3100 *
3101 * @par JSON-RPC response example
3102 * {"id":1,"jsonrpc":"2.0","result":-1}
3103 * \endenglish
3104 */
3105 int resumeMoveJoint(const std::vector<double> &q, double a, double v,
3106 double duration);
3107
3108 /**
3109 * \chinese
3110 * 添加直线运动
3111 *
3112 * @param pose 目标位姿
3113 * @param a 加速度(如果位置变化小于1mm,姿态变化大于 1e-4
3114 * rad,此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
3115 * 最大值可通过RobotConfig类中的接口getTcpMaxAccelerations()来获取
3116 * @param v 速度(如果位置变化小于1mm,姿态变化大于 1e-4
3117 * rad,此速度会被作为角速度,单位 rad/s.否则为线速度,单位 m/s)
3118 * 最大值可通过RobotConfig类中的接口getTcpMaxSpeeds()来获取
3119 * @param blend_radius 交融半径,单位 m,值介于0.001和1之间
3120 * @param duration 运行时间,单位 s \n
3121 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3122 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3123 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3124 * 当 duration = 0的时候,
3125 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3126 * 如果duration不等于0,a 和 v 的值将被忽略。
3127 * @retval 0 成功
3128 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
3129 * Normal、ReducedMode、Recovery 状态
3130 * @retval AUBO_QUEUE_FULL(2) 轨迹队列已满
3131 * @retval AUBO_BUSY(3) 上一条指令正在执行中
3132 * @retval -AUBO_BAD_STATE(-1)
3133 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
3134 * 未找到,或者当前机器人模式非 Running
3135 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
3136 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组 pose
3137 * 的长度小于当前机器臂的自由度
3138 * @retval AUBO_REQUEST_IGNORE(13) 参数数组 pose
3139 * 路径长度太短且无需在该点停留
3140 *
3141 * @throws arcs::common_interface::AuboException
3142 *
3143 * @par Python函数原型
3144 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
3145 * arg2: float, arg3: float, arg4: float) -> int
3146 *
3147 * @par Lua函数原型
3148 * moveLine(pose: table, a: number, v: number, blend_radius: number,
3149 * duration: number) -> nil
3150 *
3151 * @par Lua示例
3152 * moveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.3,1.0,0)
3153 *
3154 * @par JSON-RPC请求示例
3155 * {"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}
3156 *
3157 * @par JSON-RPC响应示例
3158 * {"id":1,"jsonrpc":"2.0","result":0}
3159 *
3160 * \endchinese
3161 * \english
3162 * Add linear motion
3163 *
3164 * @param pose Target pose
3165 * @param a Acceleration (if the position change is less than 1mm and the
3166 * posture change is greater than 1e-4 rad, this acceleration is treated as
3167 * angular acceleration in rad/s^2; otherwise, as linear acceleration in
3168 * m/s^2). The maximum value can be obtained via
3169 * RobotConfig::getTcpMaxAccelerations().
3170 * @param v Velocity (if the position change is less than 1mm and the
3171 * posture change is greater than 1e-4 rad, this velocity is treated as
3172 * angular velocity in rad/s; otherwise, as linear velocity in m/s). The
3173 * maximum value can be obtained via RobotConfig::getTcpMaxSpeeds().
3174 * @param blend_radius Blend radius, unit: m, value between 0.001 and 1
3175 * @param duration Execution time, unit: s \n
3176 * Normally, when speed and acceleration are given, the trajectory duration
3177 * can be determined. If you want to extend the trajectory duration, set the
3178 * duration parameter. Duration can extend the trajectory time, but cannot
3179 * shorten it.\n When duration = 0, it means the execution time is not
3180 * specified, and the time will be calculated based on speed and
3181 * acceleration. If duration is not 0, a and v values will be ignored.
3182 * @retval 0 Success
3183 * @retval AUBO_BAD_STATE(1) The current safety mode is not Normal,
3184 * ReducedMode, or Recovery
3185 * @retval AUBO_QUEUE_FULL(2) Trajectory queue is full
3186 * @retval AUBO_BUSY(3) The previous instruction is being executed
3187 * @retval -AUBO_BAD_STATE(-1) Possible reasons include but are not limited
3188 * to: thread has been detached, thread terminated, task_id not found, or
3189 * the current robot mode is not Running
3190 * @retval -AUBO_TIMEOUT(-4) Interface call timeout
3191 * @retval -AUBO_INVL_ARGUMENT(-5) The length of the pose array is less than
3192 * the degrees of freedom of the current robot arm
3193 * @retval AUBO_REQUEST_IGNORE(13) The length of the pose array is too short
3194 * and there is no need to stop at that point
3195 *
3196 * @throws arcs::common_interface::AuboException
3197 *
3198 * @par Python function prototype
3199 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
3200 * arg2: float, arg3: float, arg4: float) -> int
3201 *
3202 * @par Lua function prototype
3203 * moveLine(pose: table, a: number, v: number, blend_radius: number,
3204 * duration: number) -> nil
3205 *
3206 * @par Lua example
3207 * moveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.3,1.0,0)
3208 *
3209 * @par JSON-RPC request example
3210 * {"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}
3211 *
3212 * @par JSON-RPC response example
3213 * {"id":1,"jsonrpc":"2.0","result":0}
3214 *
3215 * \endenglish
3216 */
3217 int moveLine(const std::vector<double> &pose, double a, double v,
3218 double blend_radius, double duration);
3219
3220 /**
3221 * \chinese
3222 * 直线运动与外部轴同步运动
3223 *
3224 * @param group_name 外部轴组名称
3225 * @param pose 目标位姿
3226 * @param a 加速度
3227 * @param v 速度
3228 * @param blend_radius 交融半径
3229 * @param duration 运行时间
3230 * @return
3231 * \endchinese
3232 * \english
3233 * Linear motion synchronized with external axes
3234 *
3235 * @param group_name Name of the external axis group
3236 * @param pose Target pose
3237 * @param a Acceleration
3238 * @param v Velocity
3239 * @param blend_radius Blend radius
3240 * @param duration Execution time
3241 * @return
3242 * \endenglish
3243 */
3244 int moveLineWithAxisGroup(const std::vector<double> &pose, double a,
3245 double v, double blend_radius, double duration,
3246 const std::string &group_name,
3247 const std::vector<double> &extq);
3248
3249 /**
3250 * \chinese
3251 * 添加工艺运动
3252 *
3253 * @param pose
3254 * @param a
3255 * @param v
3256 * @param blend_radius
3257 * @return 成功返回0;失败返回错误码
3258 * AUBO_BAD_STATE
3259 * AUBO_BUSY
3260 * -AUBO_INVL_ARGUMENT
3261 * -AUBO_BAD_STATE
3262 *
3263 * @throws arcs::common_interface::AuboException
3264 *
3265 * @par Lua函数原型
3266 * moveProcess(pose: table, a: number, v: number, blend_radius: number,
3267 * duration: number) -> nil
3268 *
3269 * @par Lua示例
3270 * moveProcess({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3271 *
3272 * @par JSON-RPC请求示例
3273 * {"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}
3274 *
3275 * @par JSON-RPC响应示例
3276 * {"id":1,"jsonrpc":"2.0","result":0}
3277 * \endchinese
3278 * \english
3279 * Add process motion
3280 *
3281 * @param pose
3282 * @param a
3283 * @param v
3284 * @param blend_radius
3285 * @return Returns 0 on success; otherwise returns an error code:
3286 * AUBO_BAD_STATE
3287 * AUBO_BUSY
3288 * -AUBO_INVL_ARGUMENT
3289 * -AUBO_BAD_STATE
3290 *
3291 * @throws arcs::common_interface::AuboException
3292 *
3293 * @par Lua function prototype
3294 * moveProcess(pose: table, a: number, v: number, blend_radius: number,
3295 * duration: number) -> nil
3296 *
3297 * @par Lua example
3298 * moveProcess({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3299 *
3300 * @par JSON-RPC request example
3301 * {"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}
3302 *
3303 * @par JSON-RPC response example
3304 * {"id":1,"jsonrpc":"2.0","result":0}
3305 * \endenglish
3306 */
3307 int moveProcess(const std::vector<double> &pose, double a, double v,
3308 double blend_radius);
3309
3310 /**
3311 * \chinese
3312 * 通过直线运动移动到暂停点的位置
3313 *
3314 * @param pose 目标位姿
3315 * @param a 加速度, 单位 m/s^2
3316 * @param v 速度, 单位 m/s
3317 * @param duration 运行时间,单位 s \n
3318 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3319 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3320 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3321 * 当 duration = 0的时候,
3322 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3323 * 如果duration不等于0,a 和 v 的值将被忽略。
3324 * @return 成功返回0;失败返回错误码
3325 * -AUBO_INVL_ARGUMENT
3326 * -AUBO_BAD_STATE
3327 *
3328 * @throws arcs::common_interface::AuboException
3329 *
3330 * @par Python函数原型
3331 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3332 * float, arg2: float, arg3: float) -> int
3333 *
3334 * @par Lua函数原型
3335 * resumeMoveLine(pose: table, a: number, v: number,duration: number) -> nil
3336 *
3337 * @par Lua示例
3338 * resumeMoveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3339 *
3340 * @par JSON-RPC请求示例
3341 * {"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}
3342 *
3343 * @par JSON-RPC响应示例
3344 * {"id":1,"jsonrpc":"2.0","result":0}
3345 *
3346 * \endchinese
3347 * \english
3348 * Move to the pause point using linear motion.
3349 *
3350 * @param pose Target pose
3351 * @param a Acceleration, unit: m/s^2
3352 * @param v Velocity, unit: m/s
3353 * @param duration Execution time, unit: s \n
3354 * Normally, when speed and acceleration are given, the trajectory duration
3355 * can be determined. If you want to extend the trajectory duration, set the
3356 * duration parameter. Duration can extend the trajectory time, but cannot
3357 * shorten it.\n When duration = 0, it means the execution time is not
3358 * specified, and the time will be calculated based on speed and
3359 * acceleration. If duration is not 0, a and v values will be ignored.
3360 * @return Returns 0 on success; otherwise returns error code
3361 * -AUBO_INVL_ARGUMENT
3362 * -AUBO_BAD_STATE
3363 *
3364 * @throws arcs::common_interface::AuboException
3365 *
3366 * @par Python function prototype
3367 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3368 * float, arg2: float, arg3: float) -> int
3369 *
3370 * @par Lua function prototype
3371 * resumeMoveLine(pose: table, a: number, v: number, duration: number) ->
3372 * nil
3373 *
3374 * @par Lua example
3375 * resumeMoveLine({0.58815,0.0532,0.62391,2.46,0.479,1.619},1.2,0.25,0)
3376 *
3377 * @par JSON-RPC request example
3378 * {"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}
3379 *
3380 * @par JSON-RPC response example
3381 * {"id":1,"jsonrpc":"2.0","result":0}
3382 *
3383 * \endenglish
3384 */
3385 int resumeMoveLine(const std::vector<double> &pose, double a, double v,
3386 double duration);
3387
3388 /**
3389 * \chinese
3390 * 添加圆弧运动
3391 *
3392 * @todo 可以由多段圆弧组成圆周运动
3393 *
3394 * @param via_pose 圆弧运动途中点的位姿
3395 * @param end_pose 圆弧运动结束点的位姿
3396 * @param a 加速度(如果via_pose与上一个路点位置变化小于1mm,姿态变化大于 1e-4
3397 * rad, 此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
3398 * @param v 速度(如果via_pose与上一个路点位置变化小于1mm, 姿态变化大于 1e-4
3399 * rad, 此速度会被作为角速度, 单位 rad / s.否则为线速度, 单位 m / s)
3400 * @param blend_radius 交融半径,单位: m
3401 * @param duration 运行时间,单位: s \n
3402 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
3403 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
3404 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
3405 * 当 duration = 0 的时候,
3406 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
3407 * 如果duration不等于0,a 和 v 的值将被忽略。
3408 * @return 成功返回0;失败返回错误码
3409 * AUBO_BAD_STATE
3410 * AUBO_BUSY
3411 * -AUBO_INVL_ARGUMENT
3412 * -AUBO_BAD_STATE
3413 *
3414 * @throws arcs::common_interface::AuboException
3415 *
3416 * @par Python函数原型
3417 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3418 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
3419 *
3420 * @par Lua函数原型
3421 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
3422 * blend_radius: number, duration: number) -> nil
3423 *
3424 * @par Lua示例
3425 * 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)
3426 *
3427 * @par JSON-RPC请求示例
3428 * {"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}
3429 *
3430 * @par JSON-RPC响应示例
3431 * {"id":1,"jsonrpc":"2.0","result":0}
3432 * \endchinese
3433 * \english
3434 * Add circular arc motion
3435 *
3436 * @todo Can be composed of multiple arcs to form a circular motion
3437 *
3438 * @param via_pose The pose of the via point during the arc motion
3439 * @param end_pose The pose of the end point of the arc motion
3440 * @param a Acceleration (if the position change between via_pose and the
3441 * previous waypoint is less than 1mm and the posture change is greater than
3442 * 1e-4 rad, this acceleration is treated as angular acceleration in
3443 * rad/s^2; otherwise, as linear acceleration in m/s^2)
3444 * @param v Velocity (if the position change between via_pose and the
3445 * previous waypoint is less than 1mm and the posture change is greater than
3446 * 1e-4 rad, this velocity is treated as angular velocity in rad/s;
3447 * otherwise, as linear velocity in m/s)
3448 * @param blend_radius Blend radius, unit: m
3449 * @param duration Execution time, unit: s \n
3450 * Normally, when speed and acceleration are given, the trajectory duration
3451 * can be determined. If you want to extend the trajectory duration, set the
3452 * duration parameter. Duration can extend the trajectory time, but cannot
3453 * shorten it.\n When duration = 0, it means the execution time is not
3454 * specified, and the time will be calculated based on speed and
3455 * acceleration. If duration is not 0, a and v values will be ignored.
3456 * @return Returns 0 on success; otherwise returns error code
3457 * AUBO_BAD_STATE
3458 * AUBO_BUSY
3459 * -AUBO_INVL_ARGUMENT
3460 * -AUBO_BAD_STATE
3461 *
3462 * @throws arcs::common_interface::AuboException
3463 *
3464 * @par Python function prototype
3465 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
3466 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
3467 *
3468 * @par Lua function prototype
3469 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
3470 * blend_radius: number, duration: number) -> nil
3471 *
3472 * @par Lua example
3473 * 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)
3474 *
3475 * @par JSON-RPC request example
3476 * {"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}
3477 *
3478 * @par JSON-RPC response example
3479 * {"id":1,"jsonrpc":"2.0","result":0}
3480 * \endenglish
3481 */
3482 int moveCircle(const std::vector<double> &via_pose,
3483 const std::vector<double> &end_pose, double a, double v,
3484 double blend_radius, double duration);
3485
3486 /**
3487 * \chinese
3488 * moveCircle 与外部轴同步运动
3489 *
3490 * @param group_name 外部轴组名称
3491 * @param via_pose 圆弧运动途中点的位姿
3492 * @param end_pose 圆弧运动结束点的位姿
3493 * @param a 加速度
3494 * @param v 速度
3495 * @param blend_radius 交融半径
3496 * @param duration 运行时间
3497 * @return
3498 * \endchinese
3499 * \english
3500 * moveCircle with external axes synchronized motion
3501 *
3502 * @param group_name Name of the external axis group
3503 * @param via_pose The pose of the via point during the arc motion
3504 * @param end_pose The pose of the end point of the arc motion
3505 * @param a Acceleration
3506 * @param v Velocity
3507 * @param blend_radius Blend radius
3508 * @param duration Execution time
3509 * @return
3510 * \endenglish
3511 */
3512 int moveCircleWithAxisGroup(const std::vector<double> &via_pose,
3513 const std::vector<double> &end_pose, double a,
3514 double v, double blend_radius, double duration,
3515 const std::string &group_name,
3516 const std::vector<double> &extq);
3517
3518 /**
3519 * \chinese
3520 * 设置圆弧路径模式
3521 *
3522 * @param mode 模式 \n
3523 * 0:工具姿态相对于圆弧路径点坐标系保持不变 \n
3524 * 1:姿态线性变化,绕着空间定轴转动,从起始点姿态变化到目标点姿态 \n
3525 * 2:从起点姿态开始经过中间点姿态,变化到目标点姿态
3526 * @return 成功返回0;失败返回错误码
3527 * AUBO_BAD_STATE
3528 * AUBO_BUSY
3529 * -AUBO_INVL_ARGUMENT
3530 * -AUBO_BAD_STATE
3531 *
3532 * @throws arcs::common_interface::AuboException
3533 *
3534 * @par Python函数原型
3535 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
3536 *
3537 * @par Lua函数原型
3538 * setCirclePathMode(mode: number) -> nil
3539 *
3540 * @par Lua示例
3541 * setCirclePathMode(1)
3542 *
3543 * @par JSON-RPC请求示例
3544 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
3545 *
3546 * @par JSON-RPC响应示例
3547 * {"id":1,"jsonrpc":"2.0","result":0}
3548 *
3549 * \endchinese
3550 * \english
3551 * Set circle path mode
3552 *
3553 * @param mode Mode \n
3554 * 0: Tool orientation remains unchanged relative to the arc path point
3555 * coordinate system \n 1: Orientation changes linearly, rotating around a
3556 * fixed axis in space, from the start orientation to the target orientation
3557 * \n 2: Orientation changes from the start orientation, through the via
3558 * point orientation, to the target orientation
3559 * @return Returns 0 on success; otherwise returns an error code
3560 * AUBO_BAD_STATE
3561 * AUBO_BUSY
3562 * -AUBO_INVL_ARGUMENT
3563 * -AUBO_BAD_STATE
3564 *
3565 * @throws arcs::common_interface::AuboException
3566 *
3567 * @par Python function prototype
3568 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
3569 *
3570 * @par Lua function prototype
3571 * setCirclePathMode(mode: number) -> nil
3572 *
3573 * @par Lua example
3574 * setCirclePathMode(1)
3575 *
3576 * @par JSON-RPC request example
3577 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
3578 *
3579 * @par JSON-RPC response example
3580 * {"id":1,"jsonrpc":"2.0","result":0}
3581 *
3582 * \endenglish
3583 */
3584 int setCirclePathMode(int mode);
3585
3586 /**
3587 * \chinese
3588 * 高级圆弧或者圆周运动
3589 *
3590 * @param param 圆周运动参数
3591 * @return 成功返回0;失败返回错误码
3592 * AUBO_BAD_STATE
3593 * AUBO_BUSY
3594 * -AUBO_INVL_ARGUMENT
3595 * -AUBO_BAD_STATE
3596 *
3597 * @throws arcs::common_interface::AuboException
3598 *
3599 * @par Python函数原型
3600 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
3601 * arcs::common_interface::CircleParameters) -> int
3602 *
3603 * @par Lua函数原型
3604 * moveCircle2(param: table) -> nil
3605 *
3606 * @par Lua示例
3607 * 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)
3608 *
3609 * @par JSON-RPC请求示例
3610 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
3611 * "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,
3612 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
3613 *
3614 * @par JSON-RPC响应示例
3615 * {"id":1,"jsonrpc":"2.0","result":0}
3616 * \endchinese
3617 * \english
3618 * Advanced arc or circular motion
3619 *
3620 * @param param Circular motion parameters
3621 * @return Returns 0 on success; otherwise returns an error code:
3622 * AUBO_BAD_STATE
3623 * AUBO_BUSY
3624 * -AUBO_INVL_ARGUMENT
3625 * -AUBO_BAD_STATE
3626 *
3627 * @throws arcs::common_interface::AuboException
3628 *
3629 * @par Python function prototype
3630 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
3631 * arcs::common_interface::CircleParameters) -> int
3632 *
3633 * @par Lua function prototype
3634 * moveCircle2(param: table) -> nil
3635 *
3636 * @par Lua example
3637 * 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)
3638 *
3639 * @par JSON-RPC request example
3640 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
3641 * "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,
3642 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
3643 *
3644 * @par JSON-RPC response example
3645 * {"id":1,"jsonrpc":"2.0","result":0}
3646 * \endenglish
3647 */
3649
3650 /**
3651 * \chinese
3652 * 新建一个路径点缓存
3653 *
3654 * @param name 指定路径的名字
3655 * @param type 路径的类型 \n
3656 * 1: toppra 时间最优路径规划 \n
3657 * 2: cubic_spline(录制的轨迹) \n
3658 * 3: 关节B样条插值,最少三个点
3659 * @param size 缓存区大小
3660 * @return 新建成功返回 AUBO_OK(0)
3661 *
3662 * @throws arcs::common_interface::AuboException
3663 *
3664 * @par Python函数原型
3665 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
3666 * arg2: int) -> int
3667 *
3668 * @par Lua函数原型
3669 * pathBufferAlloc(name: string, type: number, size: number) -> nil
3670 *
3671 * @par Lua示例
3672 * pathBufferAlloc("traje_name",5,100)
3673 *
3674 * @par JSON-RPC请求示例
3675 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
3676 *
3677 * @par JSON-RPC响应示例
3678 * {"id":1,"jsonrpc":"2.0","result":0}
3679 *
3680 * \endchinese
3681 * \english
3682 * Create a new path point buffer
3683 *
3684 * @param name Name of the path
3685 * @param type Type of the path \n
3686 * 1: toppra time-optimal path planning \n
3687 * 2: cubic_spline (recorded trajectory) \n
3688 * 3: Joint B-spline interpolation, at least three points
3689 * @param size Buffer size
3690 * @return Returns AUBO_OK(0) on success
3691 *
3692 * @throws arcs::common_interface::AuboException
3693 *
3694 * @par Python function prototype
3695 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
3696 * arg2: int) -> int
3697 *
3698 * @par Lua function prototype
3699 * pathBufferAlloc(name: string, type: number, size: number) -> nil
3700 *
3701 * @par Lua exmaple
3702 * pathBufferAlloc("traje_name",5,100)
3703 *
3704 * @par JSON-RPC request example
3705 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
3706 *
3707 * @par JSON-RPC response example
3708 * {"id":1,"jsonrpc":"2.0","result":0}
3709 *
3710 * \endenglish
3711 */
3712 int pathBufferAlloc(const std::string &name, int type, int size);
3713
3714 /**
3715 * \chinese
3716 * 向路径缓存添加路点
3717 *
3718 * @param name 路径缓存的名字
3719 * @param waypoints 路点
3720 * @return 成功返回0;失败返回错误码
3721 * -AUBO_INVL_ARGUMENT
3722 * -AUBO_BAD_STATE
3723 *
3724 * @throws arcs::common_interface::AuboException
3725 *
3726 * @par Python函数原型
3727 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3728 * List[List[float]]) -> int
3729 *
3730 * @par Lua函数原型
3731 * pathBufferAppend(name: string, waypoints: table) -> nil
3732 *
3733 * @par Lua示例
3734 * 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}})
3735 *
3736 * @par JSON-RPC请求示例
3737 * {"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}
3738 *
3739 * @par JSON-RPC响应示例
3740 * {"id":1,"jsonrpc":"2.0","result":0}
3741 * \endchinese
3742 * \english
3743 * Add waypoints to the path buffer
3744 *
3745 * @param name Name of the path buffer
3746 * @param waypoints Waypoints
3747 * @return Returns 0 on success; otherwise returns an error code
3748 * -AUBO_INVL_ARGUMENT
3749 * -AUBO_BAD_STATE
3750 *
3751 * @throws arcs::common_interface::AuboException
3752 *
3753 * @par Python function prototype
3754 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3755 * List[List[float]]) -> int
3756 *
3757 * @par Lua function prototype
3758 * pathBufferAppend(name: string, waypoints: table) -> nil
3759 *
3760 * @par Lua example
3761 * 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}})
3762 *
3763 * @par JSON-RPC request example
3764 * {"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}
3765 *
3766 * @par JSON-RPC response example
3767 * {"id":1,"jsonrpc":"2.0","result":0}
3768 * \endenglish
3769 */
3770 int pathBufferAppend(const std::string &name,
3771 const std::vector<std::vector<double>> &waypoints);
3772
3773 /**
3774 * \chinese
3775 * 计算、优化等耗时操作,传入的参数相同时不会重新计算
3776 *
3777 * @param name 通过pathBufferAlloc新建的路径点缓存的名字
3778 * @param a 关节加速度限制,需要和机器人自由度大小相同,单位 rad/s^2
3779 * @param v 关节速度限制,需要和机器人自由度大小相同,单位 rad/s
3780 * @param t 时间 \n
3781 * pathBufferAlloc 这个接口分配内存的时候要指定类型,
3782 * 根据pathBufferAlloc这个接口的类型:\n
3783 * 类型为1时,表示运动持续时间\n
3784 * 类型为2时,表示采样时间间隔\n
3785 * 类型为3时:t表示运动持续时间\n
3786 * 若 t=0, 则由使用软件内部默认的时间(推荐使用)\n
3787 * 若 t!=0, t需要设置为 路径点数*相邻点时间间隔(points *
3788 * interval,interval >= 0.01)
3789 * @return 成功返回0;失败返回错误码
3790 * -AUBO_INVL_ARGUMENT
3791 * -AUBO_BAD_STATE
3792 *
3793 * @throws arcs::common_interface::AuboException
3794 *
3795 * @par Python函数原型
3796 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3797 * List[float], arg2: List[float], arg3: float) -> int
3798 *
3799 * @par Lua函数原型
3800 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
3801 *
3802 * @par Lua示例
3803 * pathBufferEval("traje_name",{1,1,1,1,1,1},{1,1,1,1,1,1},0.02)
3804 *
3805 * @par JSON-RPC请求示例
3806 * {"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}
3807 *
3808 * @par JSON-RPC响应示例
3809 * {"id":1,"jsonrpc":"2.0","result":0}
3810 * \endchinese
3811 * \english
3812 * Perform computation and optimization (time-consuming operations). If the
3813 * input parameters are the same, the calculation will not be repeated.
3814 *
3815 * @param name Name of the path point buffer created by pathBufferAlloc
3816 * @param a Joint acceleration limits, must match the robot DOF, unit:
3817 * rad/s^2
3818 * @param v Joint velocity limits, must match the robot DOF, unit: rad/s
3819 * @param t Time \n
3820 * When allocating memory with pathBufferAlloc, the type must be specified.
3821 * According to the type in pathBufferAlloc:\n
3822 * Type 1: t means motion duration\n
3823 * Type 2: t means sampling interval\n
3824 * Type 3: t means motion duration\n
3825 * If t=0, the internal default time is used (recommended)\n
3826 * If t!=0, t should be set to number_of_points *
3827 * interval_between_points (interval >= 0.01)
3828 * @return Returns 0 on success; otherwise returns an error code
3829 * -AUBO_INVL_ARGUMENT
3830 * -AUBO_BAD_STATE
3831 *
3832 * @throws arcs::common_interface::AuboException
3833 *
3834 * @par Python function prototype
3835 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
3836 * List[float], arg2: List[float], arg3: float) -> int
3837 *
3838 * @par Lua function prototype
3839 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
3840 *
3841 * @par Lua example
3842 * pathBufferEval("traje_name",{1,1,1,1,1,1},{1,1,1,1,1,1},0.02)
3843 *
3844 * @par JSON-RPC request example
3845 * {"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}
3846 *
3847 * @par JSON-RPC response example
3848 * {"id":1,"jsonrpc":"2.0","result":0}
3849 * \endenglish
3850 */
3851 int pathBufferEval(const std::string &name, const std::vector<double> &a,
3852 const std::vector<double> &v, double t);
3853
3854 /**
3855 * \chinese
3856 * 指定名字的buffer是否有效
3857 *
3858 * buffer需要满足三个条件有效: \n
3859 * 1、buffer存在,已经分配过内存 \n
3860 * 2、传进buffer的点要大于等于buffer的大小 \n
3861 * 3、要执行一次pathBufferEval
3862 *
3863 * @param name buffer的名字
3864 * @return 有效返回true; 无效返回false
3865 *
3866 * @throws arcs::common_interface::AuboException
3867 *
3868 * @par Python函数原型
3869 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
3870 *
3871 * @par Lua函数原型
3872 * pathBufferValid(name: string) -> boolean
3873 *
3874 * @par Lua示例
3875 * buffer_status = pathBufferValid("traje_name")
3876 *
3877 * @par JSON-RPC请求示例
3878 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
3879 *
3880 * @par JSON-RPC响应示例
3881 * {"id":1,"jsonrpc":"2.0","result":false}
3882 * \endchinese
3883 * \english
3884 * Whether the buffer with the specified name is valid
3885 *
3886 * The buffer must meet three conditions to be valid: \n
3887 * 1. The buffer exists and memory has been allocated \n
3888 * 2. The number of points passed into the buffer must be greater than or
3889 * equal to the buffer size \n
3890 * 3. pathBufferEval must be executed once
3891 *
3892 * @param name Name of the buffer
3893 * @return Returns true if valid; false otherwise
3894 *
3895 * @throws arcs::common_interface::AuboException
3896 *
3897 * @par Python function prototype
3898 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
3899 *
3900 * @par Lua function prototype
3901 * pathBufferValid(name: string) -> boolean
3902 *
3903 * @par Lua example
3904 * buffer_status = pathBufferValid("traje_name")
3905 *
3906 * @par JSON-RPC request example
3907 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
3908 *
3909 * @par JSON-RPC response example
3910 * {"id":1,"jsonrpc":"2.0","result":false}
3911 * \endenglish
3912 */
3913 bool pathBufferValid(const std::string &name);
3914
3915 /**
3916 * \chinese
3917 * 释放路径缓存
3918 *
3919 * @param name 缓存路径的名字
3920 * @return 成功返回0;失败返回错误码
3921 * -AUBO_INVL_ARGUMENT
3922 * -AUBO_BAD_STATE
3923 *
3924 * @throws arcs::common_interface::AuboException
3925 *
3926 * @par Python函数原型
3927 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
3928 *
3929 * @par Lua函数原型
3930 * pathBufferFree(name: string) -> nil
3931 *
3932 * @par Lua示例
3933 * pathBufferFree("traje_name")
3934 *
3935 * @par JSON-RPC请求示例
3936 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
3937 *
3938 * @par JSON-RPC响应示例
3939 * {"id":1,"jsonrpc":"2.0","result":-5}
3940 *
3941 * \endchinese
3942 * \english
3943 * Release path buffer
3944 *
3945 * @param name Name of the path buffer
3946 * @return Returns 0 on success; otherwise returns an error code
3947 * -AUBO_INVL_ARGUMENT
3948 * -AUBO_BAD_STATE
3949 *
3950 * @throws arcs::common_interface::AuboException
3951 *
3952 * @par Python function prototype
3953 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
3954 *
3955 * @par Lua function prototype
3956 * pathBufferFree(name: string) -> nil
3957 *
3958 * @par Lua example
3959 * pathBufferFree("traje_name")
3960 *
3961 * @par JSON-RPC request example
3962 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
3963 *
3964 * @par JSON-RPC response example
3965 * {"id":1,"jsonrpc":"2.0","result":-5}
3966 *
3967 * \endenglish
3968 */
3969 int pathBufferFree(const std::string &name);
3970
3971 /**
3972 * \chinese
3973 * 关节空间路径滤波器
3974 *
3975 * @brief pathBufferFilter
3976 *
3977 * @param name 缓存路径的名称
3978 * @param order 滤波器阶数(一般取2)
3979 * @param fd 截止频率,越小越光滑,但是延迟会大(一般取3-20)
3980 * @param fs 离散数据的采样频率(一般取20-500)
3981 *
3982 * @return 成功返回0
3983 *
3984 * @throws arcs::common_interface::AuboException
3985 *
3986 * @par Python函数原型
3987 * pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
3988 * arg2: float, arg3: float) -> int
3989 *
3990 * @par Lua函数原型
3991 * pathBufferFilter(name: string, order: number, fd: number, fs:number) ->
3992 * nil
3993 *
3994 * @par Lua示例
3995 * pathBufferFilter("traje_name",2,5,125)
3996 *
3997 * \endchinese
3998 * \english
3999 * Joint space path filter
4000 *
4001 * @brief pathBufferFilter
4002 *
4003 * @param name Name of the path buffer
4004 * @param order Filter order (usually 2)
4005 * @param fd Cutoff frequency, the smaller the smoother but with more delay
4006 * (usually 3-20)
4007 * @param fs Sampling frequency of discrete data (usually 20-500)
4008 *
4009 * @return Returns 0 on success
4010 *
4011 * @throws arcs::common_interface::AuboException
4012 *
4013 * @par Python function prototype
4014 * pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
4015 * arg2: float, arg3: float) -> int
4016 *
4017 * @par Lua function prototype
4018 * pathBufferFilter(name: string, order: number, fd: number, fs:number) ->
4019 * nil
4020 *
4021 * @par Lua example
4022 * pathBufferFilter("traje_name",2,5,125)
4023 *
4024 * \endenglish
4025 */
4026 int pathBufferFilter(const std::string &name, int order, double fd,
4027 double fs);
4028
4029 /**
4030 * \chinese
4031 * 列出所有缓存路径的名字
4032 *
4033 * @return 返回所有缓存路径的名字
4034 *
4035 * @throws arcs::common_interface::AuboException
4036 *
4037 * @par Python函数原型
4038 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
4039 *
4040 * @par Lua函数原型
4041 * pathBufferList() -> table
4042 *
4043 * @par Lua示例
4044 * Buffer_table = pathBufferList()
4045 *
4046 * @par JSON-RPC请求示例
4047 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
4048 *
4049 * @par JSON-RPC响应示例
4050 * {"id":1,"jsonrpc":"2.0","result":[]}
4051 *
4052 * \endchinese
4053 * \english
4054 * List all cached path names
4055 *
4056 * @return Returns all cached path names
4057 *
4058 * @throws arcs::common_interface::AuboException
4059 *
4060 * @par Python function prototype
4061 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
4062 *
4063 * @par Lua function prototype
4064 * pathBufferList() -> table
4065 *
4066 * @par Lua example
4067 * Buffer_table = pathBufferList()
4068 *
4069 * @par JSON-RPC request example
4070 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
4071 *
4072 * @par JSON-RPC response example
4073 * {"id":1,"jsonrpc":"2.0","result":[]}
4074 *
4075 * \endenglish
4076 */
4077 std::vector<std::string> pathBufferList();
4078
4079 /**
4080 * \chinese
4081 * 执行缓存的路径
4082 *
4083 * @param name 缓存路径的名字
4084 * @return 成功返回0;失败返回错误码
4085 * -AUBO_INVL_ARGUMENT
4086 * -AUBO_BAD_STATE
4087 *
4088 * @throws arcs::common_interface::AuboException
4089 *
4090 * @par Python函数原型
4091 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4092 *
4093 * @par Lua函数原型
4094 * movePathBuffer(name: string) -> nil
4095 *
4096 * @par Lua示例
4097 * movePathBuffer("traje_name")
4098 *
4099 * @par JSON-RPC请求示例
4100 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
4101 *
4102 * @par JSON-RPC响应示例
4103 * {"id":1,"jsonrpc":"2.0","result":0}
4104 * \endchinese
4105 * \english
4106 * Execute the cached path
4107 *
4108 * @param name Name of the cached path
4109 * @return Returns 0 on success; otherwise returns an error code
4110 * -AUBO_INVL_ARGUMENT
4111 * -AUBO_BAD_STATE
4112 *
4113 * @throws arcs::common_interface::AuboException
4114 *
4115 * @par Python function prototype
4116 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
4117 *
4118 * @par Lua function prototype
4119 * movePathBuffer(name: string) -> nil
4120 *
4121 * @par Lua example
4122 * movePathBuffer("traje_name")
4123 *
4124 * @par JSON-RPC request example
4125 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
4126 *
4127 * @par JSON-RPC response example
4128 * {"id":1,"jsonrpc":"2.0","result":0}
4129 * \endenglish
4130 */
4131 int movePathBuffer(const std::string &name);
4132
4133 /**
4134 * \chinese
4135 * 相贯线接口
4136 *
4137 * @param pose 由三个示教位姿组成(首先需要运动到起始点,起始点的要求:过主圆柱
4138 * 柱体轴心且与子圆柱体轴线平行的平面与子圆柱体在底部的交点)
4139 * p1:过子圆柱体轴线且与大圆柱体轴线平行的平面,与小圆柱体在左侧顶部的交点
4140 * p2:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在左侧底部的交点
4141 * p3:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在右侧底部的交点
4142 * @param v 速度
4143 * @param a 加速度
4144 * @param main_pipe_radius 主圆柱体半径
4145 * @param sub_pipe_radius 子圆柱体半径
4146 * @param normal_distance 两圆柱体轴线距离
4147 * @param normal_alpha 两圆柱体轴线的夹角
4148 *
4149 * @return 成功返回0;失败返回错误码
4150 * AUBO_BUSY
4151 * AUBO_BAD_STATE
4152 * -AUBO_INVL_ARGUMENT
4153 * -AUBO_BAD_STATE
4154 *
4155 * @throws arcs::common_interface::AuboException
4156 *
4157 * @par Python函数原型
4158 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
4159 * float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float)
4160 * -> int
4161 *
4162 * @par Lua函数原型
4163 * moveIntersection(poses: table, a: number, v: number,
4164 * main_pipe_radius: number, sub_pipe_radius: number, normal_distance:
4165 * number, normal_alpha: number) -> nil \endchinese \english Intersection
4166 * interface
4167 *
4168 * @param poses Consists of three taught poses (first, move to the starting
4169 * point. The starting point requirement: the intersection of the plane
4170 * passing through the main cylinder axis and parallel to the sub-cylinder
4171 * axis with the sub-cylinder at the bottom) p1: Intersection of the plane
4172 * passing through the sub-cylinder axis and parallel to the main cylinder
4173 * axis with the sub-cylinder at the left top p2: Intersection of the plane
4174 * passing through the sub-cylinder axis and parallel to the main cylinder
4175 * axis with the main cylinder at the left bottom p3: Intersection of the
4176 * plane passing through the sub-cylinder axis and parallel to the main
4177 * cylinder axis with the main cylinder at the right bottom
4178 * @param v Velocity
4179 * @param a Acceleration
4180 * @param main_pipe_radius Main cylinder radius
4181 * @param sub_pipe_radius Sub cylinder radius
4182 * @param normal_distance Distance between the two cylinder axes
4183 * @param normal_alpha Angle between the two cylinder axes
4184 *
4185 * @return Returns 0 on success; otherwise returns an error code
4186 * AUBO_BUSY
4187 * AUBO_BAD_STATE
4188 * -AUBO_INVL_ARGUMENT
4189 * -AUBO_BAD_STATE
4190 *
4191 * @throws arcs::common_interface::AuboException
4192 *
4193 * @par Python function prototype
4194 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
4195 * float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float)
4196 * -> int
4197 *
4198 * @par Lua function prototype
4199 * moveIntersection(poses: table, a: number, v: number,
4200 * main_pipe_radius: number, sub_pipe_radius: number, normal_distance:
4201 * number, normal_alpha: number) -> nil \endenglish
4202 */
4203 int moveIntersection(const std::vector<std::vector<double>> &poses,
4204 double a, double v, double main_pipe_radius,
4205 double sub_pipe_radius, double normal_distance,
4206 double normal_alpha);
4207 /**
4208 * \chinese
4209 * 关节空间停止运动
4210 *
4211 * @param acc 关节加速度,单位: rad/s^2
4212 * @return 成功返回0;失败返回错误码
4213 * AUBO_BUSY
4214 * AUBO_BAD_STATE
4215 * -AUBO_INVL_ARGUMENT
4216 * -AUBO_BAD_STATE
4217 *
4218 * @throws arcs::common_interface::AuboException
4219 *
4220 * @par Python函数原型
4221 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4222 *
4223 * @par Lua函数原型
4224 * stopJoint(acc: number) -> nil
4225 *
4226 * @par Lua示例
4227 * stopJoint(2)
4228 *
4229 * @par JSON-RPC请求示例
4230 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
4231 *
4232 * @par JSON-RPC响应示例
4233 * {"id":1,"jsonrpc":"2.0","result":0}
4234 *
4235 * \endchinese
4236 * \english
4237 * Stop motion in joint space
4238 *
4239 * @param acc Joint acceleration, unit: rad/s^2
4240 * @return Returns 0 on success; otherwise returns an error code
4241 * AUBO_BUSY
4242 * AUBO_BAD_STATE
4243 * -AUBO_INVL_ARGUMENT
4244 * -AUBO_BAD_STATE
4245 *
4246 * @throws arcs::common_interface::AuboException
4247 *
4248 * @par Python function prototype
4249 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4250 *
4251 * @par Lua function prototype
4252 * stopJoint(acc: number) -> nil
4253 *
4254 * @par Lua example
4255 * stopJoint(2)
4256 *
4257 * @par JSON-RPC request example
4258 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
4259 *
4260 * @par JSON-RPC response example
4261 * {"id":1,"jsonrpc":"2.0","result":0}
4262 *
4263 * \endenglish
4264 */
4265 int stopJoint(double acc);
4266
4267 /**
4268 * \chinese
4269 * 关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
4270 *
4271 * @param acc 关节加速度,单位: rad/s^2
4272 * @return 成功返回0;失败返回错误码
4273 * AUBO_BUSY
4274 * AUBO_BAD_STATE
4275 * -AUBO_INVL_ARGUMENT
4276 * -AUBO_BAD_STATE
4277 *
4278 * @throws arcs::common_interface::AuboException
4279 *
4280 * @par Python函数原型
4281 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4282 *
4283 * @par Lua函数原型
4284 * resumeStopJoint(acc: number) -> nil
4285 *
4286 * @par Lua示例
4287 * resumeStopJoint(31)
4288 *
4289 * @par JSON-RPC请求示例
4290 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
4291 *
4292 * @par JSON-RPC响应示例
4293 * {"id":1,"jsonrpc":"2.0","result":-1}
4294 *
4295 * \endchinese
4296 * \english
4297 * Stop motion in joint space (used after moving to a safe position via
4298 * resumeSpeedJoint following a collision during process execution)
4299 *
4300 * @param acc Joint acceleration, unit: rad/s^2
4301 * @return Returns 0 on success; otherwise returns an error code
4302 * AUBO_BUSY
4303 * AUBO_BAD_STATE
4304 * -AUBO_INVL_ARGUMENT
4305 * -AUBO_BAD_STATE
4306 *
4307 * @throws arcs::common_interface::AuboException
4308 *
4309 * @par Python function prototype
4310 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
4311 *
4312 * @par Lua function prototype
4313 * resumeStopJoint(acc: number) -> nil
4314 *
4315 * @par Lua example
4316 * resumeStopJoint(31)
4317 *
4318 * @par JSON-RPC request example
4319 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
4320 *
4321 * @par JSON-RPC response example
4322 * {"id":1,"jsonrpc":"2.0","result":-1}
4323 *
4324 * \endenglish
4325 */
4326 int resumeStopJoint(double acc);
4327
4328 /**
4329 * \chinese
4330 * 停止 moveLine/moveCircle 等在笛卡尔空间的运动
4331 *
4332 * @param acc 工具加速度, 单位: m/s^2
4333 * @param acc_rot
4334 * @return 成功返回0;失败返回错误码
4335 * AUBO_BUSY
4336 * AUBO_BAD_STATE
4337 * -AUBO_INVL_ARGUMENT
4338 * -AUBO_BAD_STATE
4339 *
4340 * @throws arcs::common_interface::AuboException
4341 *
4342 * @par Python函数原型
4343 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
4344 *
4345 * @par Lua函数原型
4346 * stopLine(acc: number, acc_rot: number) -> nil
4347 *
4348 * @par Lua示例
4349 * stopLine(10,10)
4350 *
4351 * @par JSON-RPC请求示例
4352 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
4353 *
4354 * @par JSON-RPC响应示例
4355 * {"id":1,"jsonrpc":"2.0","result":0}
4356 *
4357 * \endchinese
4358 * \english
4359 * Stop motions in Cartesian space such as moveLine/moveCircle.
4360 *
4361 * @param acc Tool acceleration, unit: m/s^2
4362 * @param acc_rot
4363 * @return Returns 0 on success; otherwise returns an error code
4364 * AUBO_BUSY
4365 * AUBO_BAD_STATE
4366 * -AUBO_INVL_ARGUMENT
4367 * -AUBO_BAD_STATE
4368 *
4369 * @throws arcs::common_interface::AuboException
4370 *
4371 * @par Python function prototype
4372 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
4373 *
4374 * @par Lua function prototype
4375 * stopLine(acc: number, acc_rot: number) -> nil
4376 *
4377 * @par Lua example
4378 * stopLine(10,10)
4379 *
4380 * @par JSON-RPC request example
4381 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
4382 *
4383 * @par JSON-RPC response example
4384 * {"id":1,"jsonrpc":"2.0","result":0}
4385 *
4386 * \endenglish
4387 */
4388 int stopLine(double acc, double acc_rot);
4389
4390 /**
4391 * \chinese
4392 * 笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
4393 *
4394 * @param acc 位置加速度, 单位: m/s^2
4395 * @param acc_rot 姿态加速度,单位: rad/s^2
4396 * @return 成功返回0;失败返回错误码
4397 * AUBO_BUSY
4398 * AUBO_BAD_STATE
4399 * -AUBO_INVL_ARGUMENT
4400 * -AUBO_BAD_STATE
4401 *
4402 * @throws arcs::common_interface::AuboException
4403 *
4404 * @par Python函数原型
4405 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
4406 * -> int
4407 *
4408 * @par Lua函数原型
4409 * resumeStopLine(acc: number, acc_rot: number) -> nil
4410 *
4411 * @par Lua示例
4412 * resumeStopLine(10,10)
4413 *
4414 * @par JSON-RPC请求示例
4415 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
4416 *
4417 * @par JSON-RPC响应示例
4418 * {"id":1,"jsonrpc":"2.0","result":-1}
4419 *
4420 * \endchinese
4421 * \english
4422 * Stop motion in Cartesian space (used after moving to a safe position via
4423 * resumeSpeedLine following a collision during process execution)
4424 *
4425 * @param acc Position acceleration, unit: m/s^2
4426 * @param acc_rot Orientation acceleration, unit: rad/s^2
4427 * @return Returns 0 on success; otherwise returns an error code
4428 * AUBO_BUSY
4429 * AUBO_BAD_STATE
4430 * -AUBO_INVL_ARGUMENT
4431 * -AUBO_BAD_STATE
4432 *
4433 * @throws arcs::common_interface::AuboException
4434 *
4435 * @par Python function prototype
4436 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
4437 * -> int
4438 *
4439 * @par Lua function prototype
4440 * resumeStopLine(acc: number, acc_rot: number) -> nil
4441 *
4442 * @par Lua example
4443 * resumeStopLine(10,10)
4444 *
4445 * @par JSON-RPC request example
4446 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
4447 *
4448 * @par JSON-RPC response example
4449 * {"id":1,"jsonrpc":"2.0","result":-1}
4450 *
4451 * \endenglish
4452 */
4453 int resumeStopLine(double acc, double acc_rot);
4454
4455 /**
4456 * \chinese
4457 * 开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params
4458 * 进行摆动
4459 *
4460 * @param params Json字符串用于定义摆动参数
4461 * {
4462 * "type": <string>, // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
4463 * "step": <num>,
4464 * "amplitude": {<num>,<num>},
4465 * "hold_distance": {<num>,<num>},
4466 * "angle": <num>
4467 * "direction": <num>
4468 * }
4469 * @return 成功返回0;失败返回错误码
4470 * AUBO_BUSY
4471 * AUBO_BAD_STATE
4472 * -AUBO_INVL_ARGUMENT
4473 * -AUBO_BAD_STATE
4474 *
4475 * @throws arcs::common_interface::AuboException
4476 * \endchinese
4477 * \english
4478 * Start weaving: moveLine/moveCircle between weaveStart and weaveEnd will
4479 * perform weaving according to params
4480 *
4481 * @param params Json string to define weaving parameters
4482 * {
4483 * "type": <string>, // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
4484 * "step": <num>,
4485 * "amplitude": {<num>,<num>},
4486 * "hold_distance": {<num>,<num>},
4487 * "angle": <num>
4488 * "direction": <num>
4489 * }
4490 * @return Returns 0 on success; otherwise returns an error code
4491 * AUBO_BUSY
4492 * AUBO_BAD_STATE
4493 * -AUBO_INVL_ARGUMENT
4494 * -AUBO_BAD_STATE
4495 *
4496 * @throws arcs::common_interface::AuboException
4497 * \endenglish
4498 */
4499 int weaveStart(const std::string &params);
4500
4501 /**
4502 * \chinese
4503 * 结束摆动
4504 *
4505 * @return 成功返回0;失败返回错误码
4506 * AUBO_BUSY
4507 * AUBO_BAD_STATE
4508 * -AUBO_BAD_STATE
4509 *
4510 * @throws arcs::common_interface::AuboException
4511 *
4512 * @par JSON-RPC请求示例
4513 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
4514 *
4515 * @par JSON-RPC响应示例
4516 * {"id":1,"jsonrpc":"2.0","result":0}
4517 *
4518 * \endchinese
4519 * \english
4520 * End weaving
4521 *
4522 * @return Returns 0 on success; otherwise returns an error code
4523 * AUBO_BUSY
4524 * AUBO_BAD_STATE
4525 * -AUBO_BAD_STATE
4526 *
4527 * @throws arcs::common_interface::AuboException
4528 *
4529 * @par JSON-RPC request example
4530 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
4531 *
4532 * @par JSON-RPC response example
4533 * {"id":1,"jsonrpc":"2.0","result":0}
4534 *
4535 * \endenglish
4536 */
4538
4539 /**
4540 * \chinese
4541 * 设置未来路径上点的采样时间间隔
4542 *
4543 * @param sample_time 采样时间间隔 单位: m/s^2
4544 * @return 成功返回0;失败返回错误码
4545 * AUBO_BUSY
4546 * AUBO_BAD_STATE
4547 * -AUBO_INVL_ARGUMENT
4548 * -AUBO_BAD_STATE
4549 *
4550 * @throws arcs::common_interface::AuboException
4551 * \endchinese
4552 * \english
4553 * Set the sampling interval for points on the future path
4554 *
4555 * @param sample_time Sampling interval, unit: m/s^2
4556 * @return Returns 0 on success; otherwise returns an error code
4557 * AUBO_BUSY
4558 * AUBO_BAD_STATE
4559 * -AUBO_INVL_ARGUMENT
4560 * -AUBO_BAD_STATE
4561 *
4562 * @throws arcs::common_interface::AuboException
4563 * \endenglish
4564 */
4565 int setFuturePointSamplePeriod(double sample_time);
4566
4567 /**
4568 * \chinese
4569 * 获取未来路径上的轨迹点
4570 *
4571 * @return 路点(100ms * 10)
4572 *
4573 * @throws arcs::common_interface::AuboException
4574 *
4575 * @par JSON-RPC请求示例
4576 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
4577 *
4578 * @par JSON-RPC响应示例
4579 * {"id":1,"jsonrpc":"2.0","result":[]}
4580 *
4581 * \endchinese
4582 * \english
4583 * Get trajectory points on the future path
4584 *
4585 * @return Waypoints (100ms * 10)
4586 *
4587 * @throws arcs::common_interface::AuboException
4588 *
4589 * @par JSON-RPC request example
4590 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
4591 *
4592 * @par JSON-RPC response example
4593 * {"id":1,"jsonrpc":"2.0","result":[]}
4594 *
4595 * \endenglish
4596 */
4597 std::vector<std::vector<double>> getFuturePathPointsJoint();
4598
4599 /**
4600 * \chinese
4601 * 设置传送带编码器参数
4602 *
4603 * @param encoder_id 预留
4604 * @param tick_per_meter
4605 * 线性传送带===>一米的脉冲值
4606 * 环形传送带===>一圈的脉冲值
4607 * @return
4608 *
4609 * @throws arcs::common_interface::AuboException
4610 *
4611 * @par Python函数原型
4612 * setConveyorTrackEncoder(self: pyaubo_sdk.MotionControl) -> int
4613 *
4614 * @par Lua函数原型
4615 * setConveyorTrackEncoder(encoder_id: bumber,tick_per_meter: number) -> int
4616 *
4617 * @par Lua示例
4618 * num = setConveyorTrackEncoder(1,40000)
4619 *
4620 * @par JSON-RPC请求示例
4621 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackEncoder","params":[1,40000],"id":1}
4622 *
4623 * @par JSON-RPC响应示例
4624 * {"id":1,"jsonrpc":"2.0","result":0}
4625 *
4626 * \endchinese
4627 * \english
4628 * Set conveyor encoder parameters
4629 *
4630 * @param encoder_id Reserved
4631 * @param tick_per_meter
4632 * Linear conveyor: pulses per meter
4633 * Circular conveyor: pulses per revolution
4634 * @return
4635 *
4636 * @throws arcs::common_interface::AuboException
4637 *
4638 * @par Python function prototype
4639 * setConveyorTrackEncoder(self: pyaubo_sdk.MotionControl) -> int
4640 *
4641 * @par Lua function prototype
4642 * setConveyorTrackEncoder(encoder_id: bumber,tick_per_meter: number) -> int
4643 *
4644 * @par Lua example
4645 * num = setConveyorTrackEncoder(1,40000)
4646 *
4647 * @par JSON-RPC request example
4648 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackEncoder","params":[1,40000],"id":1}
4649 *
4650 * @par JSON-RPC response example
4651 * {"id":1,"jsonrpc":"2.0","result":0}
4652 *
4653 * \endenglish
4654 */
4655 int setConveyorTrackEncoder(int encoder_id, int tick_per_meter);
4656 /**
4657 * \chinese
4658 * 圆形传送带跟随
4659 *
4660 * @note 暂未实现
4661 *
4662 * @param encoder_id
4663 * 0-集成传感器
4664 * @param rotate_tool
4665 * @return
4666 *
4667 * @throws arcs::common_interface::AuboException
4668 * \endchinese
4669 * \english
4670 * Circular conveyor tracking
4671 *
4672 * @note Not implemented yet
4673 *
4674 * @param encoder_id
4675 * 0 - integrated sensor
4676 * @param rotate_tool
4677 * @return
4678 *
4679 * @throws arcs::common_interface::AuboException
4680 * \endenglish
4681 */
4682 int conveyorTrackCircle(int encoder_id, const std::vector<double> &center,
4683 bool rotate_tool);
4684
4685 /**
4686 * \chinese
4687 * 线性传送带跟随
4688 *
4689 * @param encoder_id 预留
4690 * @param direction 传送带相对机器人基坐标系的移动方向
4691 * @return
4692 *
4693 * @throws arcs::common_interface::AuboException
4694 *
4695 * @par Python函数原型
4696 * conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
4697 *
4698 * @par Lua函数原型
4699 * conveyorTrackLine -> int
4700 *
4701 * @par JSON-RPC请求示例
4702 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
4703 *
4704 * @par JSON-RPC响应示例
4705 * {"id":1,"jsonrpc":"2.0","result":0}
4706 *
4707 * \endchinese
4708 * \english
4709 * Linear conveyor tracking
4710 *
4711 * @param encoder_id Reserved
4712 * @param direction The movement direction of the conveyor relative to the
4713 * robot base coordinate system
4714 * @return
4715 *
4716 * @throws arcs::common_interface::AuboException
4717 *
4718 * @par Python function prototype
4719 * conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
4720 *
4721 * @par Lua function prototype
4722 * conveyorTrackLine -> int
4723 *
4724 * @par JSON-RPC request example
4725 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
4726 *
4727 * @par JSON-RPC response example
4728 * {"id":1,"jsonrpc":"2.0","result":0}
4729 *
4730 * \endenglish
4731 */
4732 int conveyorTrackLine(int encoder_id, const std::vector<double> &direction);
4733
4734 /**
4735 * \chinese
4736 * 终止传送带跟随
4737 *
4738 * @param encoder_id 预留
4739 * @param a 预留
4740 * @return
4741 *
4742 * @throws arcs::common_interface::AuboException
4743 *
4744 * @par Python函数原型
4745 * conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
4746 *
4747 * @par Lua函数原型
4748 * conveyorTrackStop -> int
4749 *
4750 * @par JSON-RPC请求示例
4751 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":[0,1.0],"id":1}
4752 *
4753 * @par JSON-RPC响应示例
4754 * {"id":1,"jsonrpc":"2.0","result":0}
4755 * \endchinese
4756 * \english
4757 * Stop conveyor tracking
4758 *
4759 * @param encoder_id Reserved
4760 * @param a Reserved
4761 * @return
4762 *
4763 * @throws arcs::common_interface::AuboException
4764 *
4765 * @par Python function prototype
4766 * conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
4767 *
4768 * @par Lua function prototype
4769 * conveyorTrackStop -> int
4770 *
4771 * @par JSON-RPC request example
4772 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":[0,1.0],"id":1}
4773 *
4774 * @par JSON-RPC response example
4775 * {"id":1,"jsonrpc":"2.0","result":0}
4776 * \endenglish
4777 */
4778 int conveyorTrackStop(int encoder_id, double a);
4779
4780 /**
4781 * \chinese
4782 * 切换传送带追踪物品
4783 * 如果当前物品正在处于跟踪状态,则将该物品出队,不再跟踪,返回true
4784 * 如果没有物品正在处于跟踪状态,返回false
4785 *
4786 * @return
4787 *
4788 * @throws arcs::common_interface::AuboException
4789 *
4790 * @param encoder_id 预留
4791 *
4792 * @par Python函数原型
4793 * conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
4794 *
4795 * @par Lua函数原型
4796 * conveyorTrackSwitch() -> boolean
4797 *
4798 * @par JSON-RPC请求示例
4799 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
4800 *
4801 * @par JSON-RPC响应示例
4802 * {"id":1,"jsonrpc":"2.0","result":true}
4803 *
4804 * \endchinese
4805 * \english
4806 * Switch conveyor tracking item.
4807 * If the current item is being tracked, it will be dequeued and no longer
4808 * tracked, returning true. If no item is currently being tracked, returns
4809 * false.
4810 *
4811 * @return
4812 *
4813 * @throws arcs::common_interface::AuboException
4814 *
4815 * @param encoder_id Reserved
4816 *
4817 * @par Python function prototype
4818 * conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
4819 *
4820 * @par Lua function prototype
4821 * conveyorTrackSwitch() -> boolean
4822 *
4823 * @par JSON-RPC request example
4824 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
4825 *
4826 * @par JSON-RPC response example
4827 * {"id":1,"jsonrpc":"2.0","result":true}
4828 *
4829 * \endenglish
4830 */
4831 bool conveyorTrackSwitch(int encoder_id);
4832
4833 /**
4834 * \chinese
4835 * 传送带上是否有物品可以跟踪
4836 * @param encoder_id 预留
4837 * @return
4838 * 如果队列第一个物品为跟踪状态,返回true
4839 * 如果队列第一个物品不为跟踪状态,则对队列中其余物品进行是否在启动窗口内的判断
4840 * 超出启动窗口则出队,直到有物品处于启动窗口内,使其变为跟踪状态返回true,
4841 * 队列中没有一个物品在启动窗口内返回false
4842 *
4843 * @throws arcs::common_interface::AuboException
4844 *
4845 * @par Python函数原型
4846 * hasItemOnConveyorToTrack(self: pyaubo_sdk.MotionControl) -> bool
4847 *
4848 * @par Lua函数原型
4849 * hasItemOnConveyorToTrack() -> boolean
4850 *
4851 * @par JSON-RPC请求示例
4852 * {"jsonrpc":"2.0","method":"rob1.MotionControl.hasItemOnConveyorToTrack","params":[0],"id":1}
4853 *
4854 * @par JSON-RPC响应示例
4855 * {"id":1,"jsonrpc":"2.0","result":{true}}
4856 * \endchinese
4857 * \english
4858 * Whether there is an item on the conveyor that can be tracked
4859 * @param encoder_id Reserved
4860 * @return
4861 * If the first item in the queue is in tracking state, returns true.
4862 * If the first item is not in tracking state, checks the rest of the queue
4863 * for items within the start window. Items outside the start window are
4864 * dequeued until an item is found within the window, which is then set to
4865 * tracking state and returns true. If no item in the queue is within the
4866 * start window, returns false.
4867 *
4868 * @throws arcs::common_interface::AuboException
4869 *
4870 * @par Python function prototype
4871 * hasItemOnConveyorToTrack(self: pyaubo_sdk.MotionControl) -> bool
4872 *
4873 * @par Lua function prototype
4874 * hasItemOnConveyorToTrack() -> boolean
4875 *
4876 * @par JSON-RPC request example
4877 * {"jsonrpc":"2.0","method":"rob1.MotionControl.hasItemOnConveyorToTrack","params":[0],"id":1}
4878 *
4879 * @par JSON-RPC response example
4880 * {"id":1,"jsonrpc":"2.0","result":{true}}
4881 * \endenglish
4882 */
4883 bool hasItemOnConveyorToTrack(int encoder_id);
4884
4885 /**
4886 * \chinese
4887 * 增加传送带队列
4888 *
4889 * @param encoder_id 预留
4890 * @param item_id 物品ID
4891 * @param offset 当前物品点位相对于模板物品点位的偏移值
4892 * @return
4893 *
4894 * @throws arcs::common_interface::AuboException
4895 *
4896 * @par Python函数原型
4897 * conveyorTrackCreatItem(self: pyaubo_sdk.MotionControl, arg0: int,
4898 * arg1:int, arg2: List[float]) -> int
4899 *
4900 * @par Lua函数原型
4901 * conveyorTrackCreatItem(encoder_id: number, item_id: number, offset:
4902 * table) -> number
4903 *
4904 * @par JSON-RPC请求示例
4905 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackCreatItem","params":[0,2,
4906 * {0.0,0.0,0.0,0.0,0.0,0.0}],"id":1}
4907 *
4908 * @par JSON-RPC响应示例
4909 * {"id":1,"jsonrpc":"2.0","result":0.0}
4910 * \endchinese
4911 * \english
4912 * Add an item to the conveyor queue
4913 *
4914 * @param encoder_id Reserved
4915 * @param item_id Item ID
4916 * @param offset Offset of the current item position relative to the
4917 * template item position
4918 * @return
4919 *
4920 * @throws arcs::common_interface::AuboException
4921 *
4922 * @par Python function prototype
4923 * conveyorTrackCreatItem(self: pyaubo_sdk.MotionControl, arg0: int,
4924 * arg1:int, arg2: List[float]) -> int
4925 *
4926 * @par Lua function prototype
4927 * conveyorTrackCreatItem(encoder_id: number, item_id: number, offset:
4928 * table) -> number
4929 *
4930 * @par JSON-RPC request example
4931 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackCreatItem","params":[0,2,
4932 * {0.0,0.0,0.0,0.0,0.0,0.0}],"id":1}
4933 *
4934 * @par JSON-RPC response example
4935 * {"id":1,"jsonrpc":"2.0","result":0.0}
4936 * \endenglish
4937 */
4938 int conveyorTrackCreatItem(int encoder_id, int item_id,
4939 const std::vector<double> &offset);
4940 /**
4941 * \chinese
4942 * 设置传送带跟踪的补偿值
4943 *
4944 * @param encoder_id 预留
4945 * @param comp 传送带补偿值
4946 * @return
4947 *
4948 * @throws arcs::common_interface::AuboException
4949 *
4950 * @par Python函数原型
4951 * setConveyorTrackCompensate(self: pyaubo_sdk.MotionControl, arg0: int,
4952 * arg1: float) -> int
4953 *
4954 * @par Lua函数原型
4955 * setConveyorTrackCompensate(comp: number) -> number
4956 *
4957 * @par JSON-RPC请求示例
4958 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackCompensate","params":[0,
4959 * 0.1],"id":1}
4960 *
4961 * @par JSON-RPC响应示例
4962 * {"id":1,"jsonrpc":"2.0","result":0}
4963 * \endchinese
4964 * \english
4965 * Set the compensation value for conveyor tracking
4966 *
4967 * @param encoder_id Reserved
4968 * @param comp Conveyor compensation value
4969 * @return
4970 *
4971 * @throws arcs::common_interface::AuboException
4972 *
4973 * @par Python function prototype
4974 * setConveyorTrackCompensate(self: pyaubo_sdk.MotionControl, arg0: int,
4975 * arg1: float) -> int
4976 *
4977 * @par Lua function prototype
4978 * setConveyorTrackCompensate(comp: number) -> number
4979 *
4980 * @par JSON-RPC request example
4981 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackCompensate","params":[0,
4982 * 0.1],"id":1}
4983 *
4984 * @par JSON-RPC response example
4985 * {"id":1,"jsonrpc":"2.0","result":0}
4986 * \endenglish
4987 */
4988 int setConveyorTrackCompensate(int encoder_id, double comp);
4989
4990 /**
4991 * \chinese
4992 * 判断传送带与机械臂之间是否达到相对静止
4993 *
4994 * @param encoder_id 预留
4995 * @return
4996 *
4997 * @throws arcs::common_interface::AuboException
4998 *
4999 * @par Python函数原型
5000 * isConveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5001 *
5002 * @par Lua函数原型
5003 * isConveyorTrackSync(encoder_id: number) -> bool
5004 *
5005 * @par JSON-RPC请求示例
5006 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackSync","params":[0],"id":1}
5007 *
5008 * @par JSON-RPC响应示例
5009 * {"id":1,"jsonrpc":"2.0","result":false}
5010 *
5011 * \endchinese
5012 * \english
5013 * Determine whether the conveyor and the robot arm have reached relative
5014 * rest
5015 *
5016 * @param encoder_id Reserved
5017 * @return
5018 *
5019 * @throws arcs::common_interface::AuboException
5020 *
5021 * @par Python function prototype
5022 * isConveyorTrackSync(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5023 *
5024 * @par Lua function prototype
5025 * isConveyorTrackSync(encoder_id: number) -> bool
5026 *
5027 * @par JSON-RPC request example
5028 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackSync","params":[0],"id":1}
5029 *
5030 * @par JSON-RPC response example
5031 * {"id":1,"jsonrpc":"2.0","result":false}
5032 *
5033 * \endenglish
5034 */
5035 bool isConveyorTrackSync(int encoder_id);
5036
5037 /**
5038 * \chinese
5039 * 设置传送带跟踪的最大距离限制
5040 *
5041 * @param encoder_id 预留
5042 * @param limit
5043 * 传送带跟踪的最大距离限制,单位:米
5044 * @return
5045 *
5046 * @throws arcs::common_interface::AuboException
5047 *
5048 * @par Python函数原型
5049 * setConveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
5050 * double) -> int
5051 *
5052 * @par Lua函数原型
5053 * setConveyorTrackLimit(encoder_id: number, limit: number) -> int
5054 *
5055 * @par JSON-RPC请求示例
5056 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackLimit","params":[0,
5057 * 1.5],"id":1}
5058 *
5059 * @par JSON-RPC响应示例
5060 * {"id":1,"jsonrpc":"2.0","result":0}
5061 * \endchinese
5062 * \english
5063 * Set the maximum distance limit for conveyor tracking
5064 *
5065 * @param encoder_id Reserved
5066 * @param limit
5067 * Maximum distance limit for conveyor tracking, unit: meter
5068 * @return
5069 *
5070 * @throws arcs::common_interface::AuboException
5071 *
5072 * @par Python function prototype
5073 * setConveyorTrackLimit(self: pyaubo_sdk.MotionControl, arg0: int, arg1:
5074 * double) -> int
5075 *
5076 * @par Lua function prototype
5077 * setConveyorTrackLimit(encoder_id: number, limit: number) -> int
5078 *
5079 * @par JSON-RPC request example
5080 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackLimit","params":[0,
5081 * 1.5],"id":1}
5082 *
5083 * @par JSON-RPC response example
5084 * {"id":1,"jsonrpc":"2.0","result":0}
5085 * \endenglish
5086 */
5087 int setConveyorTrackLimit(int encoder_id, double limit);
5088
5089 /**
5090 * \chinese
5091 * 设置传送带跟踪的启动窗口
5092 *
5093 * @param encoder_id 预留
5094 * @param min_window
5095 * 启动窗口的起始位置,单位:米
5096 * @param max_window
5097 * 启动窗口的结束位置,单位:米
5098 * @return
5099 *
5100 * @throws arcs::common_interface::AuboException
5101 *
5102 * @par Python函数原型
5103 * setConveyorTrackStartWindow(self: pyaubo_sdk.MotionControl, arg0: int,
5104 * arg1: double, arg2: double) -> int
5105 *
5106 * @par Lua函数原型
5107 * setConveyorTrackStartWindow(encoder_id: number, min_window: number,
5108 * max_window: number) -> int
5109 *
5110 * @par JSON-RPC请求示例
5111 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackStartWindow","params":[0,
5112 * 0.2, 1.0],"id":1}
5113 *
5114 * @par JSON-RPC响应示例
5115 * {"id":1,"jsonrpc":"2.0","result":0}
5116 *
5117 * \endchinese
5118 * \english
5119 * Set the start window for conveyor tracking
5120 *
5121 * @param encoder_id Reserved
5122 * @param min_window
5123 * Start position of the window, unit: meter
5124 * @param max_window
5125 * End position of the window, unit: meter
5126 * @return
5127 *
5128 * @throws arcs::common_interface::AuboException
5129 *
5130 * @par Python function prototype
5131 * setConveyorTrackStartWindow(self: pyaubo_sdk.MotionControl, arg0: int,
5132 * arg1: double, arg2: double) -> int
5133 *
5134 * @par Lua function prototype
5135 * setConveyorTrackStartWindow(encoder_id: number, min_window: number,
5136 * max_window: number) -> int
5137 *
5138 * @par JSON-RPC request example
5139 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackStartWindow","params":[0,
5140 * 0.2, 1.0],"id":1}
5141 *
5142 * @par JSON-RPC response example
5143 * {"id":1,"jsonrpc":"2.0","result":0}
5144 *
5145 * \endenglish
5146 */
5147 int setConveyorTrackStartWindow(int encoder_id, double window_min,
5148 double window_max);
5149
5150 /**
5151 * \chinese
5152 * 设置传送带示教位置到同步开关之间的距离
5153 *
5154 * @param encoder_id 预留
5155 * @param offset
5156 * 传送带示教位置到同步开关之间的距离,单位:米
5157 * @return
5158 *
5159 * @throws arcs::common_interface::AuboException
5160 *
5161 * @par Python函数原型
5162 * setConveyorTrackSensorOffset(self: pyaubo_sdk.MotionControl, arg0: int,
5163 * arg1: double) -> int
5164 *
5165 * @par Lua函数原型
5166 * setConveyorTrackSensorOffset(encoder_id: number, offset: number) -> int
5167 *
5168 * @par JSON-RPC请求示例
5169 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSensorOffset","params":[0,
5170 * 0.2],"id":1}
5171 *
5172 * @par JSON-RPC响应示例
5173 * {"id":1,"jsonrpc":"2.0","result":0}
5174 *
5175 * \endchinese
5176 * \english
5177 * Set the distance from the conveyor teaching position to the sync switch
5178 *
5179 * @param encoder_id Reserved
5180 * @param offset
5181 * Distance from the conveyor teaching position to the sync switch, unit:
5182 * meter
5183 * @return
5184 *
5185 * @throws arcs::common_interface::AuboException
5186 *
5187 * @par Python function prototype
5188 * setConveyorTrackSensorOffset(self: pyaubo_sdk.MotionControl, arg0: int,
5189 * arg1: double) -> int
5190 *
5191 * @par Lua function prototype
5192 * setConveyorTrackSensorOffset(encoder_id: number, offset: number) -> int
5193 *
5194 * @par JSON-RPC request example
5195 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSensorOffset","params":[0,
5196 * 0.2],"id":1}
5197 *
5198 * @par JSON-RPC response example
5199 * {"id":1,"jsonrpc":"2.0","result":0}
5200 *
5201 * \endenglish
5202 */
5203 int setConveyorTrackSensorOffset(int encoder_id, double offset);
5204
5205 /**
5206 * \chinese
5207 * 设置传送带同步分离,用于过滤掉同步开关中不需要的信号
5208 *
5209 * @param encoder_id 预留
5210 * @param distance
5211 * 从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短距离,单位:米
5212 * @param time
5213 * 从出现一个同步信号后到把一个新的同步信号接受为一个有效对象前走的最短时间,单位:秒
5214 *
5215 * distance和time设置数值大于0即为生效
5216 * 当distance与time同时设置时,优先生效distance
5217 * @return
5218 *
5219 * @throws arcs::common_interface::AuboException
5220 *
5221 * @par Python函数原型
5222 * setConveyorTrackSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int,
5223 * arg1: double, arg2: double) -> int
5224 *
5225 * @par Lua函数原型
5226 * setConveyorTrackSyncSeparation(encoder_id: number, distance: number,
5227 * time: number) -> int
5228 *
5229 * @par JSON-RPC请求示例
5230 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSyncSeparation","params":[0,
5231 * 0.05, 0.2],"id":1}
5232 *
5233 * @par JSON-RPC响应示例
5234 * {"id":1,"jsonrpc":"2.0","result":0}
5235 * \endchinese
5236 * \english
5237 * Set conveyor sync separation, used to filter out unwanted signals from
5238 * the sync switch.
5239 *
5240 * @param encoder_id Reserved
5241 * @param distance
5242 * The minimum distance to travel after a sync signal appears before
5243 * accepting a new sync signal as a valid object, unit: meter
5244 * @param time
5245 * The minimum time to elapse after a sync signal appears before accepting a
5246 * new sync signal as a valid object, unit: second
5247 *
5248 * If distance and time are both set greater than 0, the setting takes
5249 * effect. If both distance and time are set, distance takes precedence.
5250 * @return
5251 *
5252 * @throws arcs::common_interface::AuboException
5253 *
5254 * @par Python function prototype
5255 * setConveyorTrackSyncSeparation(self: pyaubo_sdk.MotionControl, arg0: int,
5256 * arg1: double, arg2: double) -> int
5257 *
5258 * @par Lua function prototype
5259 * setConveyorTrackSyncSeparation(encoder_id: number, distance: number,
5260 * time: number) -> int
5261 *
5262 * @par JSON-RPC request example
5263 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorTrackSyncSeparation","params":[0,
5264 * 0.05, 0.2],"id":1}
5265 *
5266 * @par JSON-RPC response example
5267 * {"id":1,"jsonrpc":"2.0","result":0}
5268 * \endenglish
5269 */
5270 int setConveyorTrackSyncSeparation(int encoder_id, double distance,
5271 double time);
5272
5273 /**
5274 * \chinese
5275 * 传送带上工件的移动距离是否超过最大限值
5276 *
5277 * @param encoder_id 预留
5278 * @return
5279 * true : 移动距离超过了最大限值
5280 * false : 移动距离没有超过了最大限值
5281 *
5282 * @throws arcs::common_interface::AuboException
5283 *
5284 * @par Python函数原型
5285 * isConveyorTrackExceed(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5286 *
5287 * @par Lua函数原型
5288 * isConveyorTrackExceed(encoder_id: number) -> bool
5289 *
5290 * @par JSON-RPC请求示例
5291 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackExceed","params":[0],"id":1}
5292 *
5293 * @par JSON-RPC响应示例
5294 * {"id":1,"jsonrpc":"2.0","result":false}
5295 * \endchinese
5296 * \english
5297 * Whether the workpiece on the conveyor has moved beyond the maximum limit
5298 *
5299 * @param encoder_id Reserved
5300 * @return
5301 * true : The movement distance exceeds the maximum limit
5302 * false : The movement distance does not exceed the maximum limit
5303 *
5304 * @throws arcs::common_interface::AuboException
5305 *
5306 * @par Python function prototype
5307 * isConveyorTrackExceed(self: pyaubo_sdk.MotionControl, arg0: int) -> bool
5308 *
5309 * @par Lua function prototype
5310 * isConveyorTrackExceed(encoder_id: number) -> bool
5311 *
5312 * @par JSON-RPC request example
5313 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isConveyorTrackExceed","params":[0],"id":1}
5314 *
5315 * @par JSON-RPC response example
5316 * {"id":1,"jsonrpc":"2.0","result":false}
5317 * \endenglish
5318 */
5319 bool isConveyorTrackExceed(int encoder_id);
5320
5321 /**
5322 * \chinese
5323 * 清空传动带队列中的所有对象
5324 *
5325 * @param encoder_id 预留
5326 * @return
5327 *
5328 * @throws arcs::common_interface::AuboException
5329 *
5330 * @par Python函数原型
5331 * conveyorTrackClearItems(self: pyaubo_sdk.MotionControl, arg0: int) -> int
5332 *
5333 * @par Lua函数原型
5334 * conveyorTrackClearItems(encoder_id: number) -> int
5335 *
5336 * @par JSON-RPC请求示例
5337 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackClearItems","params":[0],"id":1}
5338 *
5339 * @par JSON-RPC响应示例
5340 * {"id":1,"jsonrpc":"2.0","result":0}
5341 *
5342 * \endchinese
5343 * \english
5344 * Clear all items in the conveyor queue
5345 *
5346 * @param encoder_id Reserved
5347 * @return
5348 *
5349 * @throws arcs::common_interface::AuboException
5350 *
5351 * @par Python function prototype
5352 * conveyorTrackClearItems(self: pyaubo_sdk.MotionControl, arg0: int) -> int
5353 *
5354 * @par Lua function prototype
5355 * conveyorTrackClearItems(encoder_id: number) -> int
5356 *
5357 * @par JSON-RPC request example
5358 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackClearItems","params":[0],"id":1}
5359 *
5360 * @par JSON-RPC response example
5361 * {"id":1,"jsonrpc":"2.0","result":0}
5362 *
5363 * \endenglish
5364 */
5365 int conveyorTrackClearItems(int encoder_id);
5366
5367 /**
5368 * \chinese
5369 * 获取传送带队列的编码器值
5370 *
5371 * @param encoder_id 预留
5372 * @return
5373 *
5374 * @throws arcs::common_interface::AuboException
5375 *
5376 * @par Python函数原型
5377 * getConveyorTrackQueue(self: pyaubo_sdk.MotionControl, arg0: int) ->
5378 * List[int]
5379 * @par Lua函数原型
5380 * getConveyorTrackQueue(encoder_id: number) -> table
5381 *
5382 * @par JSON-RPC请求示例
5383 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackQueue","params":[0],"id":1}
5384 *
5385 * @par JSON-RPC响应示例
5386 * {"id":1,"jsonrpc":"2.0","result":{[-500,-200,150,-50]}}
5387 * \endchinese
5388 * \english
5389 * Get encoder values of the conveyor queue
5390 *
5391 * @param encoder_id Reserved
5392 * @return
5393 *
5394 * @throws arcs::common_interface::AuboException
5395 *
5396 * @par Python function prototype
5397 * getConveyorTrackQueue(self: pyaubo_sdk.MotionControl, arg0: int) ->
5398 * List[int]
5399 * @par Lua function prototype
5400 * getConveyorTrackQueue(encoder_id: number) -> table
5401 *
5402 * @par JSON-RPC request example
5403 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackQueue","params":[0],"id":1}
5404 *
5405 * @par JSON-RPC response example
5406 * {"id":1,"jsonrpc":"2.0","result":{[-500,-200,150,-50]}}
5407 * \endenglish
5408 */
5409 std::vector<int> getConveyorTrackQueue(int encoder_id);
5410 /**
5411 * \chinese
5412 * 获取下一个跟踪的传送带物品的id
5413 *
5414 * @param encoder_id 预留
5415 * @return
5416 * 返回物品id,没有next item返回 -1
5417 *
5418 * @throws arcs::common_interface::AuboException
5419 *
5420 * @par Python函数原型
5421 * getConveyorTrackNextItem(self: pyaubo_sdk.MotionControl, arg0: int) ->
5422 * int
5423 * @par Lua函数原型
5424 * getConveyorTrackNextItem(encoder_id: number) -> int
5425 *
5426 * @par JSON-RPC请求示例
5427 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackNextItem","params":[0],"id":1}
5428 *
5429 * @par JSON-RPC响应示例
5430 * {"id":1,"jsonrpc":"2.0","result":{10}}
5431 * \endchinese
5432 * \english
5433 * Get the ID of the next item on the conveyor to be tracked
5434 *
5435 * @param encoder_id Reserved
5436 * @return
5437 * Returns the item ID; returns -1 if there is no next item
5438 *
5439 * @throws arcs::common_interface::AuboException
5440 *
5441 * @par Python function prototype
5442 * getConveyorTrackNextItem(self: pyaubo_sdk.MotionControl, arg0: int) ->
5443 * int
5444 * @par Lua function prototype
5445 * getConveyorTrackNextItem(encoder_id: number) -> int
5446 *
5447 * @par JSON-RPC Request Example
5448 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorTrackNextItem","params":[0],"id":1}
5449 *
5450 * @par JSON-RPC Response Example
5451 * {"id":1,"jsonrpc":"2.0","result":{10}}
5452 * \endenglish
5453 */
5454
5455 int getConveyorTrackNextItem(int encoder_id);
5456
5457 /**
5458 * \chinese
5459 * 螺旋线运动
5460 *
5461 * @param param 封装的参数
5462 * @param blend_radius
5463 * @param v
5464 * @param a
5465 * @param t
5466 * @return 成功返回0;失败返回错误码
5467 * AUBO_BUSY
5468 * AUBO_BAD_STATE
5469 * -AUBO_INVL_ARGUMENT
5470 * -AUBO_BAD_STATE
5471 *
5472 * @throws arcs::common_interface::AuboException
5473 *
5474 * @par JSON-RPC请求示例
5475 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
5476 * "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}
5477 *
5478 * @par JSON-RPC响应示例
5479 * {"id":1,"jsonrpc":"2.0","result":0}
5480 * \endchinese
5481 * \english
5482 * Spiral motion
5483 *
5484 * @param param Encapsulated parameters
5485 * @param blend_radius
5486 * @param v
5487 * @param a
5488 * @param t
5489 * @return Returns 0 on success; otherwise returns an error code
5490 * AUBO_BUSY
5491 * AUBO_BAD_STATE
5492 * -AUBO_INVL_ARGUMENT
5493 * -AUBO_BAD_STATE
5494 *
5495 * @throws arcs::common_interface::AuboException
5496 *
5497 * @par JSON-RPC request example
5498 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
5499 * "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}
5500 *
5501 * @par JSON-RPC response example
5502 * {"id":1,"jsonrpc":"2.0","result":0}
5503 * \endenglish
5504 */
5505 int moveSpiral(const SpiralParameters &param, double blend_radius, double v,
5506 double a, double t);
5507
5508 /**
5509 * \chinese
5510 * 获取前瞻段数
5511 *
5512 * @return 返回前瞻段数
5513 *
5514 * @throws arcs::common_interface::AuboException
5515 *
5516 * @par Python函数原型
5517 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
5518 *
5519 * @par Lua函数原型
5520 * getLookAheadSize() -> number
5521 *
5522 * @par JSON-RPC请求示例
5523 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
5524 *
5525 * @par JSON-RPC响应示例
5526 * {"id":1,"jsonrpc":"2.0","result":1}
5527 *
5528 * \endchinese
5529 * \english
5530 * Get look-ahead segment size
5531 *
5532 * @return Returns the look-ahead segment size
5533 *
5534 * @throws arcs::common_interface::AuboException
5535 *
5536 * @par Python function prototype
5537 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
5538 *
5539 * @par Lua function prototype
5540 * getLookAheadSize() -> number
5541 *
5542 * @par JSON-RPC request example
5543 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
5544 *
5545 * @par JSON-RPC response example
5546 * {"id":1,"jsonrpc":"2.0","result":1}
5547 *
5548 * \endenglish
5549 */
5551
5552 /**
5553 * \chinese
5554 * 设置前瞻段数
5555 * 1.对于有较高速度平稳性要求的任务,如数控加工,涂胶,焊接等匀速需求,较长的前瞻段数可以提供更优的速度规划,产生的运动会更加平滑;
5556 * 2.对于快速响应的抓取类任务,更倾向于较短的前瞻段数,以提高反应速度,但可能因为进给的路径不够及时导致速度波动很大.
5557 *
5558 * @return 成功返回0
5559 *
5560 * @throws arcs::common_interface::AuboException
5561 *
5562 * @par Python函数原型
5563 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
5564 *
5565 * @par Lua函数原型
5566 * setLookAheadSize(eqradius: number) -> number
5567 *
5568 * @par JSON-RPC请求示例
5569 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
5570 *
5571 * @par JSON-RPC响应示例
5572 * {"id":1,"jsonrpc":"2.0","result":0}
5573 * \endchinese
5574 * \english
5575 * Set look-ahead segment size
5576 * 1. For tasks requiring high speed smoothness, such as CNC machining,
5577 * gluing, welding, etc., a longer look-ahead segment size can provide
5578 * better speed planning and smoother motion.
5579 * 2. For fast-response tasks such as picking, a shorter look-ahead segment
5580 * size is preferred to improve response speed, but may cause large speed
5581 * fluctuations due to insufficiently timely path feeding.
5582 *
5583 * @return Returns 0 on success
5584 *
5585 * @throws arcs::common_interface::AuboException
5586 *
5587 * @par Python function prototype
5588 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
5589 *
5590 * @par Lua function prototype
5591 * setLookAheadSize(eqradius: number) -> number
5592 *
5593 * @par JSON-RPC request example
5594 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
5595 *
5596 * @par JSON-RPC response example
5597 * {"id":1,"jsonrpc":"2.0","result":0}
5598 * \endenglish
5599 */
5600 int setLookAheadSize(int size);
5601
5602 /**
5603 * \chinese
5604 * 更新摆动过程中的频率和振幅
5605 *
5606 * @param params Json字符串用于定义摆动参数
5607 * {
5608 * "frequency": <num>,
5609 * "amplitude": {<num>,<num>}
5610 * }
5611 *
5612 * @return 成功返回0
5613 *
5614 * @throws arcs::common_interface::AuboException
5615 * \endchinese
5616 * \english
5617 * Update frequency and amplitude during weaving process
5618 *
5619 * @param params Json string used to define weaving parameters
5620 * {
5621 * "frequency": <num>,
5622 * "amplitude": {<num>,<num>}
5623 * }
5624 *
5625 * @return Returns 0 on success
5626 *
5627 * @throws arcs::common_interface::AuboException
5628 * \endenglish
5629 */
5630 int weaveUpdateParameters(const std::string &params);
5631
5632 /**
5633 * \chinese
5634 * 设置关节电流环刚度系数
5635 *
5636 * @param stiffness 各个关节刚度系数,百分比。[0 -> 1],值越大,表现为越硬。
5637 * @return
5638 *
5639 * @throws arcs::common_interface::AuboException
5640 *
5641 * @par Python函数原型
5642 * enableJointSoftServo(self: pyaubo_sdk.RobotConfig, arg0: List[float]) ->
5643 * int
5644 *
5645 * @par Lua函数原型
5646 * enableJointSoftServo(stiffness: table) -> int
5647 *
5648 * @par JSON-RPC请求示例
5649 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.enableJointSoftServo","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
5650 *
5651 * @par JSON-RPC响应示例
5652 * {"id":1,"jsonrpc":"2.0","result":0}
5653 * \endchinese
5654 * \english
5655 * Set joint current loop stiffness coefficient
5656 *
5657 * @param stiffness Stiffness coefficient for each joint, as a percentage [0
5658 * -> 1]. The larger the value, the stiffer the joint.
5659 * @return
5660 *
5661 * @throws arcs::common_interface::AuboException
5662 *
5663 * @par Python function prototype
5664 * enableJointSoftServo(self: pyaubo_sdk.RobotConfig, arg0: List[float]) ->
5665 * int
5666 *
5667 * @par Lua function prototype
5668 * enableJointSoftServo(stiffness: table) -> int
5669 *
5670 * @par JSON-RPC request example
5671 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.enableJointSoftServo","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
5672 *
5673 * @par JSON-RPC response example
5674 * {"id":1,"jsonrpc":"2.0","result":0}
5675 * \endenglish
5676 */
5677 int enableJointSoftServo(const std::vector<double> &stiffness);
5678
5679 /**
5680 * \chinese
5681 * 关闭关节电流环刚度系数
5682 *
5683 * @return 返回0表示成功,其他为错误码
5684 *
5685 * @throws arcs::common_interface::AuboException
5686 *
5687 * @par Python函数原型
5688 * disableJointSoftServo(self: pyaubo_sdk.MotionControl) -> int
5689 *
5690 * @par Lua函数原型
5691 * disableJointSoftServo() -> number
5692 *
5693 * @par JSON-RPC请求示例
5694 * {"jsonrpc":"2.0","method":"rob1.MotionControl.disableJointSoftServo","params":[],"id":1}
5695 *
5696 * @par JSON-RPC响应示例
5697 * {"id":1,"jsonrpc":"2.0","result":1}
5698 * \endchinese
5699 * \english
5700 * Disable joint current loop stiffness coefficient
5701 *
5702 * @return Returns 0 on success, otherwise error code
5703 *
5704 * @throws arcs::common_interface::AuboException
5705 *
5706 * @par Python function prototype
5707 * disableJointSoftServo(self: pyaubo_sdk.MotionControl) -> int
5708 *
5709 * @par Lua function prototype
5710 * disableJointSoftServo() -> number
5711 *
5712 * @par JSON-RPC request example
5713 * {"jsonrpc":"2.0","method":"rob1.MotionControl.disableJointSoftServo","params":[],"id":1}
5714 *
5715 * @par JSON-RPC response example
5716 * {"id":1,"jsonrpc":"2.0","result":1}
5717 * \endenglish
5718 */
5720
5721 /**
5722 * \chinese
5723 * 判断关节电流环刚度系数是否使能
5724 *
5725 * @return 已使能返回true,反之则返回false
5726 *
5727 * @throws arcs::common_interface::AuboException
5728 *
5729 * @par Python函数原型
5730 * isJointSoftServoEnabled(self: pyaubo_sdk.MotionControl) -> bool
5731 *
5732 * @par Lua函数原型
5733 * isJointSoftServoEnabled() -> boolean
5734 *
5735 * @par JSON-RPC请求示例
5736 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isJointSoftServoEnabled","params":[],"id":1}
5737 *
5738 * @par JSON-RPC响应示例
5739 * {"id":1,"jsonrpc":"2.0","result":1}
5740 * \endchinese
5741 * \english
5742 * Determine whether the joint current loop stiffness coefficient is
5743 * enabled.
5744 *
5745 * @return Returns true if enabled, otherwise returns false.
5746 *
5747 * @throws arcs::common_interface::AuboException
5748 *
5749 * @par Python function prototype
5750 * isJointSoftServoEnabled(self: pyaubo_sdk.MotionControl) -> bool
5751 *
5752 * @par Lua function prototype
5753 * isJointSoftServoEnabled() -> boolean
5754 *
5755 * @par JSON-RPC request example
5756 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isJointSoftServoEnabled","params":[],"id":1}
5757 *
5758 * @par JSON-RPC response example
5759 * {"id":1,"jsonrpc":"2.0","result":1}
5760 * \endenglish
5761 */
5763
5764 /**
5765 * \chinese
5766 * 打开振动抑制
5767 *
5768 * @param omega 振动抑制频率,长度一般为笛卡尔维度或关节自由度.为0时关闭抑制
5769 * \n
5770 * @param zeta 振动抑制阻尼比,长度一般为笛卡尔维度或关节自由度.为0时关闭抑制
5771 * \n
5772 * @param level
5773 * 振动抑制等级(1~3),等级越高抑制效果越明显响应速度相应变慢.等级0关闭振动抑制
5774 * \n
5775 * @retval 0 成功
5776 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
5777 * Normal、ReducedMode、Recovery 状态
5778 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
5779 * @retval AUBO_BUSY(3) 上一条指令正在执行中
5780 * @retval -AUBO_BAD_STATE(-1)
5781 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
5782 * 未找到,或者当前机器人模式非 Running
5783 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
5784 *
5785 * @throws arcs::common_interface::AuboException
5786 *
5787 * @par Python函数原型
5788 * enableVibrationSuppress(self: pyaubo_sdk.MotionControl, arg0:
5789 * list[float], arg1: list[float], arg2: int) -> int
5790 *
5791 * @par Lua函数原型
5792 * enableVibrationSuppress(omega: table, zeta: table, level: number) -> nil
5793 *
5794 * @par JSON-RPC请求示例
5795 * {"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}
5796 *
5797 * @par JSON-RPC响应示例
5798 * {"id":1,"jsonrpc":"2.0","result":0}
5799 *
5800 * \endchinese
5801 */
5802 int enableVibrationSuppress(const std::vector<double> &omega,
5803 const std::vector<double> &zeta, int level);
5804 /**
5805 * \chinese
5806 * 关闭振动抑制
5807 *
5808 * @return 已使能返回true,反之则返回false
5809 *
5810 * @throws arcs::common_interface::AuboException
5811 *
5812 * @par Python函数原型
5813 * disbaleVibrationSuppress(self: pyaubo_sdk.MotionControl) -> int
5814 *
5815 * @par Lua函数原型
5816 * disbaleVibrationSuppress() -> number
5817 *
5818 * @par JSON-RPC请求示例
5819 * {"jsonrpc":"2.0","method":"rob1.MotionControl.disbaleVibrationSuppress","params":[],"id":1}
5820 *
5821 * @par JSON-RPC响应示例
5822 * {"id":1,"jsonrpc":"2.0","result":1}
5823 * \endchinese
5824 */
5826
5827protected:
5828 void *d_;
5829};
5830using MotionControlPtr = std::shared_ptr<MotionControl>;
5831} // namespace common_interface
5832} // namespace arcs
5833
5834#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 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)
开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 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)
关节空间伺服
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样条插值,最少三个点,但是传入的是笛卡尔空间位姿
数据类型的定义