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