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