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