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