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