ARCS SDK API  0.25.0
载入中...
搜索中...
未找到
motion_control.h
浏览该文件的文档.
1/** @file motion_control.h
2 * @brief 运动控制接口
3 *
4 * The robot movements are programmed as pose-to-pose movements, that is move
5 * from the current position to a new position. The path between these two
6 * positions is then automatically calculated by the robot.
7 */
8#ifndef AUBO_SDK_MOTION_CONTROL_INTERFACE_H
9#define AUBO_SDK_MOTION_CONTROL_INTERFACE_H
10
11#include <vector>
12#include <functional>
13#include <thread>
14
15#include <aubo/global_config.h>
16#include <aubo/type_def.h>
17
18namespace arcs {
19namespace common_interface {
20
21/**
22 * pathBuffer类型
23 */
25{
26 PathBuffer_TOPPRA = 1, ///< 1: toppra 时间最优路径规划
27 PathBuffer_CubicSpline = 2, ///< 2: cubic_spline(录制的轨迹)
28
29 /// 3: 关节B样条插值,最少三个点
30 /// 废弃,建议用5替代,现在实际是关节空间 CUBIC_SPLINE
32
33 /// 4:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
34 /// 废弃,建议用6替代,现在实际是关节空间 CUBIC_SPLINE
36
37 ///< 5: 关节B样条插值,最少三个点
39
40 /// 6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
42};
43
44/**
45 * MotionControl类
46 */
47class ARCS_ABI_EXPORT MotionControl
48{
49public:
51 virtual ~MotionControl();
52
53 /**
54 * 获取等效半径,单位 m
55 * moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动
56 * 可以通过 setEqradius 设置,默认为1
57 *
58 * @return 返回等效半径
59 *
60 * @throws arcs::common_interface::AuboException
61 *
62 * @par Python函数原型
63 * getEqradius(self: pyaubo_sdk.MotionControl) -> float
64 *
65 * @par Lua函数原型
66 * getEqradius() -> number
67 *
68 * @par JSON-RPC请求示例
69 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getEqradius","params":[],"id":1}
70 *
71 * @par JSON-RPC响应示例
72 * {"id":1,"jsonrpc":"2.0","result":1.0}
73 *
74 */
75 double getEqradius();
76
77 /**
78 * 设置等效半径,单位 m
79 * moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
80 *
81 * @param eqradius 0表示只规划移动,姿态旋转跟随移动
82 *
83 * @return 成功返回0; 失败返回错误码
84 * AUBO_BAD_STATE
85 * AUBO_BUSY
86 * -AUBO_INVL_ARGUMENT
87 * -AUBO_BAD_STATE
88 *
89 * @throws arcs::common_interface::AuboException
90 *
91 * @par JSON-RPC请求示例
92 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setEqradius","params":[0.8],"id":1}
93 *
94 * @par JSON-RPC响应示例
95 * {"id":1,"jsonrpc":"2.0","result":0}
96 *
97 * @par Python函数原型
98 * setEqradius(self: pyaubo_sdk.MotionControl, arg0: float) -> int
99 *
100 * @par Lua函数原型
101 * setEqradius(eqradius: number) -> number
102 */
103 int setEqradius(double eqradius);
104
105 /**
106 * 动态调整机器人运行速度和加速度比例 (0., 1.]
107 *
108 * @param fraction 机器人运行速度和加速度比例
109 * @return 成功返回0; 失败返回错误码
110 * AUBO_INVL_ARGUMENT
111 * AUBO_BUSY
112 * AUBO_BAD_STATE
113 * -AUBO_INVL_ARGUMENT
114 * -AUBO_BAD_STATE
115 *
116 * @throws arcs::common_interface::AuboException
117 *
118 * @par Python函数原型
119 * setSpeedFraction(self: pyaubo_sdk.MotionControl, arg0: float) -> int
120 *
121 * @par Lua函数原型
122 * setSpeedFraction(fraction: number) -> nil
123 *
124 * @par JSON-RPC请求示例
125 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setSpeedFraction","params":[0.8],"id":1}
126 *
127 * @par JSON-RPC响应示例
128 * {"id":1,"jsonrpc":"2.0","result":0}
129 *
130 */
131 int setSpeedFraction(double fraction);
132
133 /**
134 * 获取速度和加速度比例,默认为 1
135 * 可以通过 setSpeedFraction 接口设置
136 *
137 * @return 返回速度和加速度比例
138 *
139 * @throws arcs::common_interface::AuboException
140 *
141 * @par Python函数原型
142 * getSpeedFraction(self: pyaubo_sdk.MotionControl) -> float
143 *
144 * @par Lua函数原型
145 * getSpeedFraction() -> number
146 *
147 * @par JSON-RPC请求示例
148 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getSpeedFraction","params":[],"id":1}
149 *
150 * @par JSON-RPC响应示例
151 * {"id":1,"jsonrpc":"2.0","result":1.0}
152 *
153 */
155
156 /**
157 * 速度比例设置临界区,使能之后速度比例被强制设定为1. ,
158 * 失能之后恢复之前的速度比例
159 *
160 * @param enable
161 * @return 成功返回0; 失败返回错误码
162 * AUBO_BAD_STATE
163 * AUBO_BUSY
164 * -AUBO_BAD_STATE
165 *
166 * @throws arcs::common_interface::AuboException
167 *
168 * @par JSON-RPC请求示例
169 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedFractionCritical","params":[true],"id":1}
170 *
171 * @par JSON-RPC响应示例
172 * {"id":1,"jsonrpc":"2.0","result":0}
173 *
174 */
175 int speedFractionCritical(bool enable);
176
177 /**
178 * 是否处于速度比例设置临界区
179 *
180 * @return 处于速度比例设置临界区返回 true; 反之返回 false
181 *
182 * @throws arcs::common_interface::AuboException
183 *
184 * @par JSON-RPC请求示例
185 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isSpeedFractionCritical","params":[],"id":1}
186 *
187 * @par JSON-RPC响应示例
188 * {"id":1,"jsonrpc":"2.0","result":true}
189 *
190 */
192
193 /**
194 * 是否处交融区
195 *
196 * @return 处交融区返回 true; 反之返回 false
197 *
198 * @throws arcs::common_interface::AuboException
199 *
200 * @par JSON-RPC请求示例
201 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isBlending","params":[],"id":1}
202 *
203 * @par JSON-RPC响应示例
204 * {"id":1,"jsonrpc":"2.0","result":false}
205 *
206 */
208
209 /**
210 * 设置偏移的最大速度和最大加速度
211 * 仅对pathOffsetSet中 type=1 有效
212 * @param v 最大速度
213 * @param a 最大加速度
214 * @return 成功返回0;失败返回错误码
215 * AUBO_BUSY
216 * AUBO_BAD_STATE
217 * -AUBO_INVL_ARGUMENT
218 * -AUBO_BAD_STATE
219 *
220 * @throws arcs::common_interface::AuboException
221 *
222 * @par Python函数原型
223 * pathOffsetLimits(self: pyaubo_sdk.MotionControl, arg0: float, arg1:
224 * float)
225 * -> int
226 *
227 * @par Lua函数原型
228 * pathOffsetLimits(v: number, a: number) -> nil
229 *
230 */
231 int pathOffsetLimits(double v, double a);
232
233 /**
234 * 设置偏移的参考坐标系
235 * 仅对pathOffsetSet中 type=1 有效
236 * @param ref_coord 参考坐标系 0-基坐标系 1-TCP
237 *
238 * @throws arcs::common_interface::AuboException
239 *
240 * @par Python函数原型
241 * pathOffsetCoordinate(self: pyaubo_sdk.MotionControl, arg0: int) -> float
242 *
243 * @par Lua函数原型
244 * pathOffsetCoordinate(ref_coord: number) -> number
245 *
246 * @par JSON-RPC请求示例
247 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetCoordinate","params":[0],"id":1}
248 *
249 * @par JSON-RPC响应示例
250 * {"id":1,"jsonrpc":"2.0","result":0}
251 *
252 */
253 int pathOffsetCoordinate(int ref_coord);
254
255 /**
256 * 路径偏移使能
257 *
258 * @return 成功返回0; 失败返回错误码
259 * AUBO_BUSY
260 * AUBO_BAD_STATE
261 * -AUBO_BAD_STATE
262 *
263 * @throws arcs::common_interface::AuboException
264 *
265 * @par Python函数原型
266 * pathOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
267 *
268 * @par Lua函数原型
269 * pathOffsetEnable() -> number
270 *
271 * @par JSON-RPC请求示例
272 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetEnable","params":[],"id":1}
273 *
274 * @par JSON-RPC响应示例
275 * {"id":1,"jsonrpc":"2.0","result":0}
276 *
277 */
279
280 /**
281 * 设置路径偏移
282 *
283 * @param offset 在各方向的位姿偏移
284 * @param type 运动类型 0-位置规划 1-速度规划
285 * @return 成功返回0; 失败返回错误码
286 * AUBO_BAD_STATE
287 * AUBO_BUSY
288 * -AUBO_INVL_ARGUMENT
289 * -AUBO_BAD_STATE
290 *
291 * @throws arcs::common_interface::AuboException
292 *
293 * @par Python函数原型
294 * pathOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
295 * int) -> int
296 *
297 * @par Lua函数原型
298 * pathOffsetSet(offset: table, type: number) -> nil
299 *
300 * @par JSON-RPC请求示例
301 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetSet","params":[[0,0,0.01,0,0,0],0],"id":1}
302 *
303 * @par JSON-RPC响应示例
304 * {"id":1,"jsonrpc":"2.0","result":0}
305 *
306 */
307 int pathOffsetSet(const std::vector<double> &offset, int type = 0);
308
309 /**
310 * 路径偏移失能
311 *
312 * @return 成功返回0; 失败返回错误码
313 * AUBO_BAD_STATE
314 * AUBO_BUSY
315 * -AUBO_BAD_STATE
316 *
317 * @throws arcs::common_interface::AuboException
318 *
319 * @par Python函数原型
320 * pathOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
321 *
322 * @par Lua函数原型
323 * pathOffsetDisable() -> nil
324 *
325 * @par JSON-RPC请求示例
326 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathOffsetDisable","params":[],"id":1}
327 *
328 * @par JSON-RPC响应示例
329 * {"id":1,"jsonrpc":"2.0","result":0}
330 *
331 */
333
334 /**
335 * @brief 监控轨迹偏移范围
336 * @param min: 沿坐标轴负方向最大偏移量
337 * @param max: 沿坐标轴负正方向最大偏移量
338 * @param strategy: 达到最大偏移量后监控策略
339 *     0-禁用监控
340 *     1-饱和限制,即维持最大姿态
341 *     2-保护停止
342 * @return
343 *
344 * @throws arcs::common_interface::AuboException
345 *
346 * @par Python函数原型
347 * pathOffsetSupv(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
348 * List[float], arg2: int) -> int
349 *
350 * @par Lua函数原型
351 * pathOffsetSupv(min: table, max: table, strategy: number) -> number
352 */
353 int pathOffsetSupv(const std::vector<double> &min,
354 const std::vector<double> &max, int strategy);
355
356 /**
357 * 关节偏移使能
358 *
359 * @return 成功返回0; 失败返回错误码
360 * AUBO_BAD_STATE
361 * AUBO_BUSY
362 * -AUBO_BAD_STATE
363 *
364 * @throws arcs::common_interface::AuboException
365 *
366 * @par Python函数原型
367 * jointOffsetEnable(self: pyaubo_sdk.MotionControl) -> int
368 *
369 * @par Lua函数原型
370 * jointOffsetEnable() -> nil
371 *
372 * @par JSON-RPC请求示例
373 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetEnable","params":[],"id":1}
374 *
375 * @par JSON-RPC响应示例
376 * {"id":1,"jsonrpc":"2.0","result":0}
377 *
378 */
380
381 /**
382 * 设置关节偏移
383 *
384 * @param offset 在各关节的位姿偏移
385 * @param type
386 * @return 成功返回0; 失败返回错误码
387 * AUBO_BAD_STATE
388 * AUBO_BUSY
389 * -AUBO_INVL_ARGUMENT
390 * -AUBO_BAD_STATE
391 *
392 * @throws arcs::common_interface::AuboException
393 *
394 * @par Python函数原型
395 * jointOffsetSet(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
396 * int) -> int
397 *
398 * @par Lua函数原型
399 * jointOffsetSet(offset: table, type: number) -> nil
400 *
401 * @par JSON-RPC请求示例
402 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetSet","params":[[0.1,0,0,0,0],1],"id":1}
403 *
404 * @par JSON-RPC响应示例
405 * {"id":1,"jsonrpc":"2.0","result":0}
406 *
407 */
408 int jointOffsetSet(const std::vector<double> &offset, int type = 1);
409
410 /**
411 * 关节偏移失能
412 *
413 * @return 成功返回0; 失败返回错误码
414 * AUBO_BAD_STATE
415 * AUBO_BUSY
416 * -AUBO_BAD_STATE
417 *
418 * @throws arcs::common_interface::AuboException
419 *
420 * @par Python函数原型
421 * jointOffsetDisable(self: pyaubo_sdk.MotionControl) -> int
422 *
423 * @par Lua函数原型
424 * jointOffsetDisable() -> nil
425 *
426 * @par JSON-RPC请求示例
427 * {"jsonrpc":"2.0","method":"rob1.MotionControl.jointOffsetDisable","params":[],"id":1}
428 *
429 * @par JSON-RPC响应示例
430 * {"id":1,"jsonrpc":"2.0","result":0}
431 *
432 */
434
435 /**
436 * 获取已经入队的指令段(INST)数量,运动指令包括
437 * moveJoint/moveLine/moveCircle 等运动指令以及 setPayload 等配置指令
438 *
439 * 指令一般会在接口宏定义里面用 _INST 指示, 比如 moveJoint
440 * _INST(MotionControl, 5, moveJoint, q, a, v, blend_radius, duration)
441 *
442 * @return 已经入队的指令段数量
443 *
444 * @throws arcs::common_interface::AuboException
445 *
446 * @par Python函数原型
447 * getQueueSize(self: pyaubo_sdk.MotionControl) -> int
448 *
449 * @par Lua函数原型
450 * getQueueSize() -> number
451 *
452 * @par JSON-RPC请求示例
453 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getQueueSize","params":[],"id":1}
454 *
455 * @par JSON-RPC响应示例
456 * {"id":1,"jsonrpc":"2.0","result":0}
457 *
458 */
460
461 /**
462 * 获取已经入队的运动规划插补点数量
463 *
464 * @return 已经入队的运动规划插补点数量
465 *
466 * @throws arcs::common_interface::AuboException
467 *
468 * @par Python函数原型
469 * getTrajectoryQueueSize(self: pyaubo_sdk.MotionControl) -> int
470 *
471 * @par Lua函数原型
472 * getTrajectoryQueueSize() -> number
473 *
474 * @par JSON-RPC请求示例
475 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getTrajectoryQueueSize","params":[],"id":1}
476 *
477 * @par JSON-RPC响应示例
478 * {"id":1,"jsonrpc":"2.0","result":0}
479 *
480 */
482
483 /**
484 * 获取当前正在插补的运动指令段的ID
485 *
486 * @return 当前正在插补的运动指令段的ID
487 * @retval -1 表示轨迹队列为空 \n
488 * 像movePathBuffer运动中的buffer或者规划器(moveJoint和moveLine等)里的队列都属于轨迹队列
489 *
490 * @throws arcs::common_interface::AuboException
491 *
492 * @par Python函数原型
493 * getExecId(self: pyaubo_sdk.MotionControl) -> int
494 *
495 * @par Lua函数原型
496 * getExecId() -> number
497 *
498 * @par JSON-RPC请求示例
499 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getExecId","params":[],"id":1}
500 *
501 * @par JSON-RPC响应示例
502 * {"id":1,"jsonrpc":"2.0","result":-1}
503 *
504 */
506
507 /**
508 * 获取指定ID的运动指令段的预期执行时间
509 *
510 * @param id 运动指令段ID
511 * @return 返回预期执行时间
512 *
513 * @throws arcs::common_interface::AuboException
514 *
515 * @par Python函数原型
516 * getDuration(self: pyaubo_sdk.MotionControl, arg0: int) -> float
517 *
518 * @par Lua函数原型
519 * getDuration(id: number) -> number
520 *
521 * @par JSON-RPC请求示例
522 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getDuration","params":[16],"id":1}
523 *
524 * @par JSON-RPC响应示例
525 * {"id":1,"jsonrpc":"2.0","result":0.0}
526 *
527 */
528 double getDuration(int id);
529
530 /**
531 * 获取指定ID的运动指令段的剩余执行时间
532 *
533 * @param id 运动指令段ID
534 * @return 返回剩余执行时间
535 *
536 * @throws arcs::common_interface::AuboException
537 *
538 * @par Python函数原型
539 * getMotionLeftTime(self: pyaubo_sdk.MotionControl, arg0: int) -> float
540 *
541 * @par Lua函数原型
542 * getMotionLeftTime(id: number) -> number
543 *
544 * @par JSON-RPC请求示例
545 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getMotionLeftTime","params":[16],"id":1}
546 *
547 * @par JSON-RPC响应示例
548 * {"id":1,"jsonrpc":"2.0","result":0.0}
549 *
550 */
551 double getMotionLeftTime(int id);
552
553 /**
554 * StopMove is used to stop robot and external axes movements and any
555 * belonging process temporarily. If the instruction StartMove is given then
556 * the movement and process resumes.
557 *
558 * This instruction can, for example, be used in a trap routine to stop the
559 * robot temporarily when an interrupt occurs.
560 *
561 * @param quick true: Stops the robot on the path as fast as possible.
562 * Without the optional parameter \Quick, the robot stops on the path, but
563 * the braking distance is longer (same as for normal Program Stop).
564 *
565 * @return 成功返回0; 失败返回错误码
566 * AUBO_BAD_STATE
567 * AUBO_BUSY
568 * -AUBO_BAD_STATE
569 *
570 * @throws arcs::common_interface::AuboException
571 *
572 */
573 int stopMove(bool quick, bool all_tasks);
574
575 /**
576 * StartMove is used to resume robot, external axes movement and belonging
577 * process after the movement has been stopped
578 *
579 * • by the instruction StopMove.
580 * • after execution of StorePath ... RestoPath sequence.
581 * • after asynchronously raised movements errors, such as ERR_PATH_STOP or
582 * specific process error after handling in the ERROR handler.
583 *
584 * @return 成功返回0; 失败返回错误码
585 * AUBO_BAD_STATE
586 * AUBO_BUSY
587 * -AUBO_BAD_STATE
588 *
589 * @throws arcs::common_interface::AuboException
590 *
591 * @par JSON-RPC请求示例
592 * {"jsonrpc":"2.0","method":"rob1.MotionControl.startMove","params":[],"id":1}
593 *
594 * @par JSON-RPC响应示例
595 * {"id":1,"jsonrpc":"2.0","result":0}
596 *
597 */
599
600 /**
601 * storePath
602 *
603 * @param keep_sync
604 * @return 成功返回0; 失败返回错误码
605 * AUBO_BAD_STATE
606 * AUBO_BUSY
607 * -AUBO_BAD_STATE
608 *
609 * @throws arcs::common_interface::AuboException
610 *
611 */
612 int storePath(bool keep_sync);
613
614 /**
615 * ClearPath (Clear Path) clears the whole motion path on the current motion
616 * path level (base level or StorePath level).
617 *
618 * @return 成功返回0; 失败返回错误码
619 * AUBO_BAD_STATE
620 * AUBO_BUSY
621 * -AUBO_BAD_STATE
622 *
623 * @throws arcs::common_interface::AuboException
624 *
625 * @par JSON-RPC请求示例
626 * {"jsonrpc":"2.0","method":"rob1.MotionControl.clearPath","params":[],"id":1}
627 *
628 * @par JSON-RPC响应示例
629 * {"id":1,"jsonrpc":"2.0","result":0}
630 *
631 */
633
634 /**
635 * restoPath
636 *
637 * @return 成功返回0; 失败返回错误码
638 * AUBO_BAD_STATE
639 * AUBO_BUSY
640 * -AUBO_BAD_STATE
641 *
642 * @throws arcs::common_interface::AuboException
643 *
644 * @par JSON-RPC请求示例
645 * {"jsonrpc":"2.0","method":"rob1.MotionControl.restoPath","params":[],"id":1}
646 *
647 * @par JSON-RPC响应示例
648 * {"id":1,"jsonrpc":"2.0","result":0}
649 *
650 */
652
653 /**
654 * 获取当前运动指令段的执行进度
655 *
656 * @return 返回执行进度
657 *
658 * @throws arcs::common_interface::AuboException
659 *
660 * @par Python函数原型
661 * getProgress(self: pyaubo_sdk.MotionControl) -> float
662 *
663 * @par Lua函数原型
664 * getProgress() -> number
665 *
666 * @par JSON-RPC请求示例
667 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getProgress","params":[],"id":1}
668 *
669 * @par JSON-RPC响应示例
670 * {"id":1,"jsonrpc":"2.0","result":0.0}
671 *
672 */
673 double getProgress();
674
675 /**
676 * 当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
677 *
678 * @note 暂未实现
679 *
680 * @param module_name 控制模块名字
681 * @param mounting_pose 抓取的相对位置,
682 * 如果是机器人,则相对于机器人末端中心点(非TCP点)
683 * @return 成功返回0; 失败返回错误码
684 * AUBO_BAD_STATE
685 * AUBO_BUSY
686 * -AUBO_INVL_ARGUMENT
687 * -AUBO_BAD_STATE
688 *
689 * @throws arcs::common_interface::AuboException
690 *
691 * @par Python函数原型
692 * setWorkObjectHold(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
693 * List[float]) -> int
694 *
695 * @par Lua函数原型
696 * setWorkObjectHold(module_name: string, mounting_pose: table) -> nil
697 *
698 */
699 int setWorkObjectHold(const std::string &module_name,
700 const std::vector<double> &mounting_pose);
701
702 /**
703 * getWorkObjectHold
704 *
705 * @note 暂未实现
706 *
707 * @return
708 *
709 * @throws arcs::common_interface::AuboException
710 *
711 * @par Python函数原型
712 * getWorkObjectHold(self: pyaubo_sdk.MotionControl) -> Tuple[str,
713 * List[float]]
714 *
715 * @par Lua函数原型
716 * getWorkObjectHold() -> table
717 *
718 * @par JSON-RPC请求示例
719 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getWorkObjectHold","params":[],"id":1}
720 *
721 * @par JSON-RPC响应示例
722 * {"id":1,"jsonrpc":"2.0","result":["",[]]}
723 *
724 */
725 std::tuple<std::string, std::vector<double>> getWorkObjectHold();
726
727 /**
728 * getPauseJointPositions
729 *
730 * @note 获取暂停点关节位置
731 * 常用于运行工程时发生碰撞后继续运动过程中(先通过resumeMoveJoint或resumeMoveLine运动到暂停位置,再恢复工程)
732 *
733 * @return 暂停关节位置
734 *
735 * @throws arcs::common_interface::AuboException
736 *
737 * @par Python函数原型
738 * getPauseJointPositions(self: pyaubo_sdk.MotionControl) -> List[float]
739 *
740 * @par Lua函数原型
741 * getPauseJointPositions() -> table
742 *
743 * @par JSON-RPC请求示例
744 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getPauseJointPositions","params":[],"id":1}
745 *
746 * @par JSON-RPC响应示例
747 * {"id":1,"jsonrpc":"2.0","result":[8.2321e-13,-0.200999,1.33999,0.334999,1.206,-6.39383e-12]}
748 *
749 */
750 std::vector<double> getPauseJointPositions();
751
752 /**
753 * 设置伺服模式
754 * 使用 setServoModeSelect 替代
755 *
756 * @param enable 是否使能
757 * @return 成功返回0; 失败返回错误码
758 * AUBO_BAD_STATE
759 * AUBO_BUSY
760 * -AUBO_BAD_STATE
761 *
762 * @throws arcs::common_interface::AuboException
763 *
764 * @par Python函数原型
765 * setServoMode(self: pyaubo_sdk.MotionControl, arg0: bool) -> int
766 *
767 * @par Lua函数原型
768 * setServoMode(enable: boolean) -> nil
769 *
770 * @par JSON-RPC请求示例
771 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoMode","params":[true],"id":1}
772 *
773 * @par JSON-RPC响应示例
774 * {"id":1,"jsonrpc":"2.0","result":0}
775 *
776 */
777 ARCS_DEPRECATED int setServoMode(bool enable);
778
779 /**
780 * 判断伺服模式是否使能
781 * 使用 getServoModeSelect 替代
782 *
783 * @return 已使能返回true,反之则返回false
784 *
785 * @throws arcs::common_interface::AuboException
786 *
787 * @par Python函数原型
788 * isServoModeEnabled(self: pyaubo_sdk.MotionControl) -> bool
789 *
790 * @par Lua函数原型
791 * isServoModeEnabled() -> boolean
792 *
793 * @par JSON-RPC请求示例
794 * {"jsonrpc":"2.0","method":"rob1.MotionControl.isServoModeEnabled","params":[],"id":1}
795 *
796 * @par JSON-RPC响应示例
797 * {"id":1,"jsonrpc":"2.0","result":false}
798 *
799 */
800 ARCS_DEPRECATED bool isServoModeEnabled();
801
802 /**
803 * 设置伺服运动模式
804 *
805 * @param mode
806 * 0-退出伺服模式
807 * 1-规划伺服模式
808 * 2-透传模式(直接下发)
809 * 3-透传模式(缓存)
810 * @return
811 *
812 * @par JSON-RPC请求示例
813 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setServoModeSelect","params":[0],"id":1}
814 *
815 * @par JSON-RPC响应示例
816 * {"id":1,"jsonrpc":"2.0","result":0}
817 *
818 */
819 int setServoModeSelect(int mode);
820
821 /**
822 * 获取伺服运动模式
823 *
824 * @return
825 *
826 * @par JSON-RPC请求示例
827 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getServoModeSelect","params":[],"id":1}
828 *
829 * @par JSON-RPC响应示例
830 * {"id":1,"jsonrpc":"2.0","result":0}
831 *
832 */
834
835 /**
836 * 关节空间伺服
837 *
838 * 目前可用参数只有 q 和 t;
839 * @param q 关节角, 单位 rad,
840 * @param a 加速度, 单位 rad/s^2,
841 * @param v 速度,单位 rad/s,
842 * @param t 运行时间,单位 s \n
843 * t 值越大,机器臂运动越慢,反之,运动越快;
844 * 该参数最优值为连续调用 servoJoint 接口的间隔时间。
845 * @param lookahead_time 前瞻时间,单位 s \n
846 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
847 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
848 * 该参数最优值为一个控制周期。
849 * @param gain 比例增益
850 * 跟踪目标位置的比例增益[100, 200],
851 * 用于控制运动的顺滑性和精度,
852 * 比例增益越大,到达目标位置的时间越长,超调量越小。
853 *
854 * @retval 0 成功
855 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
856 * Normal、ReducedMode、Recovery 状态
857 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
858 * @retval AUBO_BUSY(3) 上一条指令正在执行中
859 * @retval -AUBO_BAD_STATE(-1)
860 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
861 * 未找到,或者当前机器人模式非 Running
862 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
863 * @retval -AUBO_INVL_ARGUMENT(-5) 轨迹位置超限或速度超限
864 * @retval -AUBO_REQUEST_IGNORE(-13) 当前处于非 servo 模式
865
866 * @throws arcs::common_interface::AuboException
867 *
868 * @par Python函数原型
869 * servoJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
870 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
871 *
872 * @par Lua函数原型
873 * servoJoint(q: table, a: number, v: number, t: number, lookahead_time:
874 * number, gain: number) -> nil
875 *
876 * @par JSON-RPC请求示例
877 * {"jsonrpc":"2.0","method":"rob1.MotionControl.servoJoint","params":[[0,0,0,0,0,0],0,0,10,0,0],"id":1}
878 *
879 * @par JSON-RPC响应示例
880 * {"id":1,"jsonrpc":"2.0","result":-13}
881 *
882 */
883 int servoJoint(const std::vector<double> &q, double a, double v, double t,
884 double lookahead_time, double gain);
885
886 /**
887 * 笛卡尔空间伺服
888 *
889 * 目前可用参数只有 pose 和 t;
890 * @param pose 位姿, 单位 m,
891 * @param a 加速度, 单位 m/s^2,
892 * @param v 速度,单位 m/s,
893 * @param t 运行时间,单位 s \n
894 * t 值越大,机器臂运动越慢,反之,运动越快;
895 * 该参数最优值为连续调用 servoCartesian 接口的间隔时间。
896 * @param lookahead_time 前瞻时间,单位 s \n
897 * 指定机器臂开始减速前要运动的时长,用前瞻时间来平滑轨迹[0.03, 0.2],
898 * 当 lookahead_time 小于一个控制周期时,越小则超调量越大,
899 * 该参数最优值为一个控制周期。
900 * @param gain 比例增益
901 * 跟踪目标位置的比例增益[100, 200],
902 * 用于控制运动的顺滑性和精度,
903 * 比例增益越大,到达目标位置的时间越长,超调量越小。
904 *
905 * @retval 0 成功
906 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
907 * Normal、ReducedMode、Recovery 状态
908 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
909 * @retval AUBO_BUSY(3) 上一条指令正在执行中
910 * @retval -AUBO_BAD_STATE(-1)
911 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
912 * 未找到,或者当前机器人模式非 Running
913 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
914 * @retval -AUBO_INVL_ARGUMENT(-5) 轨迹位置超限或速度超限
915 * @retval -AUBO_REQUEST_IGNORE(-13) 当前处于非 servo 模式
916 * @retval -AUBO_IK_NO_CONVERGE(-23) 逆解计算不收敛,计算出错;
917 * @retval -AUBO_IK_OUT_OF_RANGE(-24) 逆解计算超出机器人最大限制;
918 * @retval AUBO_IK_CONFIG_DISMATCH(-25) 逆解输入配置存在错误;
919 * @retval -AUBO_IK_JACOBIAN_FAILED(-26) 逆解雅可比矩阵计算失败;
920 * @retval -AUBO_IK_NO_SOLU(-27) 目标点存在解析解,但均不满足选解条件;
921 * @retval -AUBO_IK_UNKOWN_ERROR(-28) 逆解返回未知类型错误;
922 *
923 * @throws arcs::common_interface::AuboException
924 *
925 * @par Python函数原型
926 * servoCartesian(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
927 * float, arg2: float, arg3: float, arg4: float, arg5: float) -> int
928 *
929 * @par Lua函数原型
930 * servoCartesian(pose: table, a: number, v: number, t: number,
931 * lookahead_time: number, gain: number) -> nil
932 *
933 * @par JSON-RPC请求示例
934 * {"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}
935 *
936 * @par JSON-RPC响应示例
937 * {"id":1,"jsonrpc":"2.0","result":-13}
938 *
939 */
940 int servoCartesian(const std::vector<double> &pose, double a, double v,
941 double t, double lookahead_time, double gain);
942
943 /**
944 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
945 *
946 * @param q
947 * @param extq
948 * @param t
949 * @param smooth_scale
950 * @param delay_sacle
951 * @return
952 */
953 int servoJointWithAxes(const std::vector<double> &q,
954 const std::vector<double> &extq, double a, double v,
955 double t, double lookahead_time, double gain);
956
957 int servoJointWithAxisGroup(const std::vector<double> &q, double a,
958 double v, double t, double lookahead_time,
959 double gain, const std::string &group_name,
960 const std::vector<double> &extq);
961
962 /**
963 * 伺服运动(带外部轴),用于执行离线轨迹、透传用户规划轨迹等
964 * 与 servoJointWithAxes 区别在于接收笛卡尔空间位姿而不是关节角度
965 * (由软件内部直接做逆解)
966 *
967 * @param pose
968 * @param extq
969 * @param t
970 * @param smooth_scale
971 * @param delay_sacle
972 * @return
973 */
974 int servoCartesianWithAxes(const std::vector<double> &pose,
975 const std::vector<double> &extq, double a,
976 double v, double t, double lookahead_time,
977 double gain);
978
979 int servoCartesianWithAxisGroup(const std::vector<double> &pose, double a,
980 double v, double t, double lookahead_time,
981 double gain, const std::string &group_name,
982 const std::vector<double> &extq);
983
984 /**
985 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
986 *
987 * @param q
988 * @param smooth_scale
989 * @param delay_sacle
990 * @return
991 *
992 * @par JSON-RPC请求示例
993 * {"jsonrpc":"2.0","method":"rob1.MotionControl.trackJoint","params":[[0,0,0,0,0,0],0.01,0.5,1],"id":1}
994 *
995 * @par JSON-RPC响应示例
996 * {"id":1,"jsonrpc":"2.0","result":0}
997 *
998 */
999 int trackJoint(const std::vector<double> &q, double t, double smooth_scale,
1000 double delay_sacle);
1001
1002 /**
1003 * 跟踪运动,用于执行离线轨迹、透传用户规划轨迹等
1004 * 与 trackJoint 区别在于接收笛卡尔空间位姿而不是关节角度
1005 * (由软件内部直接做逆解)
1006 *
1007 * @param pose
1008 * @param t
1009 * @param smooth_scale
1010 * @param delay_sacle
1011 * @return
1012 *
1013 * @par JSON-RPC请求示例
1014 * {"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}
1015 *
1016 * @par JSON-RPC响应示例
1017 * {"id":1,"jsonrpc":"2.0","result":0}
1018 *
1019 */
1020 int trackCartesian(const std::vector<double> &pose, double t,
1021 double smooth_scale, double delay_sacle);
1022
1023 /**
1024 * 关节空间跟随
1025 *
1026 * @note 暂未实现
1027 *
1028 * @throws arcs::common_interface::AuboException
1029 *
1030 * @par Python函数原型
1031 * followJoint(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
1032 *
1033 * @par Lua函数原型
1034 * followJoint(q: table) -> nil
1035 *
1036 */
1037 int followJoint(const std::vector<double> &q);
1038
1039 /**
1040 * 笛卡尔空间跟随
1041 *
1042 * @note 暂未实现
1043 *
1044 * @throws arcs::common_interface::AuboException
1045 *
1046 * @par Python函数原型
1047 * followLine(self: pyaubo_sdk.MotionControl, arg0: List[float]) -> int
1048 *
1049 * @par Lua函数原型
1050 * followLine(pose: table) -> nil
1051 *
1052 */
1053 int followLine(const std::vector<double> &pose);
1054
1055 /**
1056 * 关节空间速度跟随
1057 *
1058 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1059 *
1060 * @param qd 目标关节速度, 单位 rad/s
1061 * @param a 主轴的加速度, 单位 rad/s^2
1062 * @param t 函数返回所需要的时间, 单位 s \n
1063 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1064 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。\n
1065 * 如果没有达到目标速度,会减速到零。
1066 * 如果达到了目标速度就是按照目标速度匀速运动。
1067 * @retval 0 成功
1068 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1069 * Normal、ReducedMode、Recovery 状态
1070 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1071 * @retval -AUBO_BAD_STATE(-1)
1072 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1073 * 未找到,或者当前机器人模式非 Running
1074 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1075 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组qd的长度小于当前机器臂的自由度
1076 *
1077 * @throws arcs::common_interface::AuboException
1078 *
1079 * @par Python函数原型
1080 * speedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1081 * float, arg2: float) -> int
1082 *
1083 * @par Lua函数原型
1084 * speedJoint(qd: table, a: number, t: number) -> nil
1085 *
1086 * @par JSON-RPC请求示例
1087 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
1088 *
1089 * @par JSON-RPC响应示例
1090 * {"id":1,"jsonrpc":"2.0","result":0}
1091 *
1092 */
1093 int speedJoint(const std::vector<double> &qd, double a, double t);
1094
1095 /**
1096 * 关节空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
1097 *
1098 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1099 *
1100 * @param qd 目标关节速度, 单位 rad/s
1101 * @param a 主轴的加速度, 单位 rad/s^2
1102 * @param t 函数返回所需要的时间, 单位 s
1103 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1104 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1105 * 如果没有达到目标速度,会减速到零。
1106 * 如果达到了目标速度就是按照目标速度匀速运动。
1107 * @return 成功返回0; 失败返回错误码
1108 * AUBO_BUSY
1109 * -AUBO_INVL_ARGUMENT
1110 * -AUBO_BAD_STATE
1111 *
1112 * @throws arcs::common_interface::AuboException
1113 *
1114 * @par Python函数原型
1115 * resumeSpeedJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1116 * float, arg2: float) -> int
1117 *
1118 *
1119 * @par Lua函数原型
1120 * resumeSpeedJoint(q: table, a: number, t: number) -> nil
1121 *
1122 * @par JSON-RPC请求示例
1123 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedJoint","params":[[0.2,0,0,0,0,0],1.5,100],"id":1}
1124 *
1125 * @par JSON-RPC响应示例
1126 * {"id":1,"jsonrpc":"2.0","result":-1}
1127 *
1128 */
1129 int resumeSpeedJoint(const std::vector<double> &qd, double a, double t);
1130
1131 /**
1132 * 笛卡尔空间速度跟随
1133 *
1134 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1135 *
1136 * @param xd 工具速度, 单位 m/s
1137 * @param a 工具位置加速度, 单位 m/s^2
1138 * @param t 函数返回所需要的时间, 单位 s \n
1139 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1140 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1141 * 如果没有达到目标速度,会减速到零。
1142 * 如果达到了目标速度就是按照目标速度匀速运动。
1143 * @retval 0 成功
1144 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1145 * Normal、ReducedMode、Recovery 状态
1146 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1147 * @retval -AUBO_BAD_STATE(-1)
1148 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1149 * 未找到,或者当前机器人模式非 Running
1150 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1151 *
1152 * @throws arcs::common_interface::AuboException
1153 *
1154 * @par Python函数原型
1155 * speedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1156 * arg2: float) -> int
1157 *
1158 * @par Lua函数原型
1159 * speedLine(pose: table, a: number, t: number) -> nil
1160 *
1161 * @par JSON-RPC请求示例
1162 * {"jsonrpc":"2.0","method":"rob1.MotionControl.speedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
1163 *
1164 * @par JSON-RPC响应示例
1165 * {"id":1,"jsonrpc":"2.0","result":0}
1166 *
1167 */
1168 int speedLine(const std::vector<double> &xd, double a, double t);
1169
1170 /**
1171 * 笛卡尔空间速度跟随(机械臂运行工程时发生碰撞,通过此接口移动到安全位置)
1172 *
1173 * 当机械臂还没达到目标速度的时候,给一个新的目标速度,机械臂会立刻达到新的目标速度
1174 *
1175 * @param xd 工具速度, 单位 m/s
1176 * @param a 工具位置加速度, 单位 m/s^2
1177 * @param t 函数返回所需要的时间, 单位 s \n
1178 * 如果 t = 0,当达到目标速度的时候,函数将返回;
1179 * 反之,则经过 t 时间后,函数返回,不管是否达到目标速度。
1180 * 如果没有达到目标速度,会减速到零。
1181 * 如果达到了目标速度就是按照目标速度匀速运动。
1182 * @return 成功返回0; 失败返回错误码
1183 * -AUBO_BAD_STATE
1184 *
1185 * @throws arcs::common_interface::AuboException
1186 *
1187 * @par Python函数原型
1188 * resumeSpeedLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1189 * float, arg2: float) -> int
1190 *
1191 * @par Lua函数原型
1192 * resumeSpeedLine(pose: table, a: number, t: number) -> nil
1193 *
1194 * @par JSON-RPC请求示例
1195 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeSpeedLine","params":[[0.25,0,0,0,0,0],1.2,100],"id":1}
1196 *
1197 * @par JSON-RPC响应示例
1198 * {"id":1,"jsonrpc":"2.0","result":-1}
1199 *
1200 */
1201 int resumeSpeedLine(const std::vector<double> &xd, double a, double t);
1202
1203 /**
1204 * 在关节空间做样条插值
1205 *
1206 * @param q 关节角度,如果传入参数维度为0,表示样条运动结束
1207 * @param a 加速度, 单位 rad/s^2,
1208 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
1209 * @param v 速度, 单位 rad/s,
1210 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
1211 * @param duration
1212 * @return 成功返回0; 失败返回错误码
1213 * AUBO_BUSY
1214 * AUBO_BAD_STATE
1215 * -AUBO_BAD_STATE
1216 *
1217 * @throws arcs::common_interface::AuboException
1218 *
1219 * @par Python函数原型
1220 * moveSpline(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1221 * float, arg2: float, arg3: float) -> int
1222 *
1223 * @par Lua函数原型
1224 * moveSpline(q: table, a: number, v: number, duration: number) -> nil
1225 *
1226 * @par JSON-RPC请求示例
1227 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpline","params":[[0,0,0,0,0,0],1,1,0],"id":1}
1228 *
1229 * @par JSON-RPC响应示例
1230 * {"id":1,"jsonrpc":"2.0","result":0}
1231 *
1232 */
1233 int moveSpline(const std::vector<double> &q, double a, double v,
1234 double duration);
1235
1236 /**
1237 * 添加关节运动
1238 *
1239 * @param q 关节角, 单位 rad
1240 * @param a 加速度, 单位 rad/s^2,
1241 * 最大值可通过RobotConfig类中的接口getJointMaxAccelerations()来获取
1242 * @param v 速度, 单位 rad/s,
1243 * 最大值可通过RobotConfig类中的接口getJointMaxSpeeds()来获取
1244 * @param blend_radius 交融半径, 单位 m
1245 * @param duration 运行时间,单位 s \n
1246 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1247 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1248 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1249 * 当 duration = 0的时候,
1250 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1251 * 如果duration不等于0,a 和 v 的值将被忽略。
1252 * @retval 0 成功
1253 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1254 * Normal、ReducedMode、Recovery 状态
1255 * @retval AUBO_QUEUE_FULL(2) 规划队列已满
1256 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1257 * @retval -AUBO_BAD_STATE(-1)
1258 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1259 * 未找到,或者当前机器人模式非 Running
1260 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1261 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组q的长度小于当前机器臂的自由度
1262 *
1263 * @throws arcs::common_interface::AuboException
1264 *
1265 * @par Python函数原型
1266 * moveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1267 * arg2: float, arg3: float, arg4: float) -> int
1268 *
1269 * @par Lua函数原型
1270 * moveJoint(q: table, a: number, v: number, blend_radius: number, duration:
1271 * number) -> nil
1272 *
1273 * @par JSON-RPC请求示例
1274 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveJoint","params":[[-2.05177,
1275 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0,0],"id":1}
1276 *
1277 * @par JSON-RPC响应示例
1278 * {"id":1,"jsonrpc":"2.0","result":0}
1279 *
1280 */
1281 int moveJoint(const std::vector<double> &q, double a, double v,
1282 double blend_radius, double duration);
1283
1284 /**
1285 * 机器人与外部轴同步运动
1286 *
1287 * @param group_name
1288 * @param q
1289 * @param a
1290 * @param v
1291 * @param blend_radius
1292 * @param duration
1293 * @return
1294 */
1295 int moveJointWithAxisGroup(const std::vector<double> &q, double a, double v,
1296 double blend_radius, double duration,
1297 const std::string &group_name,
1298 const std::vector<double> &extq);
1299
1300 /**
1301 * 通过关节运动移动到暂停点的位置
1302 *
1303 * @param q 关节角, 单位 rad
1304 * @param a 加速度, 单位 rad/s^2
1305 * @param v 速度, 单位 rad/s
1306 * @param duration 运行时间,单位 s \n
1307 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1308 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1309 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1310 * 当 duration = 0的时候,
1311 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1312 * 如果duration不等于0,a 和 v 的值将被忽略。
1313 * @return 成功返回0;失败返回错误码
1314 * -AUBO_INVL_ARGUMENT
1315 * -AUBO_BAD_STATE
1316 *
1317 * @throws arcs::common_interface::AuboException
1318 *
1319 * @par Python函数原型
1320 * resumeMoveJoint(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1321 * float, arg2: float, arg3: float) -> int
1322 *
1323 * @par Lua函数原型
1324 * resumeMoveJoint(q: table, a: number, v: number, duration: number) -> nil
1325 *
1326 * @par JSON-RPC请求示例
1327 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeMoveJoint","params":[[-2.05177,
1328 * -0.400292, 1.19625, 0.0285152, 1.57033, -2.28774],0.3,0.3,0],"id":1}
1329 *
1330 * @par JSON-RPC响应示例
1331 * {"id":1,"jsonrpc":"2.0","result":-1}
1332 */
1333 int resumeMoveJoint(const std::vector<double> &q, double a, double v,
1334 double duration);
1335
1336 /**
1337 * 添加直线运动
1338 *
1339 * @param pose 目标位姿
1340 * @param a 加速度(如果位置变化小于1mm,姿态变化大于 1e-4
1341 * rad,此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
1342 * 最大值可通过RobotConfig类中的接口getTcpMaxAccelerations()来获取
1343 * @param v 速度(如果位置变化小于1mm,姿态变化大于 1e-4
1344 * rad,此速度会被作为角速度,单位 rad/s.否则为线速度,单位 m/s)
1345 * 最大值可通过RobotConfig类中的接口getTcpMaxSpeeds()来获取
1346 * @param blend_radius 交融半径,单位 m,值介于0.001和1之间
1347 * @param duration 运行时间,单位 s \n
1348 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1349 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1350 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1351 * 当 duration = 0的时候,
1352 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1353 * 如果duration不等于0,a 和 v 的值将被忽略。
1354 * @retval 0 成功
1355 * @retval AUBO_BAD_STATE(1) 当前安全模式处于非
1356 * Normal、ReducedMode、Recovery 状态
1357 * @retval AUBO_QUEUE_FULL(2) 轨迹队列已满
1358 * @retval AUBO_BUSY(3) 上一条指令正在执行中
1359 * @retval -AUBO_BAD_STATE(-1)
1360 * 可能的原因包括但不限于:线程已分离、线程被终止、task_id
1361 * 未找到,或者当前机器人模式非 Running
1362 * @retval -AUBO_TIMEOUT(-4) 调用接口超时
1363 * @retval -AUBO_INVL_ARGUMENT(-5) 参数数组 pose
1364 * 的长度小于当前机器臂的自由度
1365 *
1366 * @throws arcs::common_interface::AuboException
1367 *
1368 * @par Python函数原型
1369 * moveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1: float,
1370 * arg2: float, arg3: float, arg4: float) -> int
1371 *
1372 * @par Lua函数原型
1373 * moveLine(pose: table, a: number, v: number, blend_radius: number,
1374 * duration: number) -> nil
1375 *
1376 * @par JSON-RPC请求示例
1377 * {"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}
1378 *
1379 * @par JSON-RPC响应示例
1380 * {"id":1,"jsonrpc":"2.0","result":0}
1381 *
1382 */
1383 int moveLine(const std::vector<double> &pose, double a, double v,
1384 double blend_radius, double duration);
1385
1386 /**
1387 * 直线运动与外部轴同步运动
1388 *
1389 * @param group_name
1390 * @param pose
1391 * @param a
1392 * @param v
1393 * @param blend_radius
1394 * @param duration
1395 * @return
1396 */
1397 int moveLineWithAxisGroup(const std::vector<double> &pose, double a,
1398 double v, double blend_radius, double duration,
1399 const std::string &group_name,
1400 const std::vector<double> &extq);
1401
1402 /**
1403 * 添加工艺运动
1404 *
1405 * @param pose
1406 * @param a
1407 * @param v
1408 * @param blend_radius
1409 * @return 成功返回0;失败返回错误码
1410 * AUBO_BAD_STATE
1411 * AUBO_BUSY
1412 * -AUBO_INVL_ARGUMENT
1413 * -AUBO_BAD_STATE
1414 *
1415 * @throws arcs::common_interface::AuboException
1416 *
1417 * @par JSON-RPC请求示例
1418 * {"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}
1419 *
1420 * @par JSON-RPC响应示例
1421 * {"id":1,"jsonrpc":"2.0","result":0}
1422 *
1423 */
1424 int moveProcess(const std::vector<double> &pose, double a, double v,
1425 double blend_radius);
1426
1427 /**
1428 * 通过直线运动移动到暂停点的位置
1429 *
1430 * @param pose 目标位姿
1431 * @param a 加速度, 单位 m/s^2
1432 * @param v 速度, 单位 m/s
1433 * @param duration 运行时间,单位 s \n
1434 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1435 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1436 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1437 * 当 duration = 0的时候,
1438 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1439 * 如果duration不等于0,a 和 v 的值将被忽略。
1440 * @return 成功返回0;失败返回错误码
1441 * -AUBO_INVL_ARGUMENT
1442 * -AUBO_BAD_STATE
1443 *
1444 * @throws arcs::common_interface::AuboException
1445 *
1446 * @par Python函数原型
1447 * resumeMoveLine(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1448 * float, arg2: float, arg3: float) -> int
1449 *
1450 * @par Lua函数原型
1451 * resumeMoveLine(pose: table, a: number, v: number,duration: number) -> nil
1452 *
1453 * @par JSON-RPC请求示例
1454 * {"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}
1455 *
1456 * @par JSON-RPC响应示例
1457 * {"id":1,"jsonrpc":"2.0","result":0}
1458 *
1459 */
1460 int resumeMoveLine(const std::vector<double> &pose, double a, double v,
1461 double duration);
1462
1463 /**
1464 * 添加圆弧运动
1465 *
1466 * @todo 可以由多段圆弧组成圆周运动
1467 *
1468 * @param via_pose 圆弧运动途中点的位姿
1469 * @param end_pose 圆弧运动结束点的位姿
1470 * @param a 加速度(如果via_pose与上一个路点位置变化小于1mm,姿态变化大于 1e-4
1471 * rad, 此加速度会被作为角加速度,单位 rad/s^2.否则为线加速度,单位 m/s^2)
1472 * @param v 速度(如果via_pose与上一个路点位置变化小于1mm, 姿态变化大于 1e-4
1473 * rad, 此速度会被作为角速度, 单位 rad / s.否则为线速度, 单位 m / s)
1474 * @param blend_radius 交融半径,单位: m
1475 * @param duration 运行时间,单位: s \n
1476 * 通常当给定了速度和加速度,便能够确定轨迹的运行时间。
1477 * 如果想延长轨迹的运行时间,便要设置 duration 这个参数。
1478 * duration 可以延长轨迹运动的时间,但是不能缩短轨迹时间。\n
1479 * 当 duration = 0 的时候,
1480 * 表示不指定运行时间,即没有明确完成运动的时间,将根据速度与加速度计算运行时间。
1481 * 如果duration不等于0,a 和 v 的值将被忽略。
1482 * @return 成功返回0;失败返回错误码
1483 * AUBO_BAD_STATE
1484 * AUBO_BUSY
1485 * -AUBO_INVL_ARGUMENT
1486 * -AUBO_BAD_STATE
1487 *
1488 * @throws arcs::common_interface::AuboException
1489 *
1490 * @par Python函数原型
1491 * moveCircle(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1492 * List[float], arg2: float, arg3: float, arg4: float, arg5: float) -> int
1493 *
1494 * @par Lua函数原型
1495 * moveCircle(via_pose: table, end_pose: table, a: number, v: number,
1496 * blend_radius: number, duration: number) -> nil
1497 *
1498 * @par JSON-RPC请求示例
1499 * {"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}
1500 *
1501 * @par JSON-RPC响应示例
1502 * {"id":1,"jsonrpc":"2.0","result":0}
1503 *
1504 */
1505 int moveCircle(const std::vector<double> &via_pose,
1506 const std::vector<double> &end_pose, double a, double v,
1507 double blend_radius, double duration);
1508
1509 /**
1510 * moveCircle 与外部轴同步运动
1511 *
1512 * @param group_name
1513 * @param via_pose
1514 * @param end_pose
1515 * @param a
1516 * @param v
1517 * @param blend_radius
1518 * @param duration
1519 * @return
1520 */
1521 int moveCircleWithAxisGroup(const std::vector<double> &via_pose,
1522 const std::vector<double> &end_pose, double a,
1523 double v, double blend_radius, double duration,
1524 const std::string &group_name,
1525 const std::vector<double> &extq);
1526
1527 /**
1528 * 设置圆弧路径模式
1529 *
1530 * @param mode 模式 \n
1531 * 0:工具姿态相对于圆弧路径点坐标系保持不变 \n
1532 * 1:姿态线性变化,绕着空间定轴转动,从起始点姿态变化到目标点姿态 \n
1533 * 2:从起点姿态开始经过中间点姿态,变化到目标点姿态
1534 * @return 成功返回0;失败返回错误码
1535 * AUBO_BAD_STATE
1536 * AUBO_BUSY
1537 * -AUBO_INVL_ARGUMENT
1538 * -AUBO_BAD_STATE
1539 *
1540 * @throws arcs::common_interface::AuboException
1541 *
1542 * @par Python函数原型
1543 * setCirclePathMode(self: pyaubo_sdk.MotionControl, arg0: int) -> int
1544 *
1545 * @par Lua函数原型
1546 * setCirclePathMode(mode: number) -> nil
1547 *
1548 * @par JSON-RPC请求示例
1549 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setCirclePathMode","params":[0],"id":1}
1550 *
1551 * @par JSON-RPC响应示例
1552 * {"id":1,"jsonrpc":"2.0","result":0}
1553 *
1554 */
1555 int setCirclePathMode(int mode);
1556
1557 /**
1558 * 高级圆弧或者圆周运动
1559 *
1560 * @param param 圆周运动参数
1561 * @return 成功返回0;失败返回错误码
1562 * AUBO_BAD_STATE
1563 * AUBO_BUSY
1564 * -AUBO_INVL_ARGUMENT
1565 * -AUBO_BAD_STATE
1566 *
1567 * @throws arcs::common_interface::AuboException
1568 *
1569 * @par Python函数原型
1570 * moveCircle2(self: pyaubo_sdk.MotionControl, arg0:
1571 * arcs::common_interface::CircleParameters) -> int
1572 *
1573 * @par Lua函数原型
1574 * moveCircle2(param: table) -> nil
1575 *
1576 * @par JSON-RPC请求示例
1577 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveCircle2","params":[{"pose_via":[0.440164,-0.00249391,0.398658,2.45651,0,1.570],
1578 * "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,
1579 * "spiral":0,"direction":0,"loop_times":0}],"id":1}
1580 *
1581 * @par JSON-RPC响应示例
1582 * {"id":1,"jsonrpc":"2.0","result":0}
1583 *
1584 */
1586
1587 /**
1588 * 新建一个路径点缓存
1589 *
1590 * @param name 指定路径的名字
1591 * @param type 路径的类型 \n
1592 * 1: toppra 时间最优路径规划 \n
1593 * 2: cubic_spline(录制的轨迹) \n
1594 * 3: 关节B样条插值,最少三个点
1595 * @param size 缓存区大小
1596 * @return 新建成功返回 AUBO_OK(0)
1597 *
1598 * @throws arcs::common_interface::AuboException
1599 *
1600 * @par Python函数原型
1601 * pathBufferAlloc(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
1602 * arg2: int) -> int
1603 *
1604 * @par Lua函数原型
1605 * pathBufferAlloc(name: string, type: number, size: number) -> nil
1606 *
1607 * @par JSON-RPC请求示例
1608 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferAlloc","params":["rec",2,3],"id":1}
1609 *
1610 * @par JSON-RPC响应示例
1611 * {"id":1,"jsonrpc":"2.0","result":0}
1612 *
1613 */
1614 int pathBufferAlloc(const std::string &name, int type, int size);
1615
1616 /**
1617 * 向路径缓存添加路点
1618 *
1619 * @param name 路径缓存的名字
1620 * @param waypoints 路点
1621 * @return 成功返回0;失败返回错误码
1622 * -AUBO_INVL_ARGUMENT
1623 * -AUBO_BAD_STATE
1624 *
1625 * @throws arcs::common_interface::AuboException
1626 *
1627 * @par Python函数原型
1628 * pathBufferAppend(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1629 * List[List[float]]) -> int
1630 *
1631 * @par Lua函数原型
1632 * pathBufferAppend(name: string, waypoints: table) -> nil
1633 *
1634 * @par JSON-RPC请求示例
1635 * {"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}
1636 *
1637 * @par JSON-RPC响应示例
1638 * {"id":1,"jsonrpc":"2.0","result":0}
1639 *
1640 */
1641 int pathBufferAppend(const std::string &name,
1642 const std::vector<std::vector<double>> &waypoints);
1643
1644 /**
1645 * 计算、优化等耗时操作,传入的参数相同时不会重新计算
1646 *
1647 * @param name 通过pathBufferAlloc新建的路径点缓存的名字
1648 * @param a 关节加速度限制,需要和机器人自由度大小相同,单位 rad/s^2
1649 * @param v 关节速度限制,需要和机器人自由度大小相同,单位 rad/s
1650 * @param t 时间 \n
1651 * pathBufferAlloc 这个接口分配内存的时候要指定类型,
1652 * 根据pathBufferAlloc这个接口的类型:\n
1653 * 类型为1时,表示运动持续时间\n
1654 * 类型为2时,表示采样时间间隔\n
1655 * 类型为3时:t表示运动持续时间\n
1656 * 若 t=0, 则由使用软件内部默认的时间(推荐使用)\n
1657 * 若 t!=0, t需要设置为 路径点数*相邻点时间间隔(points *
1658 * interval,interval >= 0.01)
1659 * @return 成功返回0;失败返回错误码
1660 * -AUBO_INVL_ARGUMENT
1661 * -AUBO_BAD_STATE
1662 *
1663 * @throws arcs::common_interface::AuboException
1664 *
1665 * @par Python函数原型
1666 * pathBufferEval(self: pyaubo_sdk.MotionControl, arg0: str, arg1:
1667 * List[float], arg2: List[float], arg3: float) -> int
1668 *
1669 * @par Lua函数原型
1670 * pathBufferEval(name: string, a: table, v: table, t: number) -> nil
1671 *
1672 * @par JSON-RPC请求示例
1673 * {"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}
1674 *
1675 * @par JSON-RPC响应示例
1676 * {"id":1,"jsonrpc":"2.0","result":0}
1677 *
1678 */
1679 int pathBufferEval(const std::string &name, const std::vector<double> &a,
1680 const std::vector<double> &v, double t);
1681
1682 /**
1683 * 指定名字的buffer是否有效
1684 *
1685 * buffer需要满足三个条件有效: \n
1686 * 1、buffer存在,已经分配过内存 \n
1687 * 2、传进buffer的点要大于等于buffer的大小 \n
1688 * 3、要执行一次pathBufferEval
1689 *
1690 * @param name buffer的名字
1691 * @return 有效返回true; 无效返回false
1692 *
1693 * @throws arcs::common_interface::AuboException
1694 *
1695 * @par Python函数原型
1696 * pathBufferValid(self: pyaubo_sdk.MotionControl, arg0: str) -> bool
1697 *
1698 * @par Lua函数原型
1699 * pathBufferValid(name: string) -> boolean
1700 *
1701 * @par JSON-RPC请求示例
1702 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferValid","params":["rec"],"id":1}
1703 *
1704 * @par JSON-RPC响应示例
1705 * {"id":1,"jsonrpc":"2.0","result":false}
1706 *
1707 */
1708 bool pathBufferValid(const std::string &name);
1709
1710 /**
1711 * 释放路径缓存
1712 *
1713 * @param name 缓存路径的名字
1714 * @return 成功返回0;失败返回错误码
1715 * -AUBO_INVL_ARGUMENT
1716 * -AUBO_BAD_STATE
1717 *
1718 * @throws arcs::common_interface::AuboException
1719 *
1720 * @par Python函数原型
1721 * pathBufferFree(self: pyaubo_sdk.MotionControl, arg0: str) -> int
1722 *
1723 * @par Lua函数原型
1724 * pathBufferFree(name: string) -> nil
1725 *
1726 * @par JSON-RPC请求示例
1727 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferFree","params":["rec"],"id":1}
1728 *
1729 * @par JSON-RPC响应示例
1730 * {"id":1,"jsonrpc":"2.0","result":-5}
1731 *
1732 */
1733 int pathBufferFree(const std::string &name);
1734
1735 /**
1736 * 关节空间路径滤波器
1737 *
1738 * @brief pathBufferFilter
1739 *
1740 * @param name 缓存路径的名称
1741 * @param order 滤波器阶数(一般取2)
1742 * @param fd 截止频率,越小越光滑,但是延迟会大(一般取3-20)
1743 * @param fs 离散数据的采样频率(一般取20-500)
1744 *
1745 * @return 成功返回0
1746 *
1747 * @throws arcs::common_interface::AuboException
1748 *
1749 * @par Python函数原型
1750 * pathBufferFilter(self: pyaubo_sdk.MotionControl, arg0: str, arg1: int,
1751 * arg2: float, arg3: float) -> int
1752 *
1753 * @par Lua函数原型
1754 * pathBufferFilter(name: string, order: number, fd: number, fs:number) ->
1755 * nil
1756 */
1757 int pathBufferFilter(const std::string &name, int order, double fd,
1758 double fs);
1759
1760 /**
1761 * 列出所有缓存路径的名字
1762 *
1763 * @return 返回所有缓存路径的名字
1764 *
1765 * @throws arcs::common_interface::AuboException
1766 *
1767 * @par Python函数原型
1768 * pathBufferList(self: pyaubo_sdk.MotionControl) -> List[str]
1769 *
1770 * @par Lua函数原型
1771 * pathBufferList() -> table
1772 *
1773 * @par JSON-RPC请求示例
1774 * {"jsonrpc":"2.0","method":"rob1.MotionControl.pathBufferList","params":[],"id":1}
1775 *
1776 * @par JSON-RPC响应示例
1777 * {"id":1,"jsonrpc":"2.0","result":[]}
1778 *
1779 */
1780 std::vector<std::string> pathBufferList();
1781
1782 /**
1783 * 执行缓存的路径
1784 *
1785 * @param name 缓存路径的名字
1786 * @return 成功返回0;失败返回错误码
1787 * -AUBO_INVL_ARGUMENT
1788 * -AUBO_BAD_STATE
1789 *
1790 * @throws arcs::common_interface::AuboException
1791 *
1792 * @par Python函数原型
1793 * movePathBuffer(self: pyaubo_sdk.MotionControl, arg0: str) -> int
1794 *
1795 * @par Lua函数原型
1796 * movePathBuffer(name: string) -> nil
1797 *
1798 * @par JSON-RPC请求示例
1799 * {"jsonrpc":"2.0","method":"rob1.MotionControl.movePathBuffer","params":["rec"],"id":1}
1800 *
1801 * @par JSON-RPC响应示例
1802 * {"id":1,"jsonrpc":"2.0","result":0}
1803 *
1804 */
1805 int movePathBuffer(const std::string &name);
1806
1807 /**
1808 * 相贯线接口
1809 *
1810 * @param pose由三个示教位姿组成(首先需要运动到起始点,起始点的要求:过主圆柱
1811 * 柱体轴心且与子圆柱体轴线平行的平面与子圆柱体在底部的交点)
1812 * p1:过子圆柱体轴线且与大圆柱体轴线平行的平面,与小圆柱体在左侧顶部的交点
1813 * p2:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在左侧底部的交点
1814 * p3:过子圆柱体轴线且与大圆柱体轴线平行的平面,与大圆柱体在右侧底部的交点
1815 * @param v:速度
1816 * @param a:加速度
1817 * @param main_pipe_radius: 主圆柱体半径
1818 * @param sub_pipe_radius: 子圆柱体半径
1819 * @param normal_distance: 两圆柱体轴线距离
1820 * @param normal_alpha: 两圆柱体轴线的夹角
1821 *
1822 * @return 成功返回0;失败返回错误码
1823 * AUBO_BUSY
1824 * AUBO_BAD_STATE
1825 * -AUBO_INVL_ARGUMENT
1826 * -AUBO_BAD_STATE
1827 *
1828 * @throws arcs::common_interface::AuboException
1829 *
1830 * @par Python函数原型
1831 * moveIntersection(self: pyaubo_sdk.MotionControl, arg0: List[float], arg1:
1832 float, arg2: float, arg3: float, arg4: float, arg5: float, arg6: float) ->
1833 int
1834 *
1835 * @par Lua函数原型
1836 * moveIntersection(poses: table, a: number, v: number,
1837 * main_pipe_radius:number, sub_pipe_radius: number,normal_distance:
1838 * number,normal_alpha: number,) -> nil
1839 */
1840 int moveIntersection(const std::vector<std::vector<double>> &poses,
1841 double a, double v, double main_pipe_radius,
1842 double sub_pipe_radius, double normal_distance,
1843 double normal_alpha);
1844 /**
1845 * 关节空间停止运动
1846 *
1847 * @param acc 关节加速度,单位: rad/s^2
1848 * @return 成功返回0;失败返回错误码
1849 * AUBO_BUSY
1850 * AUBO_BAD_STATE
1851 * -AUBO_INVL_ARGUMENT
1852 * -AUBO_BAD_STATE
1853 *
1854 * @throws arcs::common_interface::AuboException
1855 *
1856 * @par Python函数原型
1857 * stopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
1858 *
1859 * @par Lua函数原型
1860 * stopJoint(acc: number) -> nil
1861 *
1862 * @par JSON-RPC请求示例
1863 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopJoint","params":[31],"id":1}
1864 *
1865 * @par JSON-RPC响应示例
1866 * {"id":1,"jsonrpc":"2.0","result":0}
1867 *
1868 */
1869 int stopJoint(double acc);
1870
1871 /**
1872 * 关节空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedJoint接口移动到安全位置后需要停止时调用此接口)
1873 *
1874 * @param acc 关节加速度,单位: rad/s^2
1875 * @return 成功返回0;失败返回错误码
1876 * AUBO_BUSY
1877 * AUBO_BAD_STATE
1878 * -AUBO_INVL_ARGUMENT
1879 * -AUBO_BAD_STATE
1880 *
1881 * @throws arcs::common_interface::AuboException
1882 *
1883 * @par Python函数原型
1884 * resumeStopJoint(self: pyaubo_sdk.MotionControl, arg0: float) -> int
1885 *
1886 * @par Lua函数原型
1887 * resumeStopJoint(acc: number) -> nil
1888 *
1889 * @par JSON-RPC请求示例
1890 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopJoint","params":[31],"id":1}
1891 *
1892 * @par JSON-RPC响应示例
1893 * {"id":1,"jsonrpc":"2.0","result":-1}
1894 *
1895 */
1896 int resumeStopJoint(double acc);
1897
1898 /**
1899 * 笛卡尔空间停止运动
1900 *
1901 * @param acc 工具加速度, 单位: m/s^2
1902 * @param acc_rot
1903 * @return 成功返回0;失败返回错误码
1904 * AUBO_BUSY
1905 * AUBO_BAD_STATE
1906 * -AUBO_INVL_ARGUMENT
1907 * -AUBO_BAD_STATE
1908 *
1909 * @throws arcs::common_interface::AuboException
1910 *
1911 * @par Python函数原型
1912 * stopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float) -> int
1913 *
1914 * @par Lua函数原型
1915 * stopLine(acc: number, acc_rot: number) -> nil
1916 *
1917 * @par JSON-RPC请求示例
1918 * {"jsonrpc":"2.0","method":"rob1.MotionControl.stopLine","params":[10,10],"id":1}
1919 *
1920 * @par JSON-RPC响应示例
1921 * {"id":1,"jsonrpc":"2.0","result":0}
1922 *
1923 */
1924 int stopLine(double acc, double acc_rot);
1925
1926 /**
1927 * 笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
1928 *
1929 * @param acc 位置加速度, 单位: m/s^2
1930 * @param acc_rot 姿态加速度,单位: rad/s^2
1931 * @return 成功返回0;失败返回错误码
1932 * AUBO_BUSY
1933 * AUBO_BAD_STATE
1934 * -AUBO_INVL_ARGUMENT
1935 * -AUBO_BAD_STATE
1936 *
1937 * @throws arcs::common_interface::AuboException
1938 *
1939 * @par Python函数原型
1940 * resumeStopLine(self: pyaubo_sdk.MotionControl, arg0: float, arg1: float)
1941 * -> int
1942 *
1943 * @par Lua函数原型
1944 * resumeStopLine(acc: number, acc_rot: number) -> nil
1945 *
1946 * @par JSON-RPC请求示例
1947 * {"jsonrpc":"2.0","method":"rob1.MotionControl.resumeStopLine","params":[10,10],"id":1}
1948 *
1949 * @par JSON-RPC响应示例
1950 * {"id":1,"jsonrpc":"2.0","result":-1}
1951 *
1952 */
1953 int resumeStopLine(double acc, double acc_rot);
1954
1955 /**
1956 * 开始摆动: weaveStart 和 weaveEnd 的 moveLine/moveCircle 将根据 params
1957 * 进行摆动
1958 *
1959 * @param params Json字符串用于定义摆动参数
1960 * {
1961 * "type": <string>, // "SINE" "SPIRAL" "TRIANGLE" "TRAPEZOIDAL"
1962 * "step": <num>,
1963 * "amplitude": {<num>,<num>},
1964 * "hold_distance": {<num>,<num>},
1965 * "angle": <num>
1966 * "direction": <num>
1967 * }
1968 * @return 成功返回0;失败返回错误码
1969 * AUBO_BUSY
1970 * AUBO_BAD_STATE
1971 * -AUBO_INVL_ARGUMENT
1972 * -AUBO_BAD_STATE
1973 *
1974 * @throws arcs::common_interface::AuboException
1975 *
1976 */
1977 int weaveStart(const std::string &params);
1978
1979 /**
1980 * 结束摆动
1981 *
1982 * @return 成功返回0;失败返回错误码
1983 * AUBO_BUSY
1984 * AUBO_BAD_STATE
1985 * -AUBO_BAD_STATE
1986 *
1987 * @throws arcs::common_interface::AuboException
1988 *
1989 * @par JSON-RPC请求示例
1990 * {"jsonrpc":"2.0","method":"rob1.MotionControl.weaveEnd","params":[],"id":1}
1991 *
1992 * @par JSON-RPC响应示例
1993 * {"id":1,"jsonrpc":"2.0","result":0}
1994 *
1995 */
1997
1998 /**
1999 * 设置未来路径上点的采样时间间隔
2000 *
2001 * @param sample_time 采样时间间隔 单位: m/s^2
2002 * @return 成功返回0;失败返回错误码
2003 * AUBO_BUSY
2004 * AUBO_BAD_STATE
2005 * -AUBO_INVL_ARGUMENT
2006 * -AUBO_BAD_STATE
2007 *
2008 * @throws arcs::common_interface::AuboException
2009 *
2010 */
2011 int setFuturePointSamplePeriod(double sample_time);
2012
2013 /**
2014 * 获取未来路径上的轨迹点
2015 *
2016 * @return 路点(100ms * 10)
2017 *
2018 * @throws arcs::common_interface::AuboException
2019 *
2020 * @par JSON-RPC请求示例
2021 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getFuturePathPointsJoint","params":[],"id":1}
2022 *
2023 * @par JSON-RPC响应示例
2024 * {"id":1,"jsonrpc":"2.0","result":[]}
2025 *
2026 */
2027 std::vector<std::vector<double>> getFuturePathPointsJoint();
2028
2029 /**
2030 * 圆形传送带跟随
2031 *
2032 * @note 暂未实现
2033 *
2034 * @param encoder_id
2035 * 0-集成传感器
2036 *
2037 * @param center
2038 * @param tick_per_revo
2039 * @param rotate_tool
2040 * @return
2041 *
2042 * @throws arcs::common_interface::AuboException
2043 *
2044 */
2045 int conveyorTrackCircle(int encoder_id, const std::vector<double> &center,
2046 int tick_per_revo, bool rotate_tool);
2047
2048 /**
2049 * 线性传送带跟随
2050 *
2051 * @param encoder_id 预留
2052 * @param direction 传送带偏移方向
2053 * @param tick_per_meter 编码器脉冲值===>传送带每走每米的脉冲值
2054 * @return
2055 *
2056 * @throws arcs::common_interface::AuboException
2057 *
2058 * @par Python函数原型
2059 * conveyorTrackLine(self: pyaubo_sdk.MotionControl) -> int
2060 *
2061 * @par Lua函数原型
2062 * conveyorTrackLine -> boolean
2063 *
2064 * @par JSON-RPC请求示例
2065 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackLine","params":[1,[1.0,1.0,1.0,0.0,0.0,0.0],40000],"id":1}
2066 *
2067 * @par JSON-RPC响应示例
2068 * {"id":1,"jsonrpc":"2.0","result":0}
2069 *
2070 */
2071 int conveyorTrackLine(int encoder_id, const std::vector<double> &direction,
2072 int tick_per_meter);
2073
2074 /**
2075 * 终止传送带跟随
2076 *
2077 *
2078 * @param a 停止类型
2079 * a = 0.0 : 停止所有物品的跟随
2080 * a = 1.0 : 停止当前物品的跟随
2081 * @return
2082 *
2083 * @throws arcs::common_interface::AuboException
2084 *
2085 * @par Python函数原型
2086 * conveyorTrackStop(self: pyaubo_sdk.MotionControl) -> int
2087 *
2088 * @par Lua函数原型
2089 * conveyorTrackStop -> int
2090 *
2091 * @par JSON-RPC请求示例
2092 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackStop","params":1.0,"id":1}
2093 *
2094 * @par JSON-RPC响应示例
2095 * {"id":1,"jsonrpc":"2.0","result":0}
2096 *
2097 */
2098 int conveyorTrackStop(double a);
2099
2100 /**
2101 * 切换传送带追踪物品
2102 * 如果没有物品,会自动关闭传送带追踪功能
2103 *
2104 * @return 有物品返回true,反之则返回false
2105 *
2106 * @throws arcs::common_interface::AuboException
2107 *
2108 * @param encoder_id 预留
2109 *
2110 * @par Python函数原型
2111 * conveyorTrackSwitch(self: pyaubo_sdk.MotionControl) -> bool
2112 *
2113 * @par Lua函数原型
2114 * conveyorTrackSwitch() -> boolean
2115 *
2116 * @par JSON-RPC请求示例
2117 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorTrackSwitch","params":[0],"id":1}
2118 *
2119 * @par JSON-RPC响应示例
2120 * {"id":1,"jsonrpc":"2.0","result":true}
2121 *
2122 */
2123 bool conveyorTrackSwitch(int encoder_id);
2124
2125 /**
2126 * 获取传送带上还未追踪的工件数量
2127 *
2128 * @return 返回物品在传送带上的工件数量
2129 *
2130 * @throws arcs::common_interface::AuboException
2131 *
2132 * @par Python函数原型
2133 * getConveyorItemNums(self: pyaubo_sdk.MotionControl) -> int
2134 *
2135 * @par Lua函数原型
2136 * getConveyorItemNums() -> number
2137 *
2138 * @par JSON-RPC请求示例
2139 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getConveyorItemNums","params":[],"id":1}
2140 *
2141 * @par JSON-RPC响应示例
2142 * {"id":1,"jsonrpc":"2.0","result":{2}}
2143 *
2144 */
2146
2147 /**
2148 * 增加传送带上检测到的物品
2149 *
2150 * @param encoder_id 预留
2151 * @return
2152 *
2153 * @throws arcs::common_interface::AuboException
2154 *
2155 * @par Python函数原型
2156 * conveyorCreatItem(self: pyaubo_sdk.MotionControl, arg0: int) -> int
2157 *
2158 * @par Lua函数原型
2159 * conveyorCreatItem(id: number) -> number
2160 *
2161 * @par JSON-RPC请求示例
2162 * {"jsonrpc":"2.0","method":"rob1.MotionControl.conveyorCreatItem","params":[0],"id":1}
2163 *
2164 * @par JSON-RPC响应示例
2165 * {"id":1,"jsonrpc":"2.0","result":0.0}
2166 *
2167 */
2168 int conveyorCreatItem(int encoder_id);
2169
2170 /**
2171 * 设置传送带跟踪的补偿值
2172 *
2173 * @param comp 传送带补偿值
2174 * @return
2175 *
2176 * @throws arcs::common_interface::AuboException
2177 *
2178 * @par Python函数原型
2179 * setConveyorCompensate(self: pyaubo_sdk.MotionControl, arg0: float) ->
2180 * float
2181 *
2182 * @par Lua函数原型
2183 * setConveyorCompensate(comp: number) -> number
2184 *
2185 * @par JSON-RPC请求示例
2186 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setConveyorCompensate","params":[0.1],"id":1}
2187 *
2188 * @par JSON-RPC响应示例
2189 * {"id":1,"jsonrpc":"2.0","result":0.0}
2190 *
2191 */
2192 int conveyorTrackCompensate(double comp);
2193
2194 /**
2195 * 螺旋线运动
2196 *
2197 * @param param 封装的参数
2198 * @param blend_radius
2199 * @param v
2200 * @param a
2201 * @param t
2202 * @return 成功返回0;失败返回错误码
2203 * AUBO_BUSY
2204 * AUBO_BAD_STATE
2205 * -AUBO_INVL_ARGUMENT
2206 * -AUBO_BAD_STATE
2207 *
2208 * @throws arcs::common_interface::AuboException
2209 *
2210 * @par JSON-RPC请求示例
2211 * {"jsonrpc":"2.0","method":"rob1.MotionControl.moveSpiral",
2212 * "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}
2213 *
2214 * @par JSON-RPC响应示例
2215 * {"id":1,"jsonrpc":"2.0","result":0}
2216 *
2217 */
2218 int moveSpiral(const SpiralParameters &param, double blend_radius, double v,
2219 double a, double t);
2220
2221 /**
2222 * 获取前瞻段数
2223 *
2224 * @return 返回前瞻段数
2225 *
2226 * @throws arcs::common_interface::AuboException
2227 *
2228 * @par Python函数原型
2229 * getLookAheadSize(self: pyaubo_sdk.MotionControl) -> int
2230 *
2231 * @par Lua函数原型
2232 * getLookAheadSize() -> number
2233 *
2234 * @par JSON-RPC请求示例
2235 * {"jsonrpc":"2.0","method":"rob1.MotionControl.getLookAheadSize","params":[],"id":1}
2236 *
2237 * @par JSON-RPC响应示例
2238 * {"id":1,"jsonrpc":"2.0","result":1}
2239 *
2240 */
2242
2243 /**
2244 * 设置前瞻段数
2245 * 1.对于有较高速度平稳性要求的任务,如数控加工,涂胶,焊接等匀速需求,较长的前瞻段数可以提供更优的速度规划,产生的运动会更加平滑;
2246 * 2.对于快速响应的抓取类任务,更倾向于较短的前瞻段数,以提高反应速度,但可能因为进给的路径不够及时导致速度波动很大.
2247 *
2248 * @return 成功返回0
2249 *
2250 * @throws arcs::common_interface::AuboException
2251 *
2252 * @par Python函数原型
2253 * setLookAheadSize(self: pyaubo_sdk.MotionControl, arg0: int) -> int
2254 *
2255 * @par Lua函数原型
2256 * setLookAheadSize(eqradius: number) -> number
2257 *
2258 * @par JSON-RPC请求示例
2259 * {"jsonrpc":"2.0","method":"rob1.MotionControl.setLookAheadSize","params":[1],"id":1}
2260 *
2261 * @par JSON-RPC响应示例
2262 * {"id":1,"jsonrpc":"2.0","result":0}
2263 *
2264 */
2265 int setLookAheadSize(int size);
2266
2267protected:
2268 void *d_;
2269};
2270using MotionControlPtr = std::shared_ptr<MotionControl>;
2271} // namespace common_interface
2272} // namespace arcs
2273
2274#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 stopJoint(double acc)
关节空间停止运动
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 clearPath()
ClearPath (Clear Path) clears the whole motion path on the current motion path level (base level or S...
bool conveyorTrackSwitch(int encoder_id)
切换传送带追踪物品 如果没有物品,会自动关闭传送带追踪功能
std::vector< std::vector< double > > getFuturePathPointsJoint()
获取未来路径上的轨迹点
int conveyorTrackStop(double a)
终止传送带跟随
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)
新建一个路径点缓存
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()
getPauseJointPositions
int startMove()
StartMove is used to resume robot, external axes movement and belonging process after the movement ha...
int storePath(bool keep_sync)
storePath
int moveJoint(const std::vector< double > &q, double a, double v, double blend_radius, double duration)
添加关节运动
bool isBlending()
是否处交融区
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)
笛卡尔空间停止运动
int resumeStopLine(double acc, double acc_rot)
笛卡尔空间停止运动(机械臂运行工程时发生碰撞,通过resumeSpeedLine接口移动到安全位置后需要停止时调用此接口)
std::tuple< std::string, std::vector< double > > getWorkObjectHold()
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 is used to stop robot and external axes movements and any belonging process temporarily.
int getConveyorItemNums()
获取传送带上还未追踪的工件数量
int jointOffsetEnable()
关节偏移使能
ARCS_DEPRECATED bool isServoModeEnabled()
判断伺服模式是否使能 使用 getServoModeSelect 替代
int conveyorCreatItem(int encoder_id)
增加传送带上检测到的物品
int pathOffsetDisable()
路径偏移失能
int conveyorTrackCircle(int encoder_id, const std::vector< double > &center, int tick_per_revo, bool rotate_tool)
圆形传送带跟随
int conveyorTrackLine(int encoder_id, const std::vector< double > &direction, int tick_per_meter)
线性传送带跟随
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 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 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 speedLine(const std::vector< double > &xd, double a, double t)
笛卡尔空间速度跟随
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 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)
设置未来路径上点的采样时间间隔
double getEqradius()
获取等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动 可以通过 setEqradius 设置,默认为1
int setWorkObjectHold(const std::string &module_name, const std::vector< double > &mounting_pose)
当工件安装在另外一台机器人的末端或者外部轴上时,指定其名字和安装位置
int setEqradius(double eqradius)
设置等效半径,单位 m moveLine/moveCircle时,末端姿态旋转的角度等效到末端位置移动,数值越大,姿态旋转速度越快
int getExecId()
获取当前正在插补的运动指令段的ID
int setSpeedFraction(double fraction)
动态调整机器人运行速度和加速度比例 (0., 1.
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 conveyorTrackCompensate(double comp)
设置传送带跟踪的补偿值
int pathBufferEval(const std::string &name, const std::vector< double > &a, const std::vector< double > &v, double t)
计算、优化等耗时操作,传入的参数相同时不会重新计算
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样条插值,最少三个点,但是传入的是笛卡尔空间位姿 废弃,建议用6替代,现在实际是关节空间 CUBIC_SPLINE
@ PathBuffer_JointBSplineC
6:关节B样条插值,最少三个点,但是传入的是笛卡尔空间位姿
数据类型的定义