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