AUBO SDK  0.25.0
载入中...
搜索中...
未找到
robot_config.h
浏览该文件的文档.
1/** @file robot_config.h
2 * @brief 获取机器人配置接口,如获取DH参数、碰撞等级、安装位姿等等
3 */
4#ifndef AUBO_SDK_ROBOT_CONFIG_H
5#define AUBO_SDK_ROBOT_CONFIG_H
6
7#include <vector>
8#include <unordered_map>
9
10#include <aubo/global_config.h>
11#include <aubo/type_def.h>
12
13namespace arcs {
14namespace common_interface {
15
16class ARCS_ABI_EXPORT RobotConfig
17{
18public:
20 virtual ~RobotConfig();
21
22 /**
23 * \chinese
24 * 获取机器人的名字
25 *
26 * @return 返回机器人的名字
27 *
28 * @throws arcs::common_interface::AuboException
29 *
30 * @par Python函数原型
31 * getName(self: pyaubo_sdk.RobotConfig) -> str
32 *
33 * @par Lua函数原型
34 * getName() -> string
35 *
36 * @par JSON-RPC请求示例
37 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getName","params":[],"id":1}
38 *
39 * @par JSON-RPC响应示例
40 * {"id":1,"jsonrpc":"2.0","result":"rob1"}
41 * \endchinese
42 * \english
43 * Get the robot's name.
44 *
45 * @return The robot's name.
46 *
47 * @throws arcs::common_interface::AuboException
48 *
49 * @par Python function prototype
50 * getName(self: pyaubo_sdk.RobotConfig) -> str
51 *
52 * @par Lua function prototype
53 * getName() -> string
54 *
55 * @par JSON-RPC request example
56 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getName","params":[],"id":1}
57 *
58 * @par JSON-RPC response example
59 * {"id":1,"jsonrpc":"2.0","result":"rob1"}
60 * \endenglish
61 */
62 std::string getName();
63
64 /**
65 * \chinese
66 * 获取机器人的自由度(从硬件抽象层读取)
67 *
68 * @return 返回机器人的自由度
69 *
70 * @throws arcs::common_interface::AuboException
71 *
72 * @par Python函数原型
73 * getDof(self: pyaubo_sdk.RobotConfig) -> int
74 *
75 * @par Lua函数原型
76 * getDof() -> number
77 *
78 * @par JSON-RPC请求示例
79 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDof","params":[],"id":1}
80 *
81 * @par JSON-RPC响应示例
82 * {"id":1,"jsonrpc":"2.0","result":6}
83 * \endchinese
84 * \english
85 * Get the robot's degrees of freedom (from the hardware abstraction layer).
86 *
87 * @return The robot's degrees of freedom.
88 *
89 * @throws arcs::common_interface::AuboException
90 *
91 * @par Python function prototype
92 * getDof(self: pyaubo_sdk.RobotConfig) -> int
93 *
94 * @par Lua function prototype
95 * getDof() -> number
96 *
97 * @par JSON-RPC request example
98 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDof","params":[],"id":1}
99 *
100 * @par JSON-RPC response example
101 * {"id":1,"jsonrpc":"2.0","result":6}
102 * \endenglish
103 */
104 int getDof();
105
106 /**
107 * \chinese
108 * 获取机器人的伺服控制周期(从硬件抽象层读取)
109 *
110 * @return 机器人的伺服控制周期
111 *
112 * @throws arcs::common_interface::AuboException
113 *
114 * @par Python函数原型
115 * getCycletime(self: pyaubo_sdk.RobotConfig) -> float
116 *
117 * @par Lua函数原型
118 * getCycletime() -> number
119 *
120 * @par JSON-RPC请求示例
121 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getCycletime","params":[],"id":1}
122 *
123 * @par JSON-RPC响应示例
124 * {"id":1,"jsonrpc":"2.0","result":0.005}
125 * \endchinese
126 * \english
127 * Get the robot's servo control cycle time (from the hardware abstraction
128 * layer).
129 *
130 * @return The robot's servo control cycle time.
131 *
132 * @throws arcs::common_interface::AuboException
133 *
134 * @par Python function prototype
135 * getCycletime(self: pyaubo_sdk.RobotConfig) -> float
136 *
137 * @par Lua function prototype
138 * getCycletime() -> number
139 *
140 * @par JSON-RPC request example
141 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getCycletime","params":[],"id":1}
142 *
143 * @par JSON-RPC response example
144 * {"id":1,"jsonrpc":"2.0","result":0.005}
145 * \endenglish
146 */
147 double getCycletime();
148
149 /**
150 * \chinese
151 * 预设缓速模式下的速度缩减比例
152 *
153 * @param level 缓速等级 1, 2
154 * @param fraction
155 *
156 * @return 成功返回0;失败返回错误码
157 * AUBO_BUSY
158 * AUBO_BAD_STATE
159 * AUBO_INVL_ARGUMENT
160 * -AUBO_BAD_STATE
161 *
162 * @throws arcs::common_interface::AuboException
163 *
164 * @par JSON-RPC请求示例
165 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setSlowDownFraction","params":[1,0.8],"id":1}
166 *
167 * @par JSON-RPC响应示例
168 * {"id":1,"jsonrpc":"2.0","result":0}
169 * \endchinese
170 * \english
171 * Set the speed reduction ratio for the preset slow-down mode.
172 *
173 * @param level Slow-down level 1, 2
174 * @param fraction
175 *
176 * @return Returns 0 on success; error code on failure
177 * AUBO_BUSY
178 * AUBO_BAD_STATE
179 * AUBO_INVL_ARGUMENT
180 * -AUBO_BAD_STATE
181 *
182 * @throws arcs::common_interface::AuboException
183 *
184 * @par JSON-RPC request example
185 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setSlowDownFraction","params":[1,0.8],"id":1}
186 *
187 * @par JSON-RPC response example
188 * {"id":1,"jsonrpc":"2.0","result":0}
189 * \endenglish
190 */
191 int setSlowDownFraction(int level, double fraction);
192
193 /**
194 * \chinese
195 * 获取预设的缓速模式下的速度缩减比例
196 *
197 * @param level 缓速等级 1, 2
198 * @return 返回预设的缓速模式下的速度缩减比例
199 *
200 * @throws arcs::common_interface::AuboException
201 *
202 * @par JSON-RPC请求示例
203 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSlowDownFraction","params":[1],"id":1}
204 *
205 * @par JSON-RPC响应示例
206 * {"id":1,"jsonrpc":"2.0","result":0.5}
207 * \endchinese
208 * \english
209 * Get the speed reduction ratio for the preset slow-down mode.
210 *
211 * @param level Slow-down level 1, 2
212 * @return The speed reduction ratio for the preset slow-down mode.
213 *
214 * @throws arcs::common_interface::AuboException
215 *
216 * @par JSON-RPC request example
217 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSlowDownFraction","params":[1],"id":1}
218 *
219 * @par JSON-RPC response example
220 * {"id":1,"jsonrpc":"2.0","result":0.5}
221 * \endenglish
222 */
223 double getSlowDownFraction(int level);
224
225 /**
226 * \chinese
227 * 获取默认的工具端加速度,单位m/s^2
228 *
229 * @return 默认的工具端加速度
230 *
231 * @throws arcs::common_interface::AuboException
232 *
233 * @par Python函数原型
234 * getDefaultToolAcc(self: pyaubo_sdk.RobotConfig) -> float
235 *
236 * @par Lua函数原型
237 * getDefaultToolAcc() -> number
238 *
239 * @par JSON-RPC请求示例
240 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultToolAcc","params":[],"id":1}
241 *
242 * @par JSON-RPC响应示例
243 * {"id":1,"jsonrpc":"2.0","result":0.0}
244 * \endchinese
245 * \english
246 * Get the default tool acceleration, in m/s^2.
247 *
248 * @return The default tool acceleration.
249 *
250 * @throws arcs::common_interface::AuboException
251 *
252 * @par Python function prototype
253 * getDefaultToolAcc(self: pyaubo_sdk.RobotConfig) -> float
254 *
255 * @par Lua function prototype
256 * getDefaultToolAcc() -> number
257 *
258 * @par JSON-RPC request example
259 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultToolAcc","params":[],"id":1}
260 *
261 * @par JSON-RPC response example
262 * {"id":1,"jsonrpc":"2.0","result":0.0}
263 * \endenglish
264 */
266
267 /**
268 * \chinese
269 * 获取默认的工具端速度,单位m/s
270 *
271 * @return 默认的工具端速度
272 *
273 * @throws arcs::common_interface::AuboException
274 *
275 * @par Python函数原型
276 * getDefaultToolSpeed(self: pyaubo_sdk.RobotConfig) -> float
277 *
278 * @par Lua函数原型
279 * getDefaultToolSpeed() -> number
280 *
281 * @par JSON-RPC请求示例
282 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultToolSpeed","params":[],"id":1}
283 *
284 * @par JSON-RPC响应示例
285 * {"id":1,"jsonrpc":"2.0","result":0.0}
286 * \endchinese
287 * \english
288 * Get the default tool speed, in m/s.
289 *
290 * @return The default tool speed.
291 *
292 * @throws arcs::common_interface::AuboException
293 *
294 * @par Python function prototype
295 * getDefaultToolSpeed(self: pyaubo_sdk.RobotConfig) -> float
296 *
297 * @par Lua function prototype
298 * getDefaultToolSpeed() -> number
299 *
300 * @par JSON-RPC request example
301 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultToolSpeed","params":[],"id":1}
302 *
303 * @par JSON-RPC response example
304 * {"id":1,"jsonrpc":"2.0","result":0.0}
305 * \endenglish
306 */
308
309 /**
310 * \chinese
311 * 获取默认的关节加速度,单位rad/s^2
312 *
313 * @return 默认的关节加速度
314 *
315 * @throws arcs::common_interface::AuboException
316 *
317 * @par Python函数原型
318 * getDefaultJointAcc(self: pyaubo_sdk.RobotConfig) -> float
319 *
320 * @par Lua函数原型
321 * getDefaultJointAcc() -> number
322 *
323 * @par JSON-RPC请求示例
324 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultJointAcc","params":[],"id":1}
325 *
326 * @par JSON-RPC响应示例
327 * {"id":1,"jsonrpc":"2.0","result":0.0}
328 * \endchinese
329 * \english
330 * Get the default joint acceleration, in rad/s^2.
331 *
332 * @return The default joint acceleration.
333 *
334 * @throws arcs::common_interface::AuboException
335 *
336 * @par Python function prototype
337 * getDefaultJointAcc(self: pyaubo_sdk.RobotConfig) -> float
338 *
339 * @par Lua function prototype
340 * getDefaultJointAcc() -> number
341 *
342 * @par JSON-RPC request example
343 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultJointAcc","params":[],"id":1}
344 *
345 * @par JSON-RPC response example
346 * {"id":1,"jsonrpc":"2.0","result":0.0}
347 * \endenglish
348 */
350
351 /**
352 * \chinese
353 * 获取默认的关节速度,单位rad/s
354 *
355 * @return 默认的关节速度
356 *
357 * @throws arcs::common_interface::AuboException
358 *
359 * @par Python函数原型
360 * getDefaultJointSpeed(self: pyaubo_sdk.RobotConfig) -> float
361 *
362 * @par Lua函数原型
363 * getDefaultJointSpeed() -> number
364 *
365 * @par JSON-RPC请求示例
366 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultJointSpeed","params":[],"id":1}
367 *
368 * @par JSON-RPC响应示例
369 * {"id":1,"jsonrpc":"2.0","result":0.0}
370 * \endchinese
371 * \english
372 * Get the default joint speed, in rad/s.
373 *
374 * @return The default joint speed.
375 *
376 * @throws arcs::common_interface::AuboException
377 *
378 * @par Python function prototype
379 * getDefaultJointSpeed(self: pyaubo_sdk.RobotConfig) -> float
380 *
381 * @par Lua function prototype
382 * getDefaultJointSpeed() -> number
383 *
384 * @par JSON-RPC request example
385 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getDefaultJointSpeed","params":[],"id":1}
386 *
387 * @par JSON-RPC response example
388 * {"id":1,"jsonrpc":"2.0","result":0.0}
389 * \endenglish
390 */
392
393 /**
394 * \chinese
395 * 获取机器人类型代码
396 *
397 * @return 机器人类型代码
398 *
399 * @throws arcs::common_interface::AuboException
400 *
401 * @par Python函数原型
402 * getRobotType(self: pyaubo_sdk.RobotConfig) -> str
403 *
404 * @par Lua函数原型
405 * getRobotType() -> string
406 *
407 * @par JSON-RPC请求示例
408 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getRobotType","params":[],"id":1}
409 *
410 * @par JSON-RPC响应示例
411 * {"id":1,"jsonrpc":"2.0","result":"aubo_i5H"}
412 * \endchinese
413 * \english
414 * Get the robot type code.
415 *
416 * @return The robot type code.
417 *
418 * @throws arcs::common_interface::AuboException
419 *
420 * @par Python function prototype
421 * getRobotType(self: pyaubo_sdk.RobotConfig) -> str
422 *
423 * @par Lua function prototype
424 * getRobotType() -> string
425 *
426 * @par JSON-RPC request example
427 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getRobotType","params":[],"id":1}
428 *
429 * @par JSON-RPC response example
430 * {"id":1,"jsonrpc":"2.0","result":"aubo_i5H"}
431 * \endenglish
432 */
433 std::string getRobotType();
434
435 /**
436 * \chinese
437 * 获取机器人子类型代码
438 *
439 * @return 机器人子类型代码
440 *
441 * @throws arcs::common_interface::AuboException
442 *
443 * @par Python函数原型
444 * getRobotSubType(self: pyaubo_sdk.RobotConfig) -> str
445 *
446 * @par Lua函数原型
447 * getRobotSubType() -> string
448 *
449 * @par JSON-RPC请求示例
450 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getRobotSubType","params":[],"id":1}
451 *
452 * @par JSON-RPC响应示例
453 * {"id":1,"jsonrpc":"2.0","result":"B0"}
454 * \endchinese
455 * \english
456 * Get the robot sub-type code.
457 *
458 * @return The robot sub-type code.
459 *
460 * @throws arcs::common_interface::AuboException
461 *
462 * @par Python function prototype
463 * getRobotSubType(self: pyaubo_sdk.RobotConfig) -> str
464 *
465 * @par Lua function prototype
466 * getRobotSubType() -> string
467 *
468 * @par JSON-RPC request example
469 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getRobotSubType","params":[],"id":1}
470 *
471 * @par JSON-RPC response example
472 * {"id":1,"jsonrpc":"2.0","result":"B0"}
473 * \endenglish
474 */
475 std::string getRobotSubType();
476
477 /**
478 * \chinese
479 * 获取控制柜类型代码
480 *
481 * @return 控制柜类型代码
482 *
483 * @throws arcs::common_interface::AuboException
484 *
485 * @par Python函数原型
486 * getControlBoxType(self: pyaubo_sdk.RobotConfig) -> str
487 *
488 * @par Lua函数原型
489 * getControlBoxType() -> string
490 *
491 * @par JSON-RPC请求示例
492 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getControlBoxType","params":[],"id":1}
493 *
494 * @par JSON-RPC响应示例
495 * {"id":1,"jsonrpc":"2.0","result":"cb_ISStation"}
496 * \endchinese
497 * \english
498 * Get the control box type code.
499 *
500 * @return The control box type code.
501 *
502 * @throws arcs::common_interface::AuboException
503 *
504 * @par Python function prototype
505 * getControlBoxType(self: pyaubo_sdk.RobotConfig) -> str
506 *
507 * @par Lua function prototype
508 * getControlBoxType() -> string
509 *
510 * @par JSON-RPC request example
511 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getControlBoxType","params":[],"id":1}
512 *
513 * @par JSON-RPC response example
514 * {"id":1,"jsonrpc":"2.0","result":"cb_ISStation"}
515 * \endenglish
516 */
517 std::string getControlBoxType();
518
519 /**
520 * \chinese
521 * 设置安装位姿(机器人的基坐标系相对于世界坐标系) world->base
522 *
523 * 一般在多机器人系统中使用,默认为 [0,0,0,0,0,0]
524 *
525 * @param pose 安装位姿
526 * @return 成功返回0; 失败返回错误码
527 * AUBO_BUSY
528 * AUBO_BAD_STATE
529 * -AUBO_INVL_ARGUMENT
530 * -AUBO_BAD_STATE
531 *
532 * @throws arcs::common_interface::AuboException
533 *
534 * @par Python函数原型
535 * setMountingPose(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
536 *
537 * @par Lua函数原型
538 * setMountingPose(pose: table) -> nil
539 *
540 * @par JSON-RPC请求示例
541 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setMountingPose","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
542 *
543 * @par JSON-RPC响应示例
544 * {"id":1,"jsonrpc":"2.0","result":0}
545 * \endchinese
546 * \english
547 * Set the mounting pose (robot base coordinate system relative to world
548 * coordinate system) world->base
549 *
550 * Typically used in multi-robot systems, default is [0,0,0,0,0,0]
551 *
552 * @param pose Mounting pose
553 * @return Returns 0 on success; error code on failure
554 * AUBO_BUSY
555 * AUBO_BAD_STATE
556 * -AUBO_INVL_ARGUMENT
557 * -AUBO_BAD_STATE
558 *
559 * @throws arcs::common_interface::AuboException
560 *
561 * @par Python function prototype
562 * setMountingPose(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
563 *
564 * @par Lua function prototype
565 * setMountingPose(pose: table) -> nil
566 *
567 * @par JSON-RPC request example
568 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setMountingPose","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
569 *
570 * @par JSON-RPC response example
571 * {"id":1,"jsonrpc":"2.0","result":0}
572 * \endenglish
573 */
574 int setMountingPose(const std::vector<double> &pose);
575
576 /**
577 * \chinese
578 * 获取安装位姿(机器人的基坐标系相对于世界坐标系)
579 *
580 * @return 安装位姿
581 *
582 * @throws arcs::common_interface::AuboException
583 *
584 * @par Python函数原型
585 * getMountingPose(self: pyaubo_sdk.RobotConfig) -> List[float]
586 *
587 * @par Lua函数原型
588 * getMountingPose() -> table
589 *
590 * @par JSON-RPC请求示例
591 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getMountingPose","params":[],"id":1}
592 *
593 * @par JSON-RPC响应示例
594 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
595 * \endchinese
596 * \english
597 * Get the mounting pose (robot base coordinate system relative to world
598 * coordinate system)
599 *
600 * @return Mounting pose
601 *
602 * @throws arcs::common_interface::AuboException
603 *
604 * @par Python function prototype
605 * getMountingPose(self: pyaubo_sdk.RobotConfig) -> List[float]
606 *
607 * @par Lua function prototype
608 * getMountingPose() -> table
609 *
610 * @par JSON-RPC request example
611 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getMountingPose","params":[],"id":1}
612 *
613 * @par JSON-RPC response example
614 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
615 * \endenglish
616 */
617 std::vector<double> getMountingPose();
618
619 /**
620 * \chinese
621 * 将机器人绑定到一个坐标系,如果这个坐标系是运动的,那机器人也会跟着运动
622 * 应用于地轨或者龙门
623 * 这个函数调用的时候 frame 和 ROBOTBASE 的相对关系就固定了
624 * \endchinese
625 * \english
626 * Attach the robot base to a coordinate frame. If this frame moves, the
627 * robot will move accordingly. Used for applications like ground rails or
628 * gantries. When this function is called, the relationship between the
629 * frame and ROBOTBASE is fixed. \endenglish
630 */
631 int attachRobotBaseTo(const std::string &frame);
632 std::string getRobotBaseParent();
633
634 /**
635 * \chinese
636 * 设置工件数据,编程点位都是基于工件坐标系
637 * \endchinese
638 * \english
639 * Set work object data. All programmed points are based on the work object
640 * coordinate system. \endenglish
641 */
642
644
645 /**
646 * \chinese
647 * 设置碰撞灵敏度等级
648 * 数值越大越灵敏
649 *
650 * @param level 碰撞灵敏度等级
651 * 0: 关闭碰撞检测功能
652 * 1~9: 碰撞灵敏等级
653 * @return 成功返回0; 失败返回错误码
654 * AUBO_BUSY
655 * AUBO_BAD_STATE
656 * -AUBO_INVL_ARGUMENT
657 * -AUBO_BAD_STATE
658 *
659 * @throws arcs::common_interface::AuboException
660 *
661 * @par Python函数原型
662 * setCollisionLevel(self: pyaubo_sdk.RobotConfig, arg0: int) -> int
663 *
664 * @par Lua函数原型
665 * setCollisionLevel(level: number) -> nil
666 *
667 * @par JSON-RPC请求示例
668 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setCollisionLevel","params":[6],"id":1}
669 *
670 * @par JSON-RPC响应示例
671 * {"id":1,"jsonrpc":"2.0","result":0}
672 * \endchinese
673 * \english
674 * Set the collision sensitivity level.
675 * The higher the value, the more sensitive.
676 *
677 * @param level Collision sensitivity level
678 * 0: Disable collision detection
679 * 1~9: Collision sensitivity levels
680 * @return Returns 0 on success; error code on failure
681 * AUBO_BUSY
682 * AUBO_BAD_STATE
683 * -AUBO_INVL_ARGUMENT
684 * -AUBO_BAD_STATE
685 *
686 * @throws arcs::common_interface::AuboException
687 *
688 * @par Python function prototype
689 * setCollisionLevel(self: pyaubo_sdk.RobotConfig, arg0: int) -> int
690 *
691 * @par Lua function prototype
692 * setCollisionLevel(level: number) -> nil
693 *
694 * @par JSON-RPC request example
695 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setCollisionLevel","params":[6],"id":1}
696 *
697 * @par JSON-RPC response example
698 * {"id":1,"jsonrpc":"2.0","result":0}
699 * \endenglish
700 */
701 int setCollisionLevel(int level);
702
703 /**
704 * \chinese
705 * 获取碰撞灵敏度等级
706 *
707 * @return 碰撞灵敏度等级
708 *
709 * @throws arcs::common_interface::AuboException
710 *
711 * @par Python函数原型
712 * getCollisionLevel(self: pyaubo_sdk.RobotConfig) -> int
713 *
714 * @par Lua函数原型
715 * getCollisionLevel() -> number
716 *
717 * @par JSON-RPC请求示例
718 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getCollisionLevel","params":[],"id":1}
719 *
720 * @par JSON-RPC响应示例
721 * {"id":1,"jsonrpc":"2.0","result":6}
722 * \endchinese
723 * \english
724 * Get the collision sensitivity level.
725 *
726 * @return Collision sensitivity level.
727 *
728 * @throws arcs::common_interface::AuboException
729 *
730 * @par Python function prototype
731 * getCollisionLevel(self: pyaubo_sdk.RobotConfig) -> int
732 *
733 * @par Lua function prototype
734 * getCollisionLevel() -> number
735 *
736 * @par JSON-RPC request example
737 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getCollisionLevel","params":[],"id":1}
738 *
739 * @par JSON-RPC response example
740 * {"id":1,"jsonrpc":"2.0","result":6}
741 * \endenglish
742 */
744
745 /**
746 * \chinese
747 * 设置碰撞停止类型
748 *
749 * @param type 类型 \n
750 * 0: 碰撞后浮动,即碰撞之后进入拖动示教模式 \n
751 * 1: 碰撞后静止 \n
752 * 2: 碰撞后抱闸
753 *
754 * @return 成功返回0; 失败返回错误码
755 * AUBO_BUSY
756 * AUBO_BAD_STATE
757 * -AUBO_INVL_ARGUMENT
758 * -AUBO_BAD_STATE
759 *
760 * @throws arcs::common_interface::AuboException
761 *
762 * @par Python函数原型
763 * setCollisionStopType(self: pyaubo_sdk.RobotConfig, arg0: int) -> int
764 *
765 * @par Lua函数原型
766 * setCollisionStopType(type: number) -> nil
767 *
768 * @par JSON-RPC请求示例
769 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setCollisionStopType","params":[1],"id":1}
770 *
771 * @par JSON-RPC响应示例
772 * {"id":1,"jsonrpc":"2.0","result":0}
773 * \endchinese
774 * \english
775 * Set the collision stop type.
776 *
777 * @param type Type \n
778 * 0: Floating after collision, i.e., enters freedrive mode after collision
779 * \n 1: Stop after collision \n 2: Brake after collision
780 *
781 * @return Returns 0 on success; error code on failure
782 * AUBO_BUSY
783 * AUBO_BAD_STATE
784 * -AUBO_INVL_ARGUMENT
785 * -AUBO_BAD_STATE
786 *
787 * @throws arcs::common_interface::AuboException
788 *
789 * @par Python function prototype
790 * setCollisionStopType(self: pyaubo_sdk.RobotConfig, arg0: int) -> int
791 *
792 * @par Lua function prototype
793 * setCollisionStopType(type: number) -> nil
794 *
795 * @par JSON-RPC request example
796 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setCollisionStopType","params":[1],"id":1}
797 *
798 * @par JSON-RPC response example
799 * {"id":1,"jsonrpc":"2.0","result":0}
800 * \endenglish
801 */
802 int setCollisionStopType(int type);
803
804 /**
805 * \chinese
806 * 获取碰撞停止类型
807 *
808 * @return 返回碰撞停止类型 \n
809 * 0: 碰撞后浮动,即碰撞之后进入拖动示教模式 \n
810 * 1: 碰撞后静止 \n
811 * 2: 碰撞后抱闸
812 *
813 * @throws arcs::common_interface::AuboException
814 *
815 * @par Python函数原型
816 * getCollisionStopType(self: pyaubo_sdk.RobotConfig) -> int
817 *
818 * @par Lua函数原型
819 * getCollisionStopType() -> number
820 *
821 * @par JSON-RPC请求示例
822 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getCollisionStopType","params":[],"id":1}
823 *
824 * @par JSON-RPC响应示例
825 * {"id":1,"jsonrpc":"2.0","result":1}
826 *
827 * \endchinese
828 * \english
829 * Get the collision stop type.
830 *
831 * @return The collision stop type. \n
832 * 0: Floating after collision, i.e., enters freedrive mode after collision
833 * \n 1: Stop after collision \n 2: Brake after collision
834 *
835 * @throws arcs::common_interface::AuboException
836 *
837 * @par Python function prototype
838 * getCollisionStopType(self: pyaubo_sdk.RobotConfig) -> int
839 *
840 * @par Lua function prototype
841 * getCollisionStopType() -> number
842 *
843 * @par JSON-RPC request example
844 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getCollisionStopType","params":[],"id":1}
845 *
846 * @par JSON-RPC response example
847 * {"id":1,"jsonrpc":"2.0","result":1}
848 *
849 * \endenglish
850 */
852
853 /**
854 * \chinese
855 * 设置机器人的原点位置
856 *
857 * @param positions 关节角度
858 * @return 成功返回0;失败返回错误码
859 * AUBO_BUSY
860 * AUBO_BAD_STATE
861 * -AUBO_INVL_ARGUMENT
862 * -AUBO_BAD_STATE
863 *
864 * @throws arcs::common_interface::AuboException
865 *
866 * @par JSON-RPC请求示例
867 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setHomePosition","params":[[0.0,-0.2617993877991494,1.74532925199433,0.4363323129985824,1.570796326794897,0.0]],"id":1}
868 *
869 * @par JSON-RPC响应示例
870 * {"id":1,"jsonrpc":"2.0","result":0}
871 * \endchinese
872 * \english
873 * Set the robot's home position.
874 *
875 * @param positions Joint angles
876 * @return Returns 0 on success; error code on failure
877 * AUBO_BUSY
878 * AUBO_BAD_STATE
879 * -AUBO_INVL_ARGUMENT
880 * -AUBO_BAD_STATE
881 *
882 * @throws arcs::common_interface::AuboException
883 *
884 * @par JSON-RPC request example
885 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setHomePosition","params":[[0.0,-0.2617993877991494,1.74532925199433,0.4363323129985824,1.570796326794897,0.0]],"id":1}
886 *
887 * @par JSON-RPC response example
888 * {"id":1,"jsonrpc":"2.0","result":0}
889 * \endenglish
890 */
891 int setHomePosition(const std::vector<double> &positions);
892
893 /**
894 * \chinese
895 * 获取机器人的原点位置
896 *
897 * @return
898 *
899 * @throws arcs::common_interface::AuboException
900 *
901 * @par JSON-RPC请求示例
902 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getHomePosition","params":[],"id":1}
903 *
904 * @par JSON-RPC响应示例
905 * {"id":1,"jsonrpc":"2.0","result":[0.0,-0.2617993877991494,1.74532925199433,0.4363323129985824,1.570796326794897,0.0]}
906 * \endchinese
907 * \english
908 * Get the robot's home position.
909 *
910 * @return
911 *
912 * @throws arcs::common_interface::AuboException
913 *
914 * @par JSON-RPC request example
915 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getHomePosition","params":[],"id":1}
916 *
917 * @par JSON-RPC response example
918 * {"id":1,"jsonrpc":"2.0","result":[0.0,-0.2617993877991494,1.74532925199433,0.4363323129985824,1.570796326794897,0.0]}
919 * \endenglish
920 */
921 std::vector<double> getHomePosition();
922
923 /**
924 * \chinese
925 * 设置拖动阻尼
926 *
927 * @param damp 阻尼
928 *
929 * @return 成功返回0;失败返回错误码
930 * AUBO_BUSY
931 * AUBO_BAD_STATE
932 * -AUBO_INVL_ARGUMENT
933 * -AUBO_BAD_STATE
934 *
935 * @throws arcs::common_interface::AuboException
936 *
937 * @par Python函数原型
938 * setFreedriveDamp(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
939 *
940 * @par Lua函数原型
941 * setFreedriveDamp(damp: table) -> number
942 *
943 * @par JSON-RPC请求示例
944 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setFreedriveDamp","params":[[0.5,0.5,0.5,0.5,0.5,0.5]],"id":1}
945 *
946 * @par JSON-RPC响应示例
947 * {"id":1,"jsonrpc":"2.0","result":0}
948 *
949 * \endchinese
950 * \english
951 * Set freedrive damping.
952 *
953 * @param damp Damping values.
954 *
955 * @return Returns 0 on success; error code on failure
956 * AUBO_BUSY
957 * AUBO_BAD_STATE
958 * -AUBO_INVL_ARGUMENT
959 * -AUBO_BAD_STATE
960 *
961 * @throws arcs::common_interface::AuboException
962 *
963 * @par Python function prototype
964 * setFreedriveDamp(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
965 *
966 * @par Lua function prototype
967 * setFreedriveDamp(damp: table) -> number
968 *
969 * @par JSON-RPC request example
970 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setFreedriveDamp","params":[[0.5,0.5,0.5,0.5,0.5,0.5]],"id":1}
971 *
972 * @par JSON-RPC response example
973 * {"id":1,"jsonrpc":"2.0","result":0}
974 *
975 * \endenglish
976 */
977 int setFreedriveDamp(const std::vector<double> &damp);
978
979 /**
980 * \chinese
981 * 获取拖动阻尼
982 *
983 * @return 拖动阻尼
984 *
985 * @throws arcs::common_interface::AuboException
986 *
987 * @par Python函数原型
988 * getFreedriveDamp(self: pyaubo_sdk.RobotConfig) -> List[float]
989 *
990 * @par Lua函数原型
991 * getFreedriveDamp() -> table
992 *
993 * @par JSON-RPC请求示例
994 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getFreedriveDamp","params":[],"id":1}
995 *
996 * @par JSON-RPC响应示例
997 * {"id":1,"jsonrpc":"2.0","result":[0.5,0.5,0.5,0.5,0.5,0.5]}
998 * \endchinese
999 * \english
1000 * Get freedrive damping.
1001 *
1002 * @return Freedrive damping values.
1003 *
1004 * @throws arcs::common_interface::AuboException
1005 *
1006 * @par Python function prototype
1007 * getFreedriveDamp(self: pyaubo_sdk.RobotConfig) -> List[float]
1008 *
1009 * @par Lua function prototype
1010 * getFreedriveDamp() -> table
1011 *
1012 * @par JSON-RPC request example
1013 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getFreedriveDamp","params":[],"id":1}
1014 *
1015 * @par JSON-RPC response example
1016 * {"id":1,"jsonrpc":"2.0","result":[0.5,0.5,0.5,0.5,0.5,0.5]}
1017 * \endenglish
1018 */
1019 std::vector<double> getFreedriveDamp();
1020
1021 /**
1022 * 设置混合拖动阻尼
1023 *
1024 * @param damp 阻尼
1025 *
1026 * @return 成功返回0;失败返回错误码
1027 * AUBO_BUSY
1028 * AUBO_BAD_STATE
1029 * -AUBO_INVL_ARGUMENT
1030 * -AUBO_BAD_STATE
1031 *
1032 * @throws arcs::common_interface::AuboException
1033 *
1034 * @par Python函数原型
1035 * setHandguidDamp(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
1036 *
1037 * @par Lua函数原型
1038 * setHandguidDamp(damp: table) -> number
1039 *
1040 * @par JSON-RPC请求示例
1041 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setHandguidDamp","params":[[0.5,0.5,0.5,0.5,0.5,0.5]],"id":1}
1042 *
1043 * @par JSON-RPC响应示例
1044 * {"id":1,"jsonrpc":"2.0","result":0}
1045 *
1046 */
1047 int setHandguidDamp(const std::vector<double> &damp);
1048
1049 /**
1050 * 获取混合拖动阻尼
1051 *
1052 * @return 拖动阻尼
1053 *
1054 * @throws arcs::common_interface::AuboException
1055 *
1056 * @par Python函数原型
1057 * getHandguidDamp(self: pyaubo_sdk.RobotConfig) -> List[float]
1058 *
1059 * @par Lua函数原型
1060 * getHandguidDamp() -> table
1061 *
1062 * @par JSON-RPC请求示例
1063 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getHandguidDamp","params":[],"id":1}
1064 *
1065 * @par JSON-RPC响应示例
1066 * {"id":1,"jsonrpc":"2.0","result":[0.5,0.5,0.5,0.5,0.5,0.5]}
1067 *
1068 */
1069 std::vector<double> getHandguidDamp();
1070
1071 /**
1072 * \chinese
1073 * 获取机器人DH参数
1074 * alpha a d theta beta
1075 *
1076 * @param real 读取真实参数(理论值+补偿值)或者理论参数
1077 * @return 返回机器人DH参数
1078 *
1079 * @throws arcs::common_interface::AuboException
1080 *
1081 * @par Python函数原型
1082 * getKinematicsParam(self: pyaubo_sdk.RobotConfig, arg0: bool) -> Dict[str,
1083 * List[float]]
1084 *
1085 * @par Lua函数原型
1086 * getKinematicsParam(real: boolean) -> table
1087 *
1088 * @par JSON-RPC请求示例
1089 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getKinematicsParam","params":[true],"id":1}
1090 *
1091 * @par JSON-RPC响应示例
1092 * {"id":1,"jsonrpc":"2.0","result":{"a":[0.0,-0.0001255999959539622,0.4086348000024445,0.3757601999930339,-0.00018950000230688602,3.7000001611886546e-05],
1093 * "alpha":[0.0,-1.5701173967707458,3.1440308735524347,3.14650750358636,-1.5703093767832055,1.5751177669179182],"beta":[0.0,0.0,0.0,0.0,0.0,0.0],
1094 * "d":[0.122,0.12154769999941345,-4.769999941345304e-05,4.769999941345304e-05,0.10287890000385232,0.116],
1095 * "theta":[3.141592653589793,-1.5707963267948966,0.0,-1.5707963267948966,0.0,0.0]}}
1096 * \endchinese
1097 * \english
1098 * Get the robot's DH parameters: alpha, a, d, theta, beta.
1099 *
1100 * @param real Read real parameters (theoretical + compensation) or
1101 * theoretical parameters.
1102 * @return Returns the robot's DH parameters.
1103 *
1104 * @throws arcs::common_interface::AuboException
1105 *
1106 * @par Python function prototype
1107 * getKinematicsParam(self: pyaubo_sdk.RobotConfig, arg0: bool) -> Dict[str,
1108 * List[float]]
1109 *
1110 * @par Lua function prototype
1111 * getKinematicsParam(real: boolean) -> table
1112 *
1113 * @par JSON-RPC request example
1114 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getKinematicsParam","params":[true],"id":1}
1115 *
1116 * @par JSON-RPC response example
1117 * {"id":1,"jsonrpc":"2.0","result":{"a":[0.0,-0.0001255999959539622,0.4086348000024445,0.3757601999930339,-0.00018950000230688602,3.7000001611886546e-05],
1118 * "alpha":[0.0,-1.5701173967707458,3.1440308735524347,3.14650750358636,-1.5703093767832055,1.5751177669179182],"beta":[0.0,0.0,0.0,0.0,0.0,0.0],
1119 * "d":[0.122,0.12154769999941345,-4.769999941345304e-05,4.769999941345304e-05,0.10287890000385232,0.116],
1120 * "theta":[3.141592653589793,-1.5707963267948966,0.0,-1.5707963267948966,0.0,0.0]}}
1121 * \endenglish
1122 */
1123 std::unordered_map<std::string, std::vector<double>> getKinematicsParam(
1124 bool real);
1125
1126 /**
1127 * \chinese
1128 * 获取指定温度下的DH参数补偿值:alpha a d theta beta
1129 *
1130 * @param ref_temperature 参考温度 ℃,默认20℃
1131 * @return 返回DH参数补偿值
1132 *
1133 * @throws arcs::common_interface::AuboException
1134 *
1135 * @par Python函数原型
1136 * getKinematicsCompensate(self: pyaubo_sdk.RobotConfig, arg0: float) ->
1137 * Dict[str, List[float]]
1138 *
1139 * @par Lua函数原型
1140 * getKinematicsCompensate(ref_temperature: number) -> table
1141 *
1142 * @par JSON-RPC请求示例
1143 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getKinematicsCompensate","params":[20],"id":1}
1144 *
1145 * @par JSON-RPC响应示例
1146 * {"id":1,"jsonrpc":"2.0","result":{"a":[0.0,-0.0001255999959539622,0.0006348000024445355,-0.0002398000069661066,-0.00018950000230688602,3.7000001611886546e-05],
1147 * "alpha":[0.0,0.000678930024150759,0.002438219962641597,0.0049148499965667725,0.00048695001169107854,0.004321440123021603],
1148 * "beta":[0.0,0.0,0.0,0.0,0.0,0.0],"d":[0.0,4.769999941345304e-05,-4.769999941345304e-05,4.769999941345304e-05,0.0003789000038523227,0.0],
1149 * "theta":[0.0,0.0,0.0,0.0,0.0,0.0]}}
1150 * \endchinese
1151 * \english
1152 * Get DH parameter compensation values (alpha, a, d, theta, beta) at the
1153 * specified temperature.
1154 *
1155 * @param ref_temperature Reference temperature in ℃, default is 20℃
1156 * @return Returns DH parameter compensation values.
1157 *
1158 * @throws arcs::common_interface::AuboException
1159 *
1160 * @par Python function prototype
1161 * getKinematicsCompensate(self: pyaubo_sdk.RobotConfig, arg0: float) ->
1162 * Dict[str, List[float]]
1163 *
1164 * @par Lua function prototype
1165 * getKinematicsCompensate(ref_temperature: number) -> table
1166 *
1167 * @par JSON-RPC request example
1168 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getKinematicsCompensate","params":[20],"id":1}
1169 *
1170 * @par JSON-RPC response example
1171 * {"id":1,"jsonrpc":"2.0","result":{"a":[0.0,-0.0001255999959539622,0.0006348000024445355,-0.0002398000069661066,-0.00018950000230688602,3.7000001611886546e-05],
1172 * "alpha":[0.0,0.000678930024150759,0.002438219962641597,0.0049148499965667725,0.00048695001169107854,0.004321440123021603],
1173 * "beta":[0.0,0.0,0.0,0.0,0.0,0.0],"d":[0.0,4.769999941345304e-05,-4.769999941345304e-05,4.769999941345304e-05,0.0003789000038523227,0.0],
1174 * "theta":[0.0,0.0,0.0,0.0,0.0,0.0]}}
1175 * \endenglish
1176 */
1177 std::unordered_map<std::string, std::vector<double>>
1178 getKinematicsCompensate(double ref_temperature);
1179
1180 /**
1181 * \chinese
1182 * 设置标准 DH 补偿到机器人
1183 *
1184 * @param param
1185 *
1186 * @return 成功返回0;失败返回错误码
1187 * AUBO_BUSY
1188 * AUBO_BAD_STATE
1189 * -AUBO_INVL_ARGUMENT
1190 * -AUBO_BAD_STATE
1191 *
1192 * @throws arcs::common_interface::AuboException
1193 * \endchinese
1194 * \english
1195 * Set standard DH compensation to the robot.
1196 *
1197 * @param param
1198 *
1199 * @return Returns 0 on success; error code on failure
1200 * AUBO_BUSY
1201 * AUBO_BAD_STATE
1202 * -AUBO_INVL_ARGUMENT
1203 * -AUBO_BAD_STATE
1204 *
1205 * @throws arcs::common_interface::AuboException
1206 * \endenglish
1207 */
1209 const std::unordered_map<std::string, std::vector<double>> &param);
1210
1211 /**
1212 * \chinese
1213 * 设置需要保存到接口板底座的参数
1214 *
1215 * @param param 补偿数据
1216 *
1217 * @return 成功返回0;失败返回错误码
1218 * AUBO_BUSY
1219 * AUBO_BAD_STATE
1220 * -AUBO_INVL_ARGUMENT
1221 * -AUBO_BAD_STATE
1222 *
1223 * @throws arcs::common_interface::AuboException
1224 *
1225 * @par Python函数原型
1226 * setPersistentParameters(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
1227 *
1228 * @par Lua函数原型
1229 * setPersistentParameters(param: string) -> nil
1230 *
1231 * \endchinese
1232 * \english
1233 * Set parameters to be saved to the interface board base.
1234 *
1235 * @param param Compensation data.
1236 *
1237 * @return Returns 0 on success; error code on failure.
1238 * AUBO_BUSY
1239 * AUBO_BAD_STATE
1240 * -AUBO_INVL_ARGUMENT
1241 * -AUBO_BAD_STATE
1242 *
1243 * @throws arcs::common_interface::AuboException
1244 *
1245 * @par Python function prototype
1246 * setPersistentParameters(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
1247 *
1248 * @par Lua function prototype
1249 * setPersistentParameters(param: string) -> nil
1250 *
1251 * \endenglish
1252 */
1253 int setPersistentParameters(const std::string &param);
1254
1255 /**
1256 * \chinese
1257 * 设置硬件抽象层自定义参数
1258 * 目的是为了做不同硬件之间的兼容
1259 *
1260 * @param param 自定义参数
1261 *
1262 * @return 成功返回0;失败返回错误码
1263 * AUBO_BUSY
1264 * AUBO_BAD_STATE
1265 * -AUBO_INVL_ARGUMENT
1266 * -AUBO_BAD_STATE
1267 *
1268 * @throws arcs::common_interface::AuboException
1269 * \endchinese
1270 * \english
1271 * Set custom parameters for the hardware abstraction layer.
1272 * The purpose is to ensure compatibility between different hardware.
1273 *
1274 * @param param Custom parameters.
1275 *
1276 * @return Returns 0 on success; error code on failure.
1277 * AUBO_BUSY
1278 * AUBO_BAD_STATE
1279 * -AUBO_INVL_ARGUMENT
1280 * -AUBO_BAD_STATE
1281 *
1282 * @throws arcs::common_interface::AuboException
1283 * \endenglish
1284 */
1285 int setHardwareCustomParameters(const std::string &param);
1286
1287 /**
1288 * \chinese
1289 * 获取硬件抽象层自定义参数
1290 *
1291 * @param
1292 * @return 返回硬件抽象层自定义的参数
1293 *
1294 * @throws arcs::common_interface::AuboException
1295 * \endchinese
1296 * \english
1297 * Get custom parameters from the hardware abstraction layer.
1298 *
1299 * @param
1300 * @return Returns custom parameters from the hardware abstraction layer.
1301 *
1302 * @throws arcs::common_interface::AuboException
1303 * \endenglish
1304 */
1305 std::string getHardwareCustomParameters(const std::string &param);
1306
1307 /**
1308 * \chinese
1309 * 设置机器人关节零位
1310 *
1311 * @return 成功返回0;失败返回错误码
1312 * AUBO_BUSY
1313 * AUBO_BAD_STATE
1314 * -AUBO_BAD_STATE
1315 *
1316 * @throws arcs::common_interface::AuboException
1317 *
1318 * @par Python函数原型
1319 * setRobotZero(self: pyaubo_sdk.RobotConfig) -> int
1320 *
1321 * @par Lua函数原型
1322 * setRobotZero() -> nil
1323 *
1324 * @par JSON-RPC请求示例
1325 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setRobotZero","params":[],"id":1}
1326 *
1327 * @par JSON-RPC响应示例
1328 * {"id":1,"jsonrpc":"2.0","result":0}
1329 * \endchinese
1330 * \english
1331 * Set the robot joint zero position.
1332 *
1333 * @return Returns 0 on success; error code on failure
1334 * AUBO_BUSY
1335 * AUBO_BAD_STATE
1336 * -AUBO_BAD_STATE
1337 *
1338 * @throws arcs::common_interface::AuboException
1339 *
1340 * @par Python function prototype
1341 * setRobotZero(self: pyaubo_sdk.RobotConfig) -> int
1342 *
1343 * @par Lua function prototype
1344 * setRobotZero() -> nil
1345 *
1346 * @par JSON-RPC request example
1347 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setRobotZero","params":[],"id":1}
1348 *
1349 * @par JSON-RPC response example
1350 * {"id":1,"jsonrpc":"2.0","result":0}
1351 * \endenglish
1352 */
1354
1355 /**
1356 * \chinese
1357 * 获取可用的末端力矩传感器的名字
1358 *
1359 * @return 返回可用的末端力矩传感器的名字
1360 *
1361 * @throws arcs::common_interface::AuboException
1362 *
1363 * @par Python函数原型
1364 * getTcpForceSensorNames(self: pyaubo_sdk.RobotConfig) -> List[str]
1365 *
1366 * @par Lua函数原型
1367 * getTcpForceSensorNames() -> table
1368 *
1369 * @par JSON-RPC请求示例
1370 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpForceSensorNames","params":[],"id":1}
1371 *
1372 * @par JSON-RPC响应示例
1373 * {"id":1,"jsonrpc":"2.0","result":[]}
1374 *
1375 * \endchinese
1376 * \english
1377 * Get the names of available TCP force sensors.
1378 *
1379 * @return Returns the names of available TCP force sensors.
1380 *
1381 * @throws arcs::common_interface::AuboException
1382 *
1383 * @par Python function prototype
1384 * getTcpForceSensorNames(self: pyaubo_sdk.RobotConfig) -> List[str]
1385 *
1386 * @par Lua function prototype
1387 * getTcpForceSensorNames() -> table
1388 *
1389 * @par JSON-RPC request example
1390 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpForceSensorNames","params":[],"id":1}
1391 *
1392 * @par JSON-RPC response example
1393 * {"id":1,"jsonrpc":"2.0","result":[]}
1394 *
1395 * \endenglish
1396 */
1397 std::vector<std::string> getTcpForceSensorNames();
1398
1399 /**
1400 * \chinese
1401 * 设置末端力矩传感器
1402 * 如果存在内置的末端力矩传感器,默认将使用内置的力矩传感器
1403 *
1404 * @param name 末端力矩传感器的名字
1405 *
1406 * @return 成功返回0;失败返回错误码
1407 * AUBO_BUSY
1408 * AUBO_BAD_STATE
1409 * -AUBO_INVL_ARGUMENT
1410 * -AUBO_BAD_STATE
1411 *
1412 * @throws arcs::common_interface::AuboException
1413 *
1414 * @par Python函数原型
1415 * selectTcpForceSensor(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
1416 *
1417 * @par Lua函数原型
1418 * selectTcpForceSensor(name: string) -> nil
1419 * \endchinese
1420 * \english
1421 * Set the TCP force sensor.
1422 * If there is a built-in TCP force sensor, the built-in sensor will be used
1423 * by default.
1424 *
1425 * @param name Name of the TCP force sensor.
1426 *
1427 * @return Returns 0 on success; error code on failure.
1428 * AUBO_BUSY
1429 * AUBO_BAD_STATE
1430 * -AUBO_INVL_ARGUMENT
1431 * -AUBO_BAD_STATE
1432 *
1433 * @throws arcs::common_interface::AuboException
1434 *
1435 * @par Python function prototype
1436 * selectTcpForceSensor(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
1437 *
1438 * @par Lua function prototype
1439 * selectTcpForceSensor(name: string) -> nil
1440 * \endenglish
1441 */
1442 int selectTcpForceSensor(const std::string &name);
1443
1444 /**
1445 * \chinese
1446 * 设置传感器安装位姿
1447 *
1448 * @param sensor_pose 传感器安装位姿
1449 *
1450 * @return 成功返回0;失败返回错误码
1451 * AUBO_BUSY
1452 * AUBO_BAD_STATE
1453 * -AUBO_INVL_ARGUMENT
1454 * -AUBO_BAD_STATE
1455 *
1456 * @throws arcs::common_interface::AuboException
1457 * \endchinese
1458 * \english
1459 * Set the sensor mounting pose.
1460 *
1461 * @param sensor_pose Sensor mounting pose
1462 *
1463 * @return Returns 0 on success; error code on failure
1464 * AUBO_BUSY
1465 * AUBO_BAD_STATE
1466 * -AUBO_INVL_ARGUMENT
1467 * -AUBO_BAD_STATE
1468 *
1469 * @throws arcs::common_interface::AuboException
1470 * \endenglish
1471 */
1472 int setTcpForceSensorPose(const std::vector<double> &sensor_pose);
1473
1474 /**
1475 * \chinese
1476 * 获取传感器安装位姿
1477 *
1478 * @return 传感器安装位姿
1479 *
1480 * @throws arcs::common_interface::AuboException
1481 *
1482 * @par JSON-RPC请求示例
1483 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpForceSensorPose","params":[],"id":1}
1484 *
1485 * @par JSON-RPC响应示例
1486 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
1487 * \endchinese
1488 * \english
1489 * Get the sensor mounting pose.
1490 *
1491 * @return Sensor mounting pose.
1492 *
1493 * @throws arcs::common_interface::AuboException
1494 *
1495 * @par JSON-RPC request example
1496 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpForceSensorPose","params":[],"id":1}
1497 *
1498 * @par JSON-RPC response example
1499 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
1500 * \endenglish
1501 */
1502 std::vector<double> getTcpForceSensorPose();
1503
1504 /**
1505 * \chinese
1506 * 是否安装了末端力矩传感器
1507 *
1508 * @return 安装返回true; 没有安装返回false
1509 *
1510 * @throws arcs::common_interface::AuboException
1511 *
1512 * @par Python函数原型
1513 * hasTcpForceSensor(self: pyaubo_sdk.RobotConfig) -> bool
1514 *
1515 * @par Lua函数原型
1516 * hasTcpForceSensor() -> boolean
1517 *
1518 * @par JSON-RPC请求示例
1519 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.hasTcpForceSensor","params":[],"id":1}
1520 *
1521 * @par JSON-RPC响应示例
1522 * {"id":1,"jsonrpc":"2.0","result":true}
1523 *
1524 * \endchinese
1525 * \english
1526 * Whether a TCP force sensor is installed.
1527 *
1528 * @return Returns true if installed; false otherwise.
1529 *
1530 * @throws arcs::common_interface::AuboException
1531 *
1532 * @par Python function prototype
1533 * hasTcpForceSensor(self: pyaubo_sdk.RobotConfig) -> bool
1534 *
1535 * @par Lua function prototype
1536 * hasTcpForceSensor() -> boolean
1537 *
1538 * @par JSON-RPC request example
1539 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.hasTcpForceSensor","params":[],"id":1}
1540 *
1541 * @par JSON-RPC response example
1542 * {"id":1,"jsonrpc":"2.0","result":true}
1543 *
1544 * \endenglish
1545 */
1547
1548 /**
1549 * \chinese
1550 * 设置末端力矩偏移
1551 *
1552 * @param force_offset 末端力矩偏移
1553 * @return 成功返回0; 失败返回错误码
1554 *
1555 * @throws arcs::common_interface::AuboException
1556 *
1557 * @par Python函数原型
1558 * setTcpForceOffset(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
1559 *
1560 * @par Lua函数原型
1561 * setTcpForceOffset(force_offset: table) -> nil
1562 *
1563 * \endchinese
1564 * \english
1565 * Set the TCP force/torque offset.
1566 *
1567 * @param force_offset TCP force/torque offset
1568 * @return Returns 0 on success; error code on failure
1569 *
1570 * @throws arcs::common_interface::AuboException
1571 *
1572 * @par Python function prototype
1573 * setTcpForceOffset(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
1574 *
1575 * @par Lua function prototype
1576 * setTcpForceOffset(force_offset: table) -> nil
1577 *
1578 * \endenglish
1579 */
1580 int setTcpForceOffset(const std::vector<double> &force_offset);
1581
1582 /**
1583 * \chinese
1584 * 获取末端力矩偏移
1585 *
1586 * @return 返回末端力矩偏移
1587 *
1588 * @throws arcs::common_interface::AuboException
1589 *
1590 * @par Python函数原型
1591 * getTcpForceOffset(self: pyaubo_sdk.RobotConfig) -> List[float]
1592 *
1593 * @par Lua函数原型
1594 * getTcpForceOffset() -> table
1595 *
1596 * @par JSON-RPC请求示例
1597 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpForceOffset","params":[],"id":1}
1598 *
1599 * @par JSON-RPC响应示例
1600 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
1601 * \endchinese
1602 * \english
1603 * Get the TCP force/torque offset.
1604 *
1605 * @return Returns the TCP force/torque offset.
1606 *
1607 * @throws arcs::common_interface::AuboException
1608 *
1609 * @par Python function prototype
1610 * getTcpForceOffset(self: pyaubo_sdk.RobotConfig) -> List[float]
1611 *
1612 * @par Lua function prototype
1613 * getTcpForceOffset() -> table
1614 *
1615 * @par JSON-RPC request example
1616 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpForceOffset","params":[],"id":1}
1617 *
1618 * @par JSON-RPC response example
1619 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
1620 * \endenglish
1621 */
1622 std::vector<double> getTcpForceOffset();
1623
1624 /**
1625 * \chinese
1626 * 获取可用的底座力矩传感器的名字
1627 *
1628 * @return 返回可用的底座力矩传感器的名字
1629 *
1630 * @throws arcs::common_interface::AuboException
1631 *
1632 * @par Python函数原型
1633 * getBaseForceSensorNames(self: pyaubo_sdk.RobotConfig) -> List[str]
1634 *
1635 * @par Lua函数原型
1636 * getBaseForceSensorNames() -> table
1637 *
1638 * @par JSON-RPC请求示例
1639 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getBaseForceSensorNames","params":[],"id":1}
1640 *
1641 * @par JSON-RPC响应示例
1642 * {"id":1,"jsonrpc":"2.0","result":[]}
1643 *
1644 * \endchinese
1645 * \english
1646 * Get the names of available base force sensors.
1647 *
1648 * @return Returns the names of available base force sensors.
1649 *
1650 * @throws arcs::common_interface::AuboException
1651 *
1652 * @par Python function prototype
1653 * getBaseForceSensorNames(self: pyaubo_sdk.RobotConfig) -> List[str]
1654 *
1655 * @par Lua function prototype
1656 * getBaseForceSensorNames() -> table
1657 *
1658 * @par JSON-RPC request example
1659 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getBaseForceSensorNames","params":[],"id":1}
1660 *
1661 * @par JSON-RPC response example
1662 * {"id":1,"jsonrpc":"2.0","result":[]}
1663 *
1664 * \endenglish
1665 */
1666 std::vector<std::string> getBaseForceSensorNames();
1667
1668 /**
1669 * \chinese
1670 * 设置底座力矩传感器
1671 * 如果存在内置的底座力矩传感器,默认将使用内置的力矩传感器
1672 *
1673 * @param name 底座力矩传感器的名字
1674 *
1675 * @return 成功返回0;失败返回错误码
1676 * AUBO_BUSY
1677 * AUBO_BAD_STATE
1678 * -AUBO_INVL_ARGUMENT
1679 * -AUBO_BAD_STATE
1680 *
1681 * @throws arcs::common_interface::AuboException
1682 *
1683 * @par Python函数原型
1684 * selectBaseForceSensor(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
1685 *
1686 * @par Lua函数原型
1687 * selectBaseForceSensor(name: string) -> nil
1688 * \endchinese
1689 * \english
1690 * Set the base force sensor.
1691 * If there is a built-in base force sensor, the built-in sensor will be
1692 * used by default.
1693 *
1694 * @param name Name of the base force sensor.
1695 *
1696 * @return Returns 0 on success; error code on failure.
1697 * AUBO_BUSY
1698 * AUBO_BAD_STATE
1699 * -AUBO_INVL_ARGUMENT
1700 * -AUBO_BAD_STATE
1701 *
1702 * @throws arcs::common_interface::AuboException
1703 *
1704 * @par Python function prototype
1705 * selectBaseForceSensor(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
1706 *
1707 * @par Lua function prototype
1708 * selectBaseForceSensor(name: string) -> nil
1709 * \endenglish
1710 */
1711 int selectBaseForceSensor(const std::string &name);
1712
1713 /**
1714 * \chinese
1715 * 是否安装了底座力矩传感器
1716 *
1717 * @return 安装返回true;没有安装返回false
1718 *
1719 * @throws arcs::common_interface::AuboException
1720 *
1721 * @par Python函数原型
1722 * hasBaseForceSensor(self: pyaubo_sdk.RobotConfig) -> bool
1723 *
1724 * @par Lua函数原型
1725 * hasBaseForceSensor() -> boolean
1726 *
1727 * @par JSON-RPC请求示例
1728 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.hasBaseForceSensor","params":[],"id":1}
1729 *
1730 * @par JSON-RPC响应示例
1731 * {"id":1,"jsonrpc":"2.0","result":false}
1732 *
1733 * \endchinese
1734 * \english
1735 * Whether a base force sensor is installed.
1736 *
1737 * @return Returns true if installed; false otherwise.
1738 *
1739 * @throws arcs::common_interface::AuboException
1740 *
1741 * @par Python function prototype
1742 * hasBaseForceSensor(self: pyaubo_sdk.RobotConfig) -> bool
1743 *
1744 * @par Lua function prototype
1745 * hasBaseForceSensor() -> boolean
1746 *
1747 * @par JSON-RPC request example
1748 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.hasBaseForceSensor","params":[],"id":1}
1749 *
1750 * @par JSON-RPC response example
1751 * {"id":1,"jsonrpc":"2.0","result":false}
1752 *
1753 * \endenglish
1754 */
1756
1757 /**
1758 * \chinese
1759 * 设置底座力矩偏移
1760 *
1761 * @param force_offset 底座力矩偏移
1762 *
1763 * @return 成功返回0;失败返回错误码
1764 * AUBO_BUSY
1765 * AUBO_BAD_STATE
1766 * -AUBO_INVL_ARGUMENT
1767 * -AUBO_BAD_STATE
1768 *
1769 * @throws arcs::common_interface::AuboException
1770 *
1771 * @par Python函数原型
1772 * setBaseForceOffset(self: pyaubo_sdk.RobotConfig, arg0: List[float]) ->
1773 * int
1774 *
1775 * @par Lua函数原型
1776 * setBaseForceOffset(force_offset: table) -> nil
1777 * \endchinese
1778 * \english
1779 * Set the base force/torque offset.
1780 *
1781 * @param force_offset Base force/torque offset
1782 *
1783 * @return Returns 0 on success; error code on failure
1784 * AUBO_BUSY
1785 * AUBO_BAD_STATE
1786 * -AUBO_INVL_ARGUMENT
1787 * -AUBO_BAD_STATE
1788 *
1789 * @throws arcs::common_interface::AuboException
1790 *
1791 * @par Python function prototype
1792 * setBaseForceOffset(self: pyaubo_sdk.RobotConfig, arg0: List[float]) ->
1793 * int
1794 *
1795 * @par Lua function prototype
1796 * setBaseForceOffset(force_offset: table) -> nil
1797 * \endenglish
1798 */
1799 int setBaseForceOffset(const std::vector<double> &force_offset);
1800
1801 /**
1802 * \chinese
1803 * 获取底座力矩偏移
1804 *
1805 * @return 返回底座力矩偏移
1806 *
1807 * @throws arcs::common_interface::AuboException
1808 *
1809 * @par Python函数原型
1810 * getBaseForceOffset(self: pyaubo_sdk.RobotConfig) -> List[float]
1811 *
1812 * @par Lua函数原型
1813 * getBaseForceOffset() -> table
1814 *
1815 * @par JSON-RPC请求示例
1816 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getBaseForceOffset","params":[],"id":1}
1817 *
1818 * @par JSON-RPC响应示例
1819 * {"id":1,"jsonrpc":"2.0","result":[]}
1820 *
1821 * \endchinese
1822 * \english
1823 * Get the base force/torque offset.
1824 *
1825 * @return Returns the base force/torque offset.
1826 *
1827 * @throws arcs::common_interface::AuboException
1828 *
1829 * @par Python function prototype
1830 * getBaseForceOffset(self: pyaubo_sdk.RobotConfig) -> List[float]
1831 *
1832 * @par Lua function prototype
1833 * getBaseForceOffset() -> table
1834 *
1835 * @par JSON-RPC request example
1836 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getBaseForceOffset","params":[],"id":1}
1837 *
1838 * @par JSON-RPC response example
1839 * {"id":1,"jsonrpc":"2.0","result":[]}
1840 *
1841 * \endenglish
1842 */
1843 std::vector<double> getBaseForceOffset();
1844
1845 /**
1846 * \chinese
1847 * 获取安全参数校验码 CRC32
1848 *
1849 * @return 返回安全参数校验码
1850 *
1851 * @throws arcs::common_interface::AuboException
1852 *
1853 * @par Python函数原型
1854 * getSafetyParametersCheckSum(self: pyaubo_sdk.RobotConfig) -> int
1855 *
1856 * @par Lua函数原型
1857 * getSafetyParametersCheckSum() -> number
1858 *
1859 * @par JSON-RPC请求示例
1860 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSafetyParametersCheckSum","params":[],"id":1}
1861 *
1862 * @par JSON-RPC响应示例
1863 * {"id":1,"jsonrpc":"2.0","result":2033397241}
1864 *
1865 * \endchinese
1866 * \english
1867 * Get the safety parameter checksum CRC32.
1868 *
1869 * @return Returns the safety parameter checksum.
1870 *
1871 * @throws arcs::common_interface::AuboException
1872 *
1873 * @par Python function prototype
1874 * getSafetyParametersCheckSum(self: pyaubo_sdk.RobotConfig) -> int
1875 *
1876 * @par Lua function prototype
1877 * getSafetyParametersCheckSum() -> number
1878 *
1879 * @par JSON-RPC request example
1880 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSafetyParametersCheckSum","params":[],"id":1}
1881 *
1882 * @par JSON-RPC response example
1883 * {"id":1,"jsonrpc":"2.0","result":2033397241}
1884 *
1885 * \endenglish
1886 */
1888
1889 /**
1890 * \chinese
1891 * 发起确认安全配置参数请求:
1892 * 将安全配置参数写入到安全接口板flash或文件
1893 *
1894 * @param parameters 安全配置参数
1895 *
1896 * @return 成功返回0;失败返回错误码
1897 * AUBO_BUSY
1898 * AUBO_BAD_STATE
1899 * -AUBO_INVL_ARGUMENT
1900 * -AUBO_BAD_STATE
1901 *
1902 * @throws arcs::common_interface::AuboException
1903 *
1904 * @par Python函数原型
1905 * confirmSafetyParameters(self: pyaubo_sdk.RobotConfig, arg0:
1906 * arcs::common_interface::RobotSafetyParameterRange) -> int
1907 *
1908 * @par Lua函数原型
1909 *
1910 * \endchinese
1911 * \english
1912 * Initiate a request to confirm safety configuration parameters:
1913 * Write safety configuration parameters to the safety interface board flash
1914 * or file.
1915 *
1916 * @param parameters Safety configuration parameters.
1917 *
1918 * @return Returns 0 on success; error code on failure.
1919 * AUBO_BUSY
1920 * AUBO_BAD_STATE
1921 * -AUBO_INVL_ARGUMENT
1922 * -AUBO_BAD_STATE
1923 *
1924 * @throws arcs::common_interface::AuboException
1925 *
1926 * @par Python function prototype
1927 * confirmSafetyParameters(self: pyaubo_sdk.RobotConfig, arg0:
1928 * arcs::common_interface::RobotSafetyParameterRange) -> int
1929 *
1930 * @par Lua function prototype
1931 *
1932 * \endenglish
1933 */
1935
1936 /**
1937 * \chinese
1938 * 计算安全参数的 CRC32 校验值
1939 *
1940 * @return crc32
1941 *
1942 * @throws arcs::common_interface::AuboException
1943 * \endchinese
1944 * \english
1945 * Calculate the CRC32 checksum of safety parameters.
1946 *
1947 * @return crc32
1948 *
1949 * @throws arcs::common_interface::AuboException
1950 * \endenglish
1951 */
1953 const RobotSafetyParameterRange &parameters);
1954
1955 /**
1956 * \chinese
1957 * 获取关节最大位置(物理极限)
1958 *
1959 * @return 返回关节最大位置
1960 *
1961 * @throws arcs::common_interface::AuboException
1962 *
1963 * @par Python函数原型
1964 * getJointMaxPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
1965 *
1966 * @par Lua函数原型
1967 * getJointMaxPositions() -> table
1968 *
1969 * @par JSON-RPC请求示例
1970 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMaxPositions","params":[],"id":1}
1971 *
1972 * @par JSON-RPC响应示例
1973 * {"id":1,"jsonrpc":"2.0","result":[6.283185307179586,6.283185307179586,6.283185307179586,6.283185307179586,6.283185307179586,6.283185307179586]}
1974 * \endchinese
1975 * \english
1976 * Get the joint maximum positions (physical limits).
1977 *
1978 * @return Returns the joint maximum positions.
1979 *
1980 * @throws arcs::common_interface::AuboException
1981 *
1982 * @par Python function prototype
1983 * getJointMaxPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
1984 *
1985 * @par Lua function prototype
1986 * getJointMaxPositions() -> table
1987 *
1988 * @par JSON-RPC request example
1989 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMaxPositions","params":[],"id":1}
1990 *
1991 * @par JSON-RPC response example
1992 * {"id":1,"jsonrpc":"2.0","result":[6.283185307179586,6.283185307179586,6.283185307179586,6.283185307179586,6.283185307179586,6.283185307179586]}
1993 * \endenglish
1994 */
1995 std::vector<double> getJointMaxPositions();
1996
1997 /**
1998 * \chinese
1999 * 获取关节最小位置(物理极限)
2000 *
2001 * @return 返回关节最小位置
2002 *
2003 * @throws arcs::common_interface::AuboException
2004 *
2005 * @par Python函数原型
2006 * getJointMinPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
2007 *
2008 * @par Lua函数原型
2009 * getJointMinPositions() -> table
2010 *
2011 * @par JSON-RPC请求示例
2012 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMinPositions","params":[],"id":1}
2013 *
2014 * @par JSON-RPC响应示例
2015 * {"id":1,"jsonrpc":"2.0","result":[-6.283185307179586,-6.283185307179586,-6.283185307179586,-6.283185307179586,-6.283185307179586,-6.283185307179586]}
2016 * \endchinese
2017 * \english
2018 * Get the joint minimum positions (physical limits).
2019 *
2020 * @return Returns the joint minimum positions.
2021 *
2022 * @throws arcs::common_interface::AuboException
2023 *
2024 * @par Python function prototype
2025 * getJointMinPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
2026 *
2027 * @par Lua function prototype
2028 * getJointMinPositions() -> table
2029 *
2030 * @par JSON-RPC request example
2031 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMinPositions","params":[],"id":1}
2032 *
2033 * @par JSON-RPC response example
2034 * {"id":1,"jsonrpc":"2.0","result":[-6.283185307179586,-6.283185307179586,-6.283185307179586,-6.283185307179586,-6.283185307179586,-6.283185307179586]}
2035 * \endenglish
2036 */
2037 std::vector<double> getJointMinPositions();
2038
2039 /**
2040 * \chinese
2041 * 获取关节最大速度(物理极限)
2042 *
2043 * @return 返回关节最大速度
2044 *
2045 * @throws arcs::common_interface::AuboException
2046 *
2047 * @par Python函数原型
2048 * getJointMaxSpeeds(self: pyaubo_sdk.RobotConfig) -> List[float]
2049 *
2050 * @par Lua函数原型
2051 * getJointMaxSpeeds() -> table
2052 *
2053 * @par JSON-RPC请求示例
2054 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMaxSpeeds","params":[],"id":1}
2055 *
2056 * @par JSON-RPC响应示例
2057 * {"id":1,"jsonrpc":"2.0","result":[3.892084231947355,3.892084231947355,3.892084231947355,3.1066860685499065,3.1066860685499065,3.1066860685499065]}
2058 * \endchinese
2059 * \english
2060 * Get the joint maximum speeds (physical limits).
2061 *
2062 * @return Returns the joint maximum speeds.
2063 *
2064 * @throws arcs::common_interface::AuboException
2065 *
2066 * @par Python function prototype
2067 * getJointMaxSpeeds(self: pyaubo_sdk.RobotConfig) -> List[float]
2068 *
2069 * @par Lua function prototype
2070 * getJointMaxSpeeds() -> table
2071 *
2072 * @par JSON-RPC request example
2073 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMaxSpeeds","params":[],"id":1}
2074 *
2075 * @par JSON-RPC response example
2076 * {"id":1,"jsonrpc":"2.0","result":[3.892084231947355,3.892084231947355,3.892084231947355,3.1066860685499065,3.1066860685499065,3.1066860685499065]}
2077 * \endenglish
2078 */
2079 std::vector<double> getJointMaxSpeeds();
2080
2081 /**
2082 * \chinese
2083 * 获取关节最大加速度(物理极限)
2084 *
2085 * @return 返回关节最大加速度
2086 *
2087 * @throws arcs::common_interface::AuboException
2088 *
2089 * @par Python函数原型
2090 * getJointMaxAccelerations(self: pyaubo_sdk.RobotConfig) -> List[float]
2091 *
2092 * @par Lua函数原型
2093 * getJointMaxAccelerations() -> table
2094 *
2095 * @par JSON-RPC请求示例
2096 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMaxAccelerations","params":[],"id":1}
2097 *
2098 * @par JSON-RPC响应示例
2099 * {"id":1,"jsonrpc":"2.0","result":[31.104877758314785,31.104877758314785,31.104877758314785,20.73625684294463,20.73625684294463,20.73625684294463]}
2100 * \endchinese
2101 * \english
2102 * Get the joint maximum accelerations (physical limits).
2103 *
2104 * @return Returns the joint maximum accelerations.
2105 *
2106 * @throws arcs::common_interface::AuboException
2107 *
2108 * @par Python function prototype
2109 * getJointMaxAccelerations(self: pyaubo_sdk.RobotConfig) -> List[float]
2110 *
2111 * @par Lua function prototype
2112 * getJointMaxAccelerations() -> table
2113 *
2114 * @par JSON-RPC request example
2115 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getJointMaxAccelerations","params":[],"id":1}
2116 *
2117 * @par JSON-RPC response example
2118 * {"id":1,"jsonrpc":"2.0","result":[31.104877758314785,31.104877758314785,31.104877758314785,20.73625684294463,20.73625684294463,20.73625684294463]}
2119 * \endenglish
2120 */
2121 std::vector<double> getJointMaxAccelerations();
2122
2123 /**
2124 * \chinese
2125 * 获取TCP最大速度(物理极限)
2126 *
2127 * @return 返回TCP最大速度
2128 *
2129 * @throws arcs::common_interface::AuboException
2130 *
2131 * @par Python函数原型
2132 * getTcpMaxSpeeds(self: pyaubo_sdk.RobotConfig) -> List[float]
2133 *
2134 * @par Lua函数原型
2135 * getTcpMaxSpeeds() -> table
2136 *
2137 * @par JSON-RPC请求示例
2138 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpMaxSpeeds","params":[],"id":1}
2139 *
2140 * @par JSON-RPC响应示例
2141 * {"id":1,"jsonrpc":"2.0","result":[2.0,5.0]}
2142 * \endchinese
2143 * \english
2144 * Get the TCP maximum speed (physical limits).
2145 *
2146 * @return Returns the TCP maximum speed.
2147 *
2148 * @throws arcs::common_interface::AuboException
2149 *
2150 * @par Python function prototype
2151 * getTcpMaxSpeeds(self: pyaubo_sdk.RobotConfig) -> List[float]
2152 *
2153 * @par Lua function prototype
2154 * getTcpMaxSpeeds() -> table
2155 *
2156 * @par JSON-RPC request example
2157 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpMaxSpeeds","params":[],"id":1}
2158 *
2159 * @par JSON-RPC response example
2160 * {"id":1,"jsonrpc":"2.0","result":[2.0,5.0]}
2161 * \endenglish
2162 */
2163 std::vector<double> getTcpMaxSpeeds();
2164
2165 /**
2166 * \chinese
2167 * 获取TCP最大加速度(物理极限)
2168 *
2169 * @return 返回TCP最大加速度
2170 *
2171 * @throws arcs::common_interface::AuboException
2172 *
2173 * @par Python函数原型
2174 * getTcpMaxAccelerations(self: pyaubo_sdk.RobotConfig) -> List[float]
2175 *
2176 * @par Lua函数原型
2177 * getTcpMaxAccelerations() -> table
2178 *
2179 * @par JSON-RPC请求示例
2180 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpMaxAccelerations","params":[],"id":1}
2181 *
2182 * @par JSON-RPC响应示例
2183 * {"id":1,"jsonrpc":"2.0","result":[10.0,10.0]}
2184 *
2185 * \endchinese
2186 * \english
2187 * Get the TCP maximum acceleration (physical limits).
2188 *
2189 * @return Returns the TCP maximum acceleration.
2190 *
2191 * @throws arcs::common_interface::AuboException
2192 *
2193 * @par Python function prototype
2194 * getTcpMaxAccelerations(self: pyaubo_sdk.RobotConfig) -> List[float]
2195 *
2196 * @par Lua function prototype
2197 * getTcpMaxAccelerations() -> table
2198 *
2199 * @par JSON-RPC request example
2200 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpMaxAccelerations","params":[],"id":1}
2201 *
2202 * @par JSON-RPC response example
2203 * {"id":1,"jsonrpc":"2.0","result":[10.0,10.0]}
2204 * \endenglish
2205 */
2206 std::vector<double> getTcpMaxAccelerations();
2207
2208 /**
2209 * \chinese
2210 * 设置机器人安装姿态
2211 *
2212 * @param gravity 安装姿态
2213 *
2214 * @return 成功返回0;失败返回错误码
2215 * AUBO_BUSY
2216 * AUBO_BAD_STATE
2217 * -AUBO_INVL_ARGUMENT
2218 * -AUBO_BAD_STATE
2219 *
2220 * @throws arcs::common_interface::AuboException
2221 *
2222 * @par Python函数原型
2223 * setGravity(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
2224 *
2225 * @par Lua函数原型
2226 * setGravity(gravity: table) -> nil
2227 *
2228 * @par JSON-RPC请求示例
2229 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setGravity","params":[[0.0,0.0,-9.87654321]],"id":1}
2230 *
2231 * @par JSON-RPC响应示例
2232 * {"id":1,"jsonrpc":"2.0","result":0}
2233 * \endchinese
2234 * \english
2235 * Set the robot installation attitude (gravity vector).
2236 *
2237 * @param gravity Installation attitude (gravity vector)
2238 *
2239 * @return Returns 0 on success; error code on failure
2240 * AUBO_BUSY
2241 * AUBO_BAD_STATE
2242 * -AUBO_INVL_ARGUMENT
2243 * -AUBO_BAD_STATE
2244 *
2245 * @throws arcs::common_interface::AuboException
2246 *
2247 * @par Python function prototype
2248 * setGravity(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
2249 *
2250 * @par Lua function prototype
2251 * setGravity(gravity: table) -> nil
2252 *
2253 * @par JSON-RPC request example
2254 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setGravity","params":[[0.0,0.0,-9.87654321]],"id":1}
2255 *
2256 * @par JSON-RPC response example
2257 * {"id":1,"jsonrpc":"2.0","result":0}
2258 * \endenglish
2259 */
2260 int setGravity(const std::vector<double> &gravity);
2261
2262 /**
2263 * \chinese
2264 * 获取机器人的安装姿态
2265 *
2266 * 如果机器人底座安装了姿态传感器,则从传感器读取数据,否则按照用户设置
2267 *
2268 * @return 返回安装姿态
2269 *
2270 * @throws arcs::common_interface::AuboException
2271 *
2272 * @par Python函数原型
2273 * getGravity(self: pyaubo_sdk.RobotConfig) -> List[float]
2274 *
2275 * @par Lua函数原型
2276 * getGravity() -> table
2277 *
2278 * @par JSON-RPC请求示例
2279 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getGravity","params":[],"id":1}
2280 *
2281 * @par JSON-RPC响应示例
2282 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,-9.87654321]}
2283 *
2284 * \endchinese
2285 * \english
2286 * Get the robot's installation attitude (gravity vector).
2287 *
2288 * If the robot base is equipped with an attitude sensor, data is read from
2289 * the sensor; otherwise, the user setting is used.
2290 *
2291 * @return Returns the installation attitude.
2292 *
2293 * @throws arcs::common_interface::AuboException
2294 *
2295 * @par Python function prototype
2296 * getGravity(self: pyaubo_sdk.RobotConfig) -> List[float]
2297 *
2298 * @par Lua function prototype
2299 * getGravity() -> table
2300 *
2301 * @par JSON-RPC request example
2302 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getGravity","params":[],"id":1}
2303 *
2304 * @par JSON-RPC response example
2305 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,-9.87654321]}
2306 *
2307 * \endenglish
2308 */
2309 std::vector<double> getGravity();
2310
2311 /**
2312 * \chinese
2313 * 设置当前的TCP偏移
2314 *
2315 * TCP偏移表示形式为(x,y,z,rx,ry,rz)。
2316 * 其中x、y、z是工具中心点(TCP)在基坐标系下相对于法兰盘中心的位置偏移,单位是m。
2317 * rx、ry、rz是工具中心点(TCP)在基坐标系下相对于法兰盘中心的的姿态偏移,是ZYX欧拉角,单位是rad。
2318 *
2319 * @param offset 当前的TCP偏移,形式为(x,y,z,rx,ry,rz)
2320 *
2321 * @return 成功返回0;失败返回错误码
2322 * AUBO_BUSY
2323 * AUBO_BAD_STATE
2324 * -AUBO_INVL_ARGUMENT
2325 * -AUBO_BAD_STATE
2326 *
2327 * @throws arcs::common_interface::AuboException
2328 *
2329 * @par Python函数原型
2330 * setTcpOffset(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
2331 *
2332 * @par Lua函数原型
2333 * setTcpOffset(offset: table) -> nil
2334 *
2335 * @par JSON-RPC请求示例
2336 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setTcpOffset","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
2337 *
2338 * @par JSON-RPC响应示例
2339 * {"id":1,"jsonrpc":"2.0","result":0}
2340 * \endchinese
2341 * \english
2342 * Set the current TCP offset.
2343 *
2344 * The TCP offset is represented as (x, y, z, rx, ry, rz).
2345 * x, y, z are the position offsets of the Tool Center Point (TCP) relative
2346 * to the flange center in the base coordinate system, in meters. rx, ry, rz
2347 * are the orientation offsets of the TCP relative to the flange center in
2348 * the base coordinate system, as ZYX Euler angles in radians.
2349 *
2350 * @param offset The current TCP offset, in the form (x, y, z, rx, ry, rz)
2351 *
2352 * @return Returns 0 on success; error code on failure
2353 * AUBO_BUSY
2354 * AUBO_BAD_STATE
2355 * -AUBO_INVL_ARGUMENT
2356 * -AUBO_BAD_STATE
2357 *
2358 * @throws arcs::common_interface::AuboException
2359 *
2360 * @par Python function prototype
2361 * setTcpOffset(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> int
2362 *
2363 * @par Lua function prototype
2364 * setTcpOffset(offset: table) -> nil
2365 *
2366 * @par JSON-RPC request example
2367 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setTcpOffset","params":[[0.0,0.0,0.0,0.0,0.0,0.0]],"id":1}
2368 *
2369 * @par JSON-RPC response example
2370 * {"id":1,"jsonrpc":"2.0","result":0}
2371 * \endenglish
2372 */
2373 int setTcpOffset(const std::vector<double> &offset);
2374
2375 /**
2376 * \chinese
2377 * 获取当前的TCP偏移
2378 *
2379 * TCP偏移表示形式为(x,y,z,rx,ry,rz)。
2380 * 其中x、y、z是工具中心点(TCP)在基坐标系下相对于法兰盘中心的位置偏移,单位是m。
2381 * rx、ry、rz是工具中心点(TCP)在基坐标系下相对于法兰盘中心的的姿态偏移,是ZYX欧拉角,单位是rad。
2382 *
2383 * @return 当前的TCP偏移,形式为(x,y,z,rx,ry,rz)
2384 *
2385 * @throws arcs::common_interface::AuboException
2386 *
2387 * @par Python函数原型
2388 * getTcpOffset(self: pyaubo_sdk.RobotConfig) -> List[float]
2389 *
2390 * @par Lua函数原型
2391 * getTcpOffset() -> table
2392 *
2393 * @par JSON-RPC请求示例
2394 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpOffset","params":[],"id":1}
2395 *
2396 * @par JSON-RPC响应示例
2397 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
2398 * \endchinese
2399 * \english
2400 * Get the current TCP offset.
2401 *
2402 * The TCP offset is represented as (x, y, z, rx, ry, rz).
2403 * x, y, z are the position offsets of the Tool Center Point (TCP) relative
2404 * to the flange center in the base coordinate system, in meters. rx, ry, rz
2405 * are the orientation offsets of the TCP relative to the flange center in
2406 * the base coordinate system, as ZYX Euler angles in radians.
2407 *
2408 * @return The current TCP offset, in the form (x, y, z, rx, ry, rz)
2409 *
2410 * @throws arcs::common_interface::AuboException
2411 *
2412 * @par Python function prototype
2413 * getTcpOffset(self: pyaubo_sdk.RobotConfig) -> List[float]
2414 *
2415 * @par Lua function prototype
2416 * getTcpOffset() -> table
2417 *
2418 * @par JSON-RPC request example
2419 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getTcpOffset","params":[],"id":1}
2420 *
2421 * @par JSON-RPC response example
2422 * {"id":1,"jsonrpc":"2.0","result":[0.0,0.0,0.0,0.0,0.0,0.0]}
2423 * \endenglish
2424 */
2425 std::vector<double> getTcpOffset();
2426
2427 /**
2428 * \chinese
2429 * 设置工具端质量、质心及惯量
2430 *
2431 * @param m 工具端质量
2432 * @param com 质心
2433 * @param inertial 惯量
2434 *
2435 * @return 成功返回0;失败返回错误码
2436 * AUBO_BUSY
2437 * AUBO_BAD_STATE
2438 * -AUBO_INVL_ARGUMENT
2439 * -AUBO_BAD_STATE
2440 *
2441 * @throws arcs::common_interface::AuboException
2442 *
2443 * @par Python函数原型
2444 * setToolInertial(self: pyaubo_sdk.RobotConfig, arg0: float, arg1:
2445 * List[float], arg2: List[float]) -> int
2446 *
2447 * @par Lua函数原型
2448 * setToolInertial(m: number, com: table, inertial: table) -> nil
2449 * \endchinese
2450 * \english
2451 * Set tool mass, center of mass, and inertia.
2452 *
2453 * @param m Tool mass
2454 * @param com Center of mass
2455 * @param inertial Inertia
2456 *
2457 * @return Returns 0 on success; error code on failure
2458 * AUBO_BUSY
2459 * AUBO_BAD_STATE
2460 * -AUBO_INVL_ARGUMENT
2461 * -AUBO_BAD_STATE
2462 *
2463 * @throws arcs::common_interface::AuboException
2464 *
2465 * @par Python function prototype
2466 * setToolInertial(self: pyaubo_sdk.RobotConfig, arg0: float, arg1:
2467 * List[float], arg2: List[float]) -> int
2468 *
2469 * @par Lua function prototype
2470 * setToolInertial(m: number, com: table, inertial: table) -> nil
2471 * \endenglish
2472 */
2473 int setToolInertial(double m, const std::vector<double> &com,
2474 const std::vector<double> &inertial);
2475
2476 /**
2477 * \chinese
2478 * 设置有效负载
2479 *
2480 * @param m 质量, 单位: kg
2481 * @param cog 重心, 单位: m, 形式为(CoGx, CoGy, CoGz)
2482 * @param aom 力矩轴的方向, 单位: rad, 形式为(rx, ry, rz)
2483 * @param inertia 惯量, 单位: kg*m^2, 形式为(Ixx, Iyy, Izz, Ixy, Ixz,
2484 * Iyz)或(Ixx, Ixy, Ixz, Iyx, Iyy, Iyz, Izx, Izy, Izz)
2485 *
2486 * @return 成功返回0;失败返回错误码
2487 * AUBO_BUSY
2488 * AUBO_BAD_STATE
2489 * -AUBO_INVL_ARGUMENT
2490 * -AUBO_BAD_STATE
2491 *
2492 * @throws arcs::common_interface::AuboException
2493 *
2494 * @par Python函数原型
2495 * setPayload(self: pyaubo_sdk.RobotConfig, arg0: float, arg1: List[float],
2496 * arg2: List[float], arg3: List[float]) -> int
2497 *
2498 * @par Lua函数原型
2499 * setPayload(m: number, cog: table, aom: table, inertia: table) -> nil
2500 *
2501 * @par Lua示例
2502 * setPayload(3, {0,0,0}, {0,0,0}, {0,0,0,0,0,0,0,0,0})
2503 *
2504 * @par JSON-RPC请求示例
2505 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setPayload","params":[3,[0,0,0],[0,0,0],[0,0,0,0,0,0,0,0,0]],"id":1}
2506 *
2507 * @par JSON-RPC响应示例
2508 * {"id":1,"jsonrpc":"2.0","result":0}
2509 * \endchinese
2510 * \english
2511 * Set the payload.
2512 *
2513 * @param m Mass, unit: kg
2514 * @param cog Center of gravity, unit: m, format (CoGx, CoGy, CoGz)
2515 * @param aom Axis of moment, unit: rad, format (rx, ry, rz)
2516 * @param inertia Inertia, unit: kg*m^2, format (Ixx, Iyy, Izz, Ixy, Ixz,
2517 * Iyz) or (Ixx, Ixy, Ixz, Iyx, Iyy, Iyz, Izx, Izy, Izz)
2518 *
2519 * @return Returns 0 on success; error code on failure
2520 * AUBO_BUSY
2521 * AUBO_BAD_STATE
2522 * -AUBO_INVL_ARGUMENT
2523 * -AUBO_BAD_STATE
2524 *
2525 * @throws arcs::common_interface::AuboException
2526 *
2527 * @par Python function prototype
2528 * setPayload(self: pyaubo_sdk.RobotConfig, arg0: float, arg1: List[float],
2529 * arg2: List[float], arg3: List[float]) -> int
2530 *
2531 * @par Lua function prototype
2532 * setPayload(m: number, cog: table, aom: table, inertia: table) -> nil
2533 *
2534 * @par Lua example
2535 * setPayload(3, {0,0,0}, {0,0,0}, {0,0,0,0,0,0,0,0,0})
2536 *
2537 * @par JSON-RPC request example
2538 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.setPayload","params":[3,[0,0,0],[0,0,0],[0,0,0,0,0,0,0,0,0]],"id":1}
2539 *
2540 * @par JSON-RPC response example
2541 * {"id":1,"jsonrpc":"2.0","result":0}
2542 * \endenglish
2543 */
2544 int setPayload(double m, const std::vector<double> &cog,
2545 const std::vector<double> &aom,
2546 const std::vector<double> &inertia);
2547
2548 /**
2549 * \chinese
2550 * 获取有效负载
2551 *
2552 * @return 有效负载.
2553 * 第一个元素表示质量, 单位: kg;
2554 * 第二个元素表示重心, 单位: m, 形式为(CoGx, CoGy, CoGz);
2555 * 第三个元素表示力矩轴的方向, 单位: rad, 形式为(rx, ry, rz);
2556 * 第四个元素表示惯量, 单位: kg*m^2, 形式为(Ixx, Iyy, Izz, Ixy, Ixz, Iyz)
2557 *
2558 * @throws arcs::common_interface::AuboException
2559 *
2560 * @par Python函数原型
2561 * getPayload(self: pyaubo_sdk.RobotConfig) -> Tuple[float, List[float],
2562 * List[float], List[float]]
2563 *
2564 * @par Lua函数原型
2565 * getPayload() -> number, table, table, table
2566 *
2567 * @par Lua示例
2568 * m, cog, aom, inertia = getPayload()
2569 *
2570 * @par JSON-RPC请求示例
2571 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getPayload","params":[],"id":1}
2572 *
2573 * @par JSON-RPC响应示例
2574 * {"id":1,"jsonrpc":"2.0","result":[3.0,[0.0,0.0,0.0],[0.0,0.0,0.0],[0.0,0.0,0.0,0.0,0.0,0.0]]}
2575 * \endchinese
2576 * \english
2577 * Get the payload.
2578 *
2579 * @return The payload.
2580 * The first element is the mass in kg;
2581 * The second element is the center of gravity in meters, format (CoGx,
2582 * CoGy, CoGz); The third element is the axis of moment in radians, format
2583 * (rx, ry, rz); The fourth element is the inertia in kg*m^2, format (Ixx,
2584 * Iyy, Izz, Ixy, Ixz, Iyz)
2585 *
2586 * @throws arcs::common_interface::AuboException
2587 *
2588 * @par Python function prototype
2589 * getPayload(self: pyaubo_sdk.RobotConfig) -> Tuple[float, List[float],
2590 * List[float], List[float]]
2591 *
2592 * @par Lua function prototype
2593 * getPayload() -> number, table, table, table
2594 *
2595 * @par Lua example
2596 * m, cog, aom, inertia = getPayload()
2597 *
2598 * @par JSON-RPC request example
2599 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getPayload","params":[],"id":1}
2600 *
2601 * @par JSON-RPC response example
2602 * {"id":1,"jsonrpc":"2.0","result":[3.0,[0.0,0.0,0.0],[0.0,0.0,0.0],[0.0,0.0,0.0,0.0,0.0,0.0]]}
2603 * \endenglish
2604 */
2606
2607 /**
2608 * \chinese
2609 * 末端位姿是否在安全范围之内
2610 *
2611 * @param pose 末端位姿
2612 * @return 在安全范围内返回true; 反之返回false
2613 *
2614 * @throws arcs::common_interface::AuboException
2615 *
2616 * @par Python函数原型
2617 * toolSpaceInRange(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> bool
2618 *
2619 * @par Lua函数原型
2620 * toolSpaceInRange(pose: table) -> boolean
2621 *
2622 * @par JSON-RPC请求示例
2623 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.toolSpaceInRange","params":[[0.58712,
2624 * -0.15775, 0.48703, 2.76, 0.344, 1.432]],"id":1}
2625 *
2626 * @par JSON-RPC响应示例
2627 * {"id":1,"jsonrpc":"2.0","result":true}
2628 * \endchinese
2629 * \english
2630 * Whether the end-effector pose is within the safety range.
2631 *
2632 * @param pose End-effector pose
2633 * @return Returns true if within the safety range; otherwise returns false
2634 *
2635 * @throws arcs::common_interface::AuboException
2636 *
2637 * @par Python function prototype
2638 * toolSpaceInRange(self: pyaubo_sdk.RobotConfig, arg0: List[float]) -> bool
2639 *
2640 * @par Lua function prototype
2641 * toolSpaceInRange(pose: table) -> boolean
2642 *
2643 * @par JSON-RPC request example
2644 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.toolSpaceInRange","params":[[0.58712,
2645 * -0.15775, 0.48703, 2.76, 0.344, 1.432]],"id":1}
2646 *
2647 * @par JSON-RPC response example
2648 * {"id":1,"jsonrpc":"2.0","result":true}
2649 * \endenglish
2650 */
2651 bool toolSpaceInRange(const std::vector<double> &pose);
2652
2653 /**
2654 * \chinese
2655 * 发起固件升级请求,控制器软件将进入固件升级模式
2656 *
2657 * @param fw 固件升级路径。该路径的格式为: 固件安装包路径\#升级节点列表。
2658 * 其中固件安装包路径和升级节点列表以井号(#)分隔,升级节点以逗号(,)分隔。
2659 * 如果节点名称后带有!,则表示强制(不带版本校验)升级该节点;
2660 * 反之,则表示带校验版本地升级节点,
2661 * 即在升级该节点前,会先判断当前版本和目标版本是否相同,如果相同就不升级该节点。\n
2662 * 可以根据实际需求灵活设置需要升级的节点。\n
2663 * 例如,
2664 * /tmp/firmware_update-1.0.42-rc.5+2347b0d.firm\#master_mcu!,slace_mcu!,
2665 * base!,tool!,joint1!,joint2!,joint3!,joint4!,joint5!,joint6!
2666 * 表示强制升级接口板主板、接口板从板、基座、工具和6个关节(joint1至joint6)。\n
2667 * all表示所有的节点,例如
2668 * /tmp/firm_XXX.firm\#all 表示带校验版本地升级全部节点,
2669 * /tmp/firm_XXX.firm\#all!表示强制升级全部节点
2670 *
2671 * @return 指令下发成功返回0; 失败返回错误码。 \n
2672 * -AUBO_BAD_STATE: 运行时(RuntimeMachine)的当前状态不是Stopped,
2673 * 固件升级请求被拒绝。AUBO_BAD_STATE的值是1。 \n
2674 * -AUBO_TIMEOUT: 超时。AUBO_TIMEOUT的值是4。 \n
2675 *
2676 * @throws arcs::common_interface::AuboException
2677 *
2678 * @par Python函数原型
2679 * firmwareUpdate(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
2680 *
2681 * @par Lua函数原型
2682 * firmwareUpdate(fw: string) -> nil
2683 *
2684 * @par JSON-RPC请求示例
2685 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.firmwareUpdate","params":["/tmp/firmware_update-1.0.42-rc.12+3e33eac.firm#master_mcu"],"id":1}
2686 *
2687 * @par JSON-RPC响应示例
2688 * {"id":1,"jsonrpc":"2.0","result":0}
2689 * \endchinese
2690 * \english
2691 * Initiate a firmware upgrade request. The controller software will enter
2692 * firmware upgrade mode.
2693 *
2694 * @param fw Firmware upgrade path. The format is: firmware package
2695 * path\#upgrade node list. The firmware package path and node list are
2696 * separated by a hash (#), and nodes are separated by commas (,). If a node
2697 * name ends with !, it means to force upgrade (without version check) that
2698 * node; otherwise, the node will be upgraded only if the current version
2699 * differs from the target version. You can flexibly specify which nodes to
2700 * upgrade as needed. For example,
2701 * /tmp/firmware_update-1.0.42-rc.5+2347b0d.firm#master_mcu!,slace_mcu!,base!,tool!,joint1!,joint2!,joint3!,joint4!,joint5!,joint6!
2702 * means to force upgrade the interface board main, interface board slave,
2703 * base, tool, and joints 1-6. "all" means all nodes, e.g.
2704 * /tmp/firm_XXX.firm#all means upgrade all nodes with version check,
2705 * /tmp/firm_XXX.firm#all! means force upgrade all nodes.
2706 *
2707 * @return Returns 0 if the command is sent successfully; otherwise, returns
2708 * an error code. -AUBO_BAD_STATE: The current state of the RuntimeMachine
2709 * is not Stopped, so the firmware upgrade request is rejected.
2710 * AUBO_BAD_STATE = 1. -AUBO_TIMEOUT: Timeout. AUBO_TIMEOUT = 4.
2711 *
2712 * @throws arcs::common_interface::AuboException
2713 *
2714 * @par Python function prototype
2715 * firmwareUpdate(self: pyaubo_sdk.RobotConfig, arg0: str) -> int
2716 *
2717 * @par Lua function prototype
2718 * firmwareUpdate(fw: string) -> nil
2719 *
2720 * @par JSON-RPC request example
2721 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.firmwareUpdate","params":["/tmp/firmware_update-1.0.42-rc.12+3e33eac.firm#master_mcu"],"id":1}
2722 *
2723 * @par JSON-RPC response example
2724 * {"id":1,"jsonrpc":"2.0","result":0}
2725 * \endenglish
2726 */
2727 int firmwareUpdate(const std::string &fw);
2728
2729 /**
2730 * \chinese
2731 * 获取当前的固件升级的进程
2732 *
2733 * @return 当前的固件升级进程。 \n
2734 * 第一个元素表示步骤名称。如果是failed,则表示固件升级失败 \n
2735 * 第二个元素表示升级的进度(0~1),完成之后,返回("", 1)
2736 *
2737 * @throws arcs::common_interface::AuboException
2738 *
2739 * @par Python函数原型
2740 * getFirmwareUpdateProcess(self: pyaubo_sdk.RobotConfig) -> Tuple[str,
2741 * float]
2742 *
2743 * @par Lua函数原型
2744 * getFirmwareUpdateProcess() -> table
2745 *
2746 * @par JSON-RPC请求示例
2747 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getFirmwareUpdateProcess","params":[],"id":1}
2748 *
2749 * @par JSON-RPC响应示例
2750 * {"id":1,"jsonrpc":"2.0","result":[" ",0.0]}
2751 *
2752 * \endchinese
2753 * \english
2754 * Get the current firmware upgrade process.
2755 *
2756 * @return The current firmware upgrade process. \n
2757 * The first element is the step name. If it is "failed", the firmware
2758 * upgrade failed. \n The second element is the upgrade progress (0~1). When
2759 * finished, returns ("", 1)
2760 *
2761 * @throws arcs::common_interface::AuboException
2762 *
2763 * @par Python function prototype
2764 * getFirmwareUpdateProcess(self: pyaubo_sdk.RobotConfig) -> Tuple[str,
2765 * float]
2766 *
2767 * @par Lua function prototype
2768 * getFirmwareUpdateProcess() -> table
2769 *
2770 * @par JSON-RPC request example
2771 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getFirmwareUpdateProcess","params":[],"id":1}
2772 *
2773 * @par JSON-RPC response example
2774 * {"id":1,"jsonrpc":"2.0","result":[" ",0.0]}
2775 *
2776 * \endenglish
2777 */
2778 std::tuple<std::string, double> getFirmwareUpdateProcess();
2779
2780 /**
2781 * \chinese
2782 * 获取关节最大位置(当前正在使用的限制值)
2783 *
2784 * @return 返回关节最大位置(当前正在使用的限制值)
2785 *
2786 * @throws arcs::common_interface::AuboException
2787 *
2788 * @par Python函数原型
2789 * getLimitJointMaxPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
2790 *
2791 * @par Lua函数原型
2792 * getLimitJointMaxPositions() -> table
2793 *
2794 * @par JSON-RPC请求示例
2795 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMaxPositions","params":[],"id":1}
2796 *
2797 * @par JSON-RPC响应示例
2798 * {"id":1,"jsonrpc":"2.0","result":[6.2831854820251465,6.2831854820251465,6.2831854820251465,6.2831854820251465,6.2831854820251465,6.2831854820251465]}
2799 * \endchinese
2800 * \english
2801 * Get the joint maximum positions (currently used limit values).
2802 *
2803 * @return Returns the joint maximum positions (currently used limit
2804 * values).
2805 *
2806 * @throws arcs::common_interface::AuboException
2807 *
2808 * @par Python function prototype
2809 * getLimitJointMaxPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
2810 *
2811 * @par Lua function prototype
2812 * getLimitJointMaxPositions() -> table
2813 *
2814 * @par JSON-RPC request example
2815 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMaxPositions","params":[],"id":1}
2816 *
2817 * @par JSON-RPC response example
2818 * {"id":1,"jsonrpc":"2.0","result":[6.2831854820251465,6.2831854820251465,6.2831854820251465,6.2831854820251465,6.2831854820251465,6.2831854820251465]}
2819 * \endenglish
2820 */
2821 std::vector<double> getLimitJointMaxPositions();
2822
2823 /**
2824 * \chinese
2825 * 获取关节最小位置(当前正在使用的限制值)
2826 *
2827 * @return 返回关节最小位置(当前正在使用的限制值)
2828 *
2829 * @throws arcs::common_interface::AuboException
2830 *
2831 * @par Python函数原型
2832 * getLimitJointMinPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
2833 *
2834 * @par Lua函数原型
2835 * getLimitJointMinPositions() -> table
2836 *
2837 * @par JSON-RPC请求示例
2838 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMinPositions","params":[],"id":1}
2839 *
2840 * @par JSON-RPC响应示例
2841 * {"id":1,"jsonrpc":"2.0","result":[-6.2831854820251465,-6.2831854820251465,-6.2831854820251465,-6.2831854820251465,-6.2831854820251465,-6.2831854820251465]}
2842 * \endchinese
2843 * \english
2844 * Get the joint minimum positions (currently used limit values).
2845 *
2846 * @return Returns the joint minimum positions (currently used limit
2847 * values).
2848 *
2849 * @throws arcs::common_interface::AuboException
2850 *
2851 * @par Python function prototype
2852 * getLimitJointMinPositions(self: pyaubo_sdk.RobotConfig) -> List[float]
2853 *
2854 * @par Lua function prototype
2855 * getLimitJointMinPositions() -> table
2856 *
2857 * @par JSON-RPC request example
2858 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMinPositions","params":[],"id":1}
2859 *
2860 * @par JSON-RPC response example
2861 * {"id":1,"jsonrpc":"2.0","result":[-6.2831854820251465,-6.2831854820251465,-6.2831854820251465,-6.2831854820251465,-6.2831854820251465,-6.2831854820251465]}
2862 * \endenglish
2863 */
2864 std::vector<double> getLimitJointMinPositions();
2865
2866 /**
2867 * \chinese
2868 * 获取关节最大速度(当前正在使用的限制值)
2869 *
2870 * @return 返回关节最大速度(当前正在使用的限制值)
2871 *
2872 * @throws arcs::common_interface::AuboException
2873 *
2874 * @par Python函数原型
2875 * getLimitJointMaxSpeeds(self: pyaubo_sdk.RobotConfig) -> List[float]
2876 *
2877 * @par Lua函数原型
2878 * getLimitJointMaxSpeeds() -> table
2879 *
2880 * @par JSON-RPC请求示例
2881 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMaxSpeeds","params":[],"id":1}
2882 *
2883 * @par JSON-RPC响应示例
2884 * {"id":1,"jsonrpc":"2.0","result":[3.8920841217041016,3.8920841217041016,3.8920841217041016,3.1066861152648926,3.1066861152648926,3.1066861152648926]}
2885 * \endchinese
2886 * \english
2887 * Get the joint maximum speeds (currently used limit values).
2888 *
2889 * @return Returns the joint maximum speeds (currently used limit values).
2890 *
2891 * @throws arcs::common_interface::AuboException
2892 *
2893 * @par Python function prototype
2894 * getLimitJointMaxSpeeds(self: pyaubo_sdk.RobotConfig) -> List[float]
2895 *
2896 * @par Lua function prototype
2897 * getLimitJointMaxSpeeds() -> table
2898 *
2899 * @par JSON-RPC request example
2900 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMaxSpeeds","params":[],"id":1}
2901 *
2902 * @par JSON-RPC response example
2903 * {"id":1,"jsonrpc":"2.0","result":[3.8920841217041016,3.8920841217041016,3.8920841217041016,3.1066861152648926,3.1066861152648926,3.1066861152648926]}
2904 * \endenglish
2905 */
2906 std::vector<double> getLimitJointMaxSpeeds();
2907
2908 /**
2909 * \chinese
2910 * 获取关节最大加速度(当前正在使用的限制值)
2911 *
2912 * @return 返回关节最大加速度(当前正在使用的限制值)
2913 *
2914 * @throws arcs::common_interface::AuboException
2915 *
2916 * @par Python函数原型
2917 * getLimitJointMaxAccelerations(self: pyaubo_sdk.RobotConfig) ->
2918 * List[float]
2919 *
2920 * @par Lua函数原型
2921 * getLimitJointMaxAccelerations() -> table
2922 *
2923 * @par JSON-RPC请求示例
2924 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMaxAccelerations","params":[],"id":1}
2925 *
2926 * @par JSON-RPC响应示例
2927 * {"id":1,"jsonrpc":"2.0","result":[31.104877758314785,31.104877758314785,31.104877758314785,20.73625684294463,20.73625684294463,20.73625684294463]}
2928 * \endchinese
2929 * \english
2930 * Get the joint maximum accelerations (currently used limit values).
2931 *
2932 * @return Returns the joint maximum accelerations (currently used limit
2933 * values).
2934 *
2935 * @throws arcs::common_interface::AuboException
2936 *
2937 * @par Python function prototype
2938 * getLimitJointMaxAccelerations(self: pyaubo_sdk.RobotConfig) ->
2939 * List[float]
2940 *
2941 * @par Lua function prototype
2942 * getLimitJointMaxAccelerations() -> table
2943 *
2944 * @par JSON-RPC request example
2945 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitJointMaxAccelerations","params":[],"id":1}
2946 *
2947 * @par JSON-RPC response example
2948 * {"id":1,"jsonrpc":"2.0","result":[31.104877758314785,31.104877758314785,31.104877758314785,20.73625684294463,20.73625684294463,20.73625684294463]}
2949 * \endenglish
2950 */
2951 std::vector<double> getLimitJointMaxAccelerations();
2952
2953 /**
2954 * \chinese
2955 * 获取TCP最大速度(当前正在使用的限制值)
2956 *
2957 * @return 返回TCP最大速度(当前正在使用的限制值)
2958 *
2959 * @throws arcs::common_interface::AuboException
2960 *
2961 * @par Python函数原型
2962 * getLimitTcpMaxSpeed(self: pyaubo_sdk.RobotConfig) -> List[float]
2963 *
2964 * @par Lua函数原型
2965 * getLimitTcpMaxSpeed() -> table
2966 *
2967 * @par JSON-RPC请求示例
2968 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitTcpMaxSpeed","params":[],"id":1}
2969 *
2970 * @par JSON-RPC响应示例
2971 * {"id":1,"jsonrpc":"2.0","result":2.0}
2972 * \endchinese
2973 * \english
2974 * Get the TCP maximum speed (currently used limit value).
2975 *
2976 * @return Returns the TCP maximum speed (currently used limit value).
2977 *
2978 * @throws arcs::common_interface::AuboException
2979 *
2980 * @par Python function prototype
2981 * getLimitTcpMaxSpeed(self: pyaubo_sdk.RobotConfig) -> List[float]
2982 *
2983 * @par Lua function prototype
2984 * getLimitTcpMaxSpeed() -> table
2985 *
2986 * @par JSON-RPC request example
2987 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getLimitTcpMaxSpeed","params":[],"id":1}
2988 *
2989 * @par JSON-RPC response example
2990 * {"id":1,"jsonrpc":"2.0","result":2.0}
2991 * \endenglish
2992 */
2994
2995 /**
2996 * \chinese
2997 * 获取当前安全停止的类型
2998 *
2999 * @return 返回当前安全停止的类型
3000 *
3001 * @par JSON-RPC请求示例
3002 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSafeguardStopType","params":[],"id":1}
3003 *
3004 * @par JSON-RPC响应示例
3005 * {"id":1,"jsonrpc":"2.0","result":"None"}
3006 * \endchinese
3007 * \english
3008 * Get the current safeguard stop type.
3009 *
3010 * @return Returns the current safeguard stop type.
3011 *
3012 * @par JSON-RPC request example
3013 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSafeguardStopType","params":[],"id":1}
3014 *
3015 * @par JSON-RPC response example
3016 * {"id":1,"jsonrpc":"2.0","result":"None"}
3017 * \endenglish
3018 */
3020
3021 /**
3022 * \chinese
3023 * 按位获取完整的安全停止触发源
3024 *
3025 * @return 返回所有安全停止触发源
3026 *
3027 * 安全停止的原因:
3028 * 手动模式下可配置安全IO触发的安全停止 - 1<<0
3029 * 自动模式下可配置安全IO触发的安全停止 - 1<<1
3030 * 控制柜SI输入触发的安全停止 - 1<<2
3031 * 示教器三态开关触发的安全停止 - 1<<3
3032 * 自动切手动触发的安全停止 - 1<<4
3033 *
3034 * @par JSON-RPC请求示例
3035 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSafeguardStopSource","params":[],"id":1}
3036 *
3037 * @par JSON-RPC响应示例
3038 * {"id":1,"jsonrpc":"2.0","result":0}
3039 * \endchinese
3040 * \english
3041 * Get the complete safeguard stop source as a bitmask.
3042 *
3043 * @return Returns all safeguard stop sources.
3044 *
3045 * Reasons for safeguard stop:
3046 * Safeguard stop triggered by configurable safety IO in manual mode - 1<<0
3047 * Safeguard stop triggered by configurable safety IO in automatic mode -
3048 * 1<<1 Safeguard stop triggered by control box SI input - 1<<2 Safeguard
3049 * stop triggered by teach pendant three-position switch - 1<<3 Safeguard
3050 * stop triggered by switching from auto to manual - 1<<4
3051 *
3052 * @par JSON-RPC request example
3053 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSafeguardStopSource","params":[],"id":1}
3054 *
3055 * @par JSON-RPC response example
3056 * {"id":1,"jsonrpc":"2.0","result":0}
3057 * \endenglish
3058 */
3060
3061 /**
3062 * \chinese
3063 * 按位获取完整的机器人紧急停止触发源
3064 *
3065 * @return 返回所有机器人紧急停止触发源
3066 *
3067 * 紧急停止的原因:
3068 * 控制柜紧急停止按钮触发 - 1<<0
3069 * 示教器紧急停止按钮触发 - 1<<1
3070 * 手柄紧急停止按钮触发 - 1<<2
3071 * 固定IO紧急停止触发 - 1<<3
3072 *
3073 * @par JSON-RPC请求示例
3074 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getRobotEmergencyStopSource","params":[],"id":1}
3075 *
3076 * @par JSON-RPC响应示例
3077 * {"id":1,"jsonrpc":"2.0","result":0}
3078 * \endchinese
3079 * \english
3080 * Get the complete robot emergency stop source as a bitmask.
3081 *
3082 * @return Returns all robot emergency stop sources.
3083 *
3084 * Reasons for emergency stop:
3085 * Emergency stop triggered by control box button - 1<<0
3086 * Emergency stop triggered by teach pendant button - 1<<1
3087 * Emergency stop triggered by handle button - 1<<2
3088 * Emergency stop triggered by fixed IO - 1<<3
3089 *
3090 * @par JSON-RPC request example
3091 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getRobotEmergencyStopSource","params":[],"id":1}
3092 *
3093 * @par JSON-RPC response example
3094 * {"id":1,"jsonrpc":"2.0","result":0}
3095 * \endenglish
3096 */
3098
3099 /**
3100 * \chinese
3101 * 获取工具端力矩传感器的名字
3102 *
3103 * @return 当前工具端力矩传感器名字
3104 *
3105 * @throws arcs::common_interface::AuboException
3106 *
3107 * @par Python函数原型
3108 * getSelectedTcpForceSensorName(self: pyaubo_sdk.RobotConfig) -> str
3109 *
3110 * @par Lua函数原型
3111 * getSelectedTcpForceSensorName() -> str
3112 *
3113 * @par JSON-RPC请求示例
3114 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSelectedTcpForceSensorName","params":[],"id":1}
3115 * \endchinese
3116 * \english
3117 * Get the name of the selected TCP force sensor.
3118 *
3119 * @return The name of the currently selected TCP force sensor.
3120 *
3121 * @throws arcs::common_interface::AuboException
3122 *
3123 * @par Python function prototype
3124 * getSelectedTcpForceSensorName(self: pyaubo_sdk.RobotConfig) -> str
3125 *
3126 * @par Lua function prototype
3127 * getSelectedTcpForceSensorName() -> str
3128 *
3129 * @par JSON-RPC request example
3130 * {"jsonrpc":"2.0","method":"rob1.RobotConfig.getSelectedTcpForceSensorName","params":[],"id":1}
3131 * \endenglish
3132 */
3134
3135protected:
3136 void *d_;
3137};
3138using RobotConfigPtr = std::shared_ptr<RobotConfig>;
3139
3140} // namespace common_interface
3141} // namespace arcs
3142#endif // AUBO_SDK_ROBOT_CONFIG_H
double getDefaultJointSpeed()
获取默认的关节速度,单位rad/s
double getDefaultJointAcc()
获取默认的关节加速度,单位rad/s^2
int setHandguidDamp(const std::vector< double > &damp)
设置混合拖动阻尼
int getSafeguardStopSource()
按位获取完整的安全停止触发源
std::string getHardwareCustomParameters(const std::string &param)
获取硬件抽象层自定义参数
bool hasBaseForceSensor()
是否安装了底座力矩传感器
std::string getName()
获取机器人的名字
int setBaseForceOffset(const std::vector< double > &force_offset)
设置底座力矩偏移
int setKinematicsCompensate(const std::unordered_map< std::string, std::vector< double > > &param)
设置标准 DH 补偿到机器人
int selectTcpForceSensor(const std::string &name)
设置末端力矩传感器 如果存在内置的末端力矩传感器,默认将使用内置的力矩传感器
std::vector< double > getTcpForceSensorPose()
获取传感器安装位姿
std::vector< double > getJointMinPositions()
获取关节最小位置(物理极限)
std::vector< double > getLimitJointMaxPositions()
获取关节最大位置(当前正在使用的限制值)
int setWorkObjectData(const WObjectData &wobj)
设置工件数据,编程点位都是基于工件坐标系
std::unordered_map< std::string, std::vector< double > > getKinematicsParam(bool real)
获取机器人DH参数 alpha a d theta beta
std::vector< double > getJointMaxSpeeds()
获取关节最大速度(物理极限)
int setPersistentParameters(const std::string &param)
设置需要保存到接口板底座的参数
double getLimitTcpMaxSpeed()
获取TCP最大速度(当前正在使用的限制值)
int setCollisionLevel(int level)
设置碰撞灵敏度等级 数值越大越灵敏
int getRobotEmergencyStopSource()
按位获取完整的机器人紧急停止触发源
int setHardwareCustomParameters(const std::string &param)
设置硬件抽象层自定义参数 目的是为了做不同硬件之间的兼容
uint32_t calcSafetyParametersCheckSum(const RobotSafetyParameterRange &parameters)
计算安全参数的 CRC32 校验值
std::vector< double > getLimitJointMinPositions()
获取关节最小位置(当前正在使用的限制值)
int setTcpForceOffset(const std::vector< double > &force_offset)
设置末端力矩偏移
std::vector< std::string > getTcpForceSensorNames()
获取可用的末端力矩传感器的名字
std::vector< double > getHomePosition()
获取机器人的原点位置
double getDefaultToolSpeed()
获取默认的工具端速度,单位m/s
Payload getPayload()
获取有效负载
std::string getRobotSubType()
获取机器人子类型代码
int getCollisionLevel()
获取碰撞灵敏度等级
std::vector< double > getTcpForceOffset()
获取末端力矩偏移
std::vector< double > getFreedriveDamp()
获取拖动阻尼
std::vector< double > getJointMaxPositions()
获取关节最大位置(物理极限)
int setTcpForceSensorPose(const std::vector< double > &sensor_pose)
设置传感器安装位姿
std::unordered_map< std::string, std::vector< double > > getKinematicsCompensate(double ref_temperature)
获取指定温度下的DH参数补偿值:alpha a d theta beta
bool toolSpaceInRange(const std::vector< double > &pose)
末端位姿是否在安全范围之内
int setGravity(const std::vector< double > &gravity)
设置机器人安装姿态
SafeguedStopType getSafeguardStopType()
获取当前安全停止的类型
int setMountingPose(const std::vector< double > &pose)
设置安装位姿(机器人的基坐标系相对于世界坐标系) world->base
std::vector< double > getBaseForceOffset()
获取底座力矩偏移
std::vector< double > getTcpOffset()
获取当前的TCP偏移
int getDof()
获取机器人的自由度(从硬件抽象层读取)
int getCollisionStopType()
获取碰撞停止类型
int setHomePosition(const std::vector< double > &positions)
设置机器人的原点位置
double getCycletime()
获取机器人的伺服控制周期(从硬件抽象层读取)
std::string getControlBoxType()
获取控制柜类型代码
std::vector< std::string > getBaseForceSensorNames()
获取可用的底座力矩传感器的名字
double getSlowDownFraction(int level)
获取预设的缓速模式下的速度缩减比例
std::vector< double > getMountingPose()
获取安装位姿(机器人的基坐标系相对于世界坐标系)
std::vector< double > getLimitJointMaxAccelerations()
获取关节最大加速度(当前正在使用的限制值)
std::vector< double > getTcpMaxAccelerations()
获取TCP最大加速度(物理极限)
std::tuple< std::string, double > getFirmwareUpdateProcess()
获取当前的固件升级的进程
int setRobotZero()
设置机器人关节零位
int setSlowDownFraction(int level, double fraction)
预设缓速模式下的速度缩减比例
int firmwareUpdate(const std::string &fw)
发起固件升级请求,控制器软件将进入固件升级模式
std::string getSelectedTcpForceSensorName()
获取工具端力矩传感器的名字
std::vector< double > getLimitJointMaxSpeeds()
获取关节最大速度(当前正在使用的限制值)
double getDefaultToolAcc()
获取默认的工具端加速度,单位m/s^2
std::vector< double > getGravity()
获取机器人的安装姿态
int selectBaseForceSensor(const std::string &name)
设置底座力矩传感器 如果存在内置的底座力矩传感器,默认将使用内置的力矩传感器
std::string getRobotType()
获取机器人类型代码
int confirmSafetyParameters(const RobotSafetyParameterRange &parameters)
发起确认安全配置参数请求: 将安全配置参数写入到安全接口板flash或文件
bool hasTcpForceSensor()
是否安装了末端力矩传感器
std::vector< double > getJointMaxAccelerations()
获取关节最大加速度(物理极限)
int setCollisionStopType(int type)
设置碰撞停止类型
int setPayload(double m, const std::vector< double > &cog, const std::vector< double > &aom, const std::vector< double > &inertia)
设置有效负载
uint32_t getSafetyParametersCheckSum()
获取安全参数校验码 CRC32
int setToolInertial(double m, const std::vector< double > &com, const std::vector< double > &inertial)
设置工具端质量、质心及惯量
int setFreedriveDamp(const std::vector< double > &damp)
设置拖动阻尼
std::vector< double > getTcpMaxSpeeds()
获取TCP最大速度(物理极限)
int setTcpOffset(const std::vector< double > &offset)
设置当前的TCP偏移
std::vector< double > getHandguidDamp()
获取混合拖动阻尼
int attachRobotBaseTo(const std::string &frame)
将机器人绑定到一个坐标系,如果这个坐标系是运动的,那机器人也会跟着运动 应用于地轨或者龙门 这个函数调用的时候 frame 和 ROBOTBASE 的相对关系就固定了
std::shared_ptr< RobotConfig > RobotConfigPtr
std::tuple< double, std::vector< double >, std::vector< double >, std::vector< double > > Payload
Definition type_def.h:703
数据类型的定义