PDF
AUBO SDK  0.26.0
robot_algorithm.h
浏览该文件的文档.
1/** @file robot_algorithm.h
2 * @brief 机器人算法相关的对外接口
3 */
4#ifndef AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
5#define AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
6
7#include <string>
8#include <vector>
9#include <memory>
10#include <functional>
11
12#include <aubo/global_config.h>
13#include <aubo/type_def.h>
14
15namespace arcs {
16namespace common_interface {
17
18// clang-format off
19
20/**
21 * \chinese
22 * @defgroup RobotAlgorithm RobotAlgorithm (机器人算法工具)
23 * @ingroup RobotInterface
24 * \endchinese
25 *
26 * \english
27 * @defgroup RobotAlgorithm Robot Algorithm Tool
28 * @ingroup RobotInterface
29 * \endenglish
30 *
31 * \chinese
32 * 机器人算法相关的对外接口
33 * \endchinese
34 * \english
35 * Interfaces related to robot algorithms
36 * \endenglish
37 */
38class ARCS_ABI_EXPORT RobotAlgorithm
39{
40public:
42 virtual ~RobotAlgorithm();
43
44 /**
45 * @ingroup RobotAlgorithm
46 * \chinese
47 * 力传感器标定算法(三点标定法)
48 *
49 * @param force 力数据
50 * @param q 关节角度
51 * @return 标定结果
52 *
53 * @throws arcs::common_interface::AuboException
54 *
55 * @par Python函数原型
56 * calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0:
57 * List[List[float]], arg1: List[List[float]]) -> Tuple[List[float],
58 * List[float], float, List[float]]
59 *
60 * @par Lua函数原型
61 * calibrateTcpForceSensor(force: table, q: table) -> table
62 *
63 * @par Lua示例
64 * cal_table = calibrateTcpForceSensor({10.0,10.0,10.0,-1.2,-1.2,-1.2}, {3.083,1.227,1.098,0.670,-1.870,-0.397})
65 *
66 * \endchinese
67 * \english
68 * Force sensor calibration algorithm (three-point calibration method)
69 *
70 * @param force Force data
71 * @param q Joint angles
72 * @return Calibration result
73 *
74 * @throws arcs::common_interface::AuboException
75 *
76 * @par Python function prototype
77 * calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0:
78 * List[List[float]], arg1: List[List[float]]) -> Tuple[List[float],
79 * List[float], float, List[float]]
80 *
81 * @par Lua function prototype
82 * calibrateTcpForceSensor(force: table, q: table) -> table
83 *
84 * @par Lua example
85 * cal_table = calibrateTcpForceSensor({10.0,10.0,10.0,-1.2,-1.2,-1.2}, {3.083,1.227,1.098,0.670,-1.870,-0.397})
86 *
87 * \endenglish
88 */
90 const std::vector<std::vector<double>> &forces,
91 const std::vector<std::vector<double>> &poses);
92
93 /**
94 * @ingroup RobotAlgorithm
95 * \chinese
96 * 力传感器标定算法(三点标定法)
97 * @param forces
98 * @param poses
99 * @return force_offset, com, mass, angle error
100 *
101 * @throws arcs::common_interface::AuboException
102 * \endchinese
103 * \english
104 * Force sensor calibration algorithm (three-point calibration method)
105 * @param forces
106 * @param poses
107 * @return force_offset, com, mass, angle error
108 *
109 * @throws arcs::common_interface::AuboException
110 * \endenglish
111 */
113 const std::vector<std::vector<double>> &forces,
114 const std::vector<std::vector<double>> &poses);
115
116 /**
117 * @ingroup RobotAlgorithm
118 * \chinese
119 * 力传感器偏置标定算法
120 *
121 * @param force 力数据
122 * @param poses 位姿
123 * @param mass 质量, 单位: kg
124 * @param cog 重心, 单位: m, 形式为(CoGx, CoGy, CoGz)
125 * @return 标定结果
126 *
127 * @throws arcs::common_interface::AuboException
128 * \endchinese
129 * \english
130 * Force sensor offset calibration algorithm
131 *
132 * @param forces Force data
133 * @param poses
134 * @param m Mass, unit: kg
135 * @param cog Center of gravity, unit: m, format (CoGx, CoGy, CoGz)
136 * @return Calibration result
137 *
138 * @throws arcs::common_interface::AuboException
139 * \endenglish
140 */
142 const std::vector<std::vector<double>> &forces,
143 const std::vector<std::vector<double>> &poses, const double &mass,
144 const std::vector<double>&cog);
145
146 /**
147 * @ingroup RobotAlgorithm
148 * \chinese
149 * 基于电流的负载辨识算法接口
150 *
151 * 需要采集空载时运行激励轨迹的位置、速度、电流以及带负载时运行激励轨迹的位置、速度、电流
152 *
153 * @param data_file_no_payload
154 * 空载时运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
155 * @param data_file_with_payload
156 * 带负载运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
157 * @return 辨识的结果
158 *
159 * @throws arcs::common_interface::AuboException
160 *
161 * @par Python函数原型
162 * payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]],
163 * arg1: List[List[float]]) -> Tuple[List[float], List[float], float,
164 * List[float]]
165 *
166 * @par Lua函数原型
167 * payloadIdentify(data_with_payload: table, data_with_payload: table) ->
168 * table
169 * \endchinese
170 * \english
171 * Payload identification algorithm interface based on current
172 *
173 * Requires collecting position, velocity, and current data when running the excitation trajectory without load, as well as with load.
174 *
175 * @param data_file_no_payload
176 * File path of joint data when running the excitation trajectory without load (.csv format), 18 columns in total: 6 joint positions, 6 joint velocities, 6 joint currents
177 * @param data_file_with_payload
178 * File path of joint data when running the excitation trajectory with load (.csv format), 18 columns in total: 6 joint positions, 6 joint velocities, 6 joint currents
179 * @return Identification result
180 *
181 * @throws arcs::common_interface::AuboException
182 *
183 * @par Python function prototype
184 * payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]],
185 * arg1: List[List[float]]) -> Tuple[List[float], List[float], float,
186 * List[float]]
187 *
188 * @par Lua function prototype
189 * payloadIdentify(data_with_payload: table, data_with_payload: table) ->
190 * table
191 * \endenglish
192 */
193 int payloadIdentify(const std::string &data_file_no_payload,
194 const std::string &data_file_with_payload);
195
196 /**
197 * @ingroup RobotAlgorithm
198 * \chinese
199 * 新版基于电流的负载辨识算法接口
200 *
201 * 需要采集带载时运行最少三个点的位置、速度、加速度、电流、温度、末端传感器数据、底座数据
202 *
203 * @param data
204 * 带负载的各关节数据的文件路径(.csv格式),共42列,末端传感器数据、底座数据默认为0
205 * @return 辨识的结果
206 * \endchinese
207 * \english
208 * New version of payload identification algorithm interface based on current
209 *
210 * Requires collecting at least three points of position, velocity, acceleration, current, temperature, end sensor data, and base data when running with load
211 *
212 * @param data
213 * File path of joint data with load (.csv format), 42 columns in total, end sensor data and base data default to 0
214 * @return Identification result
215 * \endenglish
216 */
217 int payloadIdentify1(const std::string &file_name);
218
219 /**
220 * @ingroup RobotAlgorithm
221 * \chinese
222 * 负载辨识是否计算完成
223 * @return 完成返回0; 正在进行中返回1; 计算失败返回<0;
224 *
225 * @throws arcs::common_interface::AuboException
226 *
227 * @par JSON-RPC请求示例
228 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
229 *
230 * @par JSON-RPC响应示例
231 * {"id":1,"jsonrpc":"2.0","result":0}
232 *
233 * \endchinese
234 * \english
235 * Whether payload identification calculation is finished
236 * @return 0 if finished; 1 if in progress; <0 if failed;
237 *
238 * @throws arcs::common_interface::AuboException
239 *
240 * @par JSON-RPC request example
241 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
242 *
243 * @par JSON-RPC response example
244 * {"id":1,"jsonrpc":"2.0","result":0}
245 *
246 * \endenglish
247 */
249
250 /**
251 * @ingroup RobotAlgorithm
252 * \chinese
253 * 获取负载辨识结果
254 * @return
255 *
256 * @throws arcs::common_interface::AuboException
257 *
258 * @par JSON-RPC请求示例
259 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
260 *
261 * @par JSON-RPC响应示例
262 * {"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}
263 *
264 * \endchinese
265 * \english
266 * Get the result of payload identification
267 * @return
268 *
269 * @throws arcs::common_interface::AuboException
270 *
271 * @par JSON-RPC request example
272 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
273 *
274 * @par JSON-RPC response example
275 * {"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}
276 *
277 * \endenglish
278 */
280
281 /**
282 * @ingroup RobotAlgorithm
283 * \chinese
284 * 关节摩擦力模型辨识算法接口
285 *
286 * @param q 关节角度
287 * @param qd 关节速度
288 * @param qdd 关节加速度
289 * @param temp 关节温度
290 * @return 是否辨识成功
291 *
292 * @throws arcs::common_interface::AuboException
293 *
294 * @par Python函数原型
295 * frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0:
296 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]],
297 * arg3: List[List[float]]) -> bool
298 *
299 * @par Lua函数原型
300 * frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) ->
301 * boolean
302 *
303 * @par Lua示例
304 * Identify_result = frictionModelIdentify({3.083,1.227,1.098,0.670,-1.870,-0.397},
305 * {10.0,10.0,10.0,10.0,10.0,10.0},{20.0,20.0,20.0,20.0,20.0,20.0},{30.0,30.0,30.0,30.0,30.0,30.0})
306 *
307 * \endchinese
308 * \english
309 * Joint friction model identification algorithm interface
310 *
311 * @param q Joint positions
312 * @param qd Joint velocities
313 * @param qdd Joint accelerations
314 * @param temp Joint temperatures
315 * @return Whether identification succeeded
316 *
317 * @throws arcs::common_interface::AuboException
318 *
319 * @par Python function prototype
320 * frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0:
321 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]],
322 * arg3: List[List[float]]) -> bool
323 *
324 * @par Lua function prototype
325 * frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) ->
326 * boolean
327 *
328 * @par Lua example
329 * Identify_result = frictionModelIdentify({3.083,1.227,1.098,0.670,-1.870,-0.397},
330 * {10.0,10.0,10.0,10.0,10.0,10.0},{20.0,20.0,20.0,20.0,20.0,20.0},{30.0,30.0,30.0,30.0,30.0,30.0})
331 *
332 * \endenglish
333 */
334 bool frictionModelIdentify(const std::vector<std::vector<double>> &q,
335 const std::vector<std::vector<double>> &qd,
336 const std::vector<std::vector<double>> &qdd,
337 const std::vector<std::vector<double>> &temp);
338
339 /**
340 * @ingroup RobotAlgorithm
341 * \chinese
342 * 工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移)
343 * 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
344 *
345 * @param q 关节角度
346 * @param type 标定类型
347 * @return 计算结果(工件坐标系位姿)以及错误代码
348 *
349 * @throws arcs::common_interface::AuboException
350 *
351 * @par Python函数原型
352 * calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0:
353 * List[List[float]], arg1: int) -> Tuple[List[float], int]
354 *
355 * @par Lua函数原型
356 * calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
357 *
358 * @par Lua示例
359 * coord_pose,coord_num = calibWorkpieceCoordinatePara({3.083,1.227,1.098,0.670,-1.870,-0.397},1)
360 *
361 * \endchinese
362 * \english
363 * Workpiece coordinate calibration algorithm interface (requires correct TCP offset set before calling)
364 * Input multiple sets of joint angles and calibration type, output workpiece coordinate pose (relative to robot base)
365 *
366 * @param q Joint angles
367 * @param type Calibration type
368 * @return Calculation result (workpiece coordinate pose) and error code
369 *
370 * @throws arcs::common_interface::AuboException
371 *
372 * @par Python function prototype
373 * calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0:
374 * List[List[float]], arg1: int) -> Tuple[List[float], int]
375 *
376 * @par Lua function prototype
377 * calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
378 *
379 * @par Lua example
380 * coord_pose,coord_num = calibWorkpieceCoordinatePara({3.083,1.227,1.098,0.670,-1.870,-0.397},1)
381 *
382 * \endenglish
383 */
385 const std::vector<std::vector<double>> &q, int type);
386
387 /**
388 * @ingroup RobotAlgorithm
389 * \chinese
390 * 动力学正解
391 *
392 * @param q 关节角
393 * @param torqs
394 * @return 计算结果以及错误代码
395 *
396 * @throws arcs::common_interface::AuboException
397 *
398 * @par Python函数原型
399 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
400 * List[float]) -> Tuple[List[float], int]
401 *
402 * @par Lua函数原型
403 * forwardDynamics(q: table, torqs: table) -> table, number
404 *
405 * @par Lua示例
406 * Dynamics, fk_result = forwardDynamics({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0})
407 *
408 * \endchinese
409 * \english
410 * Forward dynamics
411 *
412 * @param q Joint angles
413 * @param torqs
414 * @return Calculation result and error code
415 *
416 * @throws arcs::common_interface::AuboException
417 *
418 * @par Python function prototype
419 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
420 * List[float]) -> Tuple[List[float], int]
421 *
422 * @par Lua function prototype
423 * forwardDynamics(q: table, torqs: table) -> table, number
424 *
425 * @par Lua example
426 * Dynamics, fk_result = forwardDynamics({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0})
427 *
428 * \endenglish
429 */
430 ResultWithErrno forwardDynamics(const std::vector<double> &q,
431 const std::vector<double> &torqs);
432
433 /**
434 * @ingroup RobotAlgorithm
435 * \chinese
436 * 动力学正解,基于给定的TCP偏移
437 *
438 * @param q 关节角
439 * @param torqs
440 * @param tcp_offset TCP偏移
441 * @return 计算结果以及错误代码,同forwardDynamics
442 *
443 * @throws arcs::common_interface::AuboException
444 *
445 * @par Python函数原型
446 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
447 * List[float], arg2: List[float]) -> Tuple[List[float], int]
448 *
449 * @par Lua函数原型
450 * forwardDynamics1(q: table, torqs: table, tcp_offset: table) -> table, number
451 *
452 * @par Lua示例
453 * Dynamics, fk_result = forwardDynamics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0},{0.0,0.13201,0.03879,0,0,0})
454 *
455 * \endchinese
456 * \english
457 * Forward dynamics based on the given TCP offset
458 *
459 * @param q Joint angles
460 * @param torqs
461 * @param tcp_offset TCP offset
462 * @return Calculation result and error code, same as forwardDynamics
463 *
464 * @throws arcs::common_interface::AuboException
465 *
466 * @par Python function prototype
467 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
468 * List[float], arg2: List[float]) -> Tuple[List[float], int]
469 *
470 * @par Lua function prototype
471 * forwardDynamics1(q: table, torqs: table, tcp_offset: table) -> table, number
472 *
473 * @par Lua example
474 * Dynamics, fk_result = forwardDynamics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0},{0.0,0.13201,0.03879,0,0,0})
475 *
476 * \endenglish
477 */
478 ResultWithErrno forwardDynamics1(const std::vector<double> &q,
479 const std::vector<double> &torqs,
480 const std::vector<double> &tcp_offset);
481
482 /**
483 * @ingroup RobotAlgorithm
484 * \chinese
485 * 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数)
486 * 输入关节角度,输出TCP位姿
487 *
488 * @param q 关节角
489 * @return TCP位姿和正解结果是否有效
490 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
491 * 0 - 成功
492 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
493 * -5 - 输入的关节角无效(维度错误)
494 * @throws arcs::common_interface::AuboException
495 *
496 * @par Python函数原型
497 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
498 * Tuple[List[float], int]
499 *
500 * @par Lua函数原型
501 * forwardKinematics(q: table) -> table, number
502 *
503 * @par Lua示例
504 * pose, fk_result = forwardKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
505 *
506 * @par JSON-RPC请求示例
507 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
508 *
509 * @par JSON-RPC响应示例
510 * {"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
511 * \endchinese
512 * \english
513 * Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset)
514 * Input joint angles, output TCP pose
515 *
516 * @param q Joint angles
517 * @return TCP pose and whether the result is valid
518 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
519 * 0 - Success
520 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
521 * -5 - The input joint angles is invalid (dimension error)
522 * @throws arcs::common_interface::AuboException
523 *
524 * @par Python function prototype
525 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
526 * Tuple[List[float], int]
527 *
528 * @par Lua function prototype
529 * forwardKinematics(q: table) -> table, number
530 *
531 * @par Lua example
532 * pose, fk_result = forwardKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
533 *
534 * @par JSON-RPC request example
535 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
536 *
537 * @par JSON-RPC response example
538 * {"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
539 * \endenglish
540 */
541 ResultWithErrno forwardKinematics(const std::vector<double> &q);
542
543 /**
544 * @ingroup RobotAlgorithm
545 * \chinese
546 * 运动学正解
547 * 输入关节角度,输出TCP位姿
548 * @param q 关节角
549 * @param tcp_offset tcp偏移
550 * @return TCP位姿和正解结果是否有效
551 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
552 * 0 - 成功
553 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
554 * -5 - 输入的关节角或tcp偏移无效(维度错误)
555 * @throws arcs::common_interface::AuboException
556 *
557 * @par Python函数原型
558 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
559 * arg1: List[float]) -> Tuple[List[float], int]
560 *
561 * @par Lua函数原型
562 * forwardKinematics1(q: table, tcp_offset: table) -> table, number
563 *
564 * @par Lua示例
565 * pose, fk_result = forwardKinematics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.13201,0.03879,0,0,0})
566 *
567 * @par JSON-RPC请求示例
568 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0,
569 * 0.13201,0.03879,0,0,0]],"id":1}
570 *
571 * @par JSON-RPC响应示例
572 * {"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
573 *
574 * @since 0.24.1
575 * \endchinese
576 * \english
577 * Forward kinematics
578 * Input joint angles, output TCP pose
579 *
580 * @param q Joint angles
581 * @param tcp_offset TCP offset
582 * @return TCP pose and whether the result is valid
583 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
584 * 0 - Success
585 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
586 * -5 - The input joint angles or tcp offset is invalid (dimension error)
587 * @throws arcs::common_interface::AuboException
588 *
589 * @par Python function prototype
590 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
591 * arg1: List[float]) -> Tuple[List[float], int]
592 *
593 * @par Lua function prototype
594 * forwardKinematics1(q: table, tcp_offset: table) -> table, number
595 *
596 * @par Lua example
597 * pose, fk_result = forwardKinematics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.13201,0.03879,0,0,0})
598 *
599 * @par JSON-RPC request example
600 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0,
601 * 0.13201,0.03879,0,0,0]],"id":1}
602 *
603 * @par JSON-RPC response example
604 * {"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
605 *
606 * @since 0.24.1
607 * \endenglish
608 */
609 ResultWithErrno forwardKinematics1(const std::vector<double> &q,
610 const std::vector<double> &tcp_offset);
611
612 /**
613 * @ingroup RobotAlgorithm
614 * \chinese
615 * 运动学正解(忽略 TCP 偏移值)
616 *
617 * @param q 关节角
618 * @return 法兰盘中心位姿和正解结果是否有效
619 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
620 * 0 - 成功
621 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
622 * -5 - 输入的关节角无效(维度错误)
623 *
624 * @throws arcs::common_interface::AuboException
625 *
626 * @par Lua函数原型
627 * forwardToolKinematics(q: table) -> table, number
628 *
629 * @par Lua示例
630 * pose, fk_result = forwardToolKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
631 *
632 * @par JSON-RPC请求示例
633 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
634 *
635 * @par JSON-RPC响应示例
636 * {"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
637 * \endchinese
638 * \english
639 * Forward kinematics (ignoring TCP offset)
640 *
641 * @param q Joint angles
642 * @return Flange center pose and whether the result is valid
643 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
644 * 0 - Success
645 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
646 * -5 - The input joint angles is invalid (dimension error)
647 *
648 * @par Lua function prototype
649 * forwardToolKinematics(q: table) -> table, number
650 *
651 * @par Lua example
652 * pose, fk_result = forwardToolKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
653 *
654 * @throws arcs::common_interface::AuboException
655 *
656 * @par JSON-RPC request example
657 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
658 *
659 * @par JSON-RPC response example
660 * {"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
661 * \endenglish
662 */
663 ResultWithErrno forwardToolKinematics(const std::vector<double> &q);
664
665 /**
666 * @ingroup RobotAlgorithm
667 * \chinese
668 * 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数)
669 * 输入关节角度,输出各连杆位姿
670 *
671 * @param q 关节角
672 * @return 各个连杆位姿和正解结果是否有效
673 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
674 * 0 - 成功
675 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
676 * -5 - 输入的关节角无效(维度错误)
677 * @throws arcs::common_interface::AuboException
678 *
679 * @par Python函数原型
680 * forwardKinematicsAll(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
681 * Tuple[List[List[float]], int]
682 *
683 * @par Lua函数原型
684 * forwardKinematicsAll(q: table) -> table, number
685 *
686 * @par Lua示例
687 * poses, fk_result = forwardKinematicsAll({3.083,1.227,1.098,0.670,-1.870,-0.397})
688 *
689 * @par JSON-RPC请求示例
690 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematicsAll","params":{"q":[-7.32945e-11,-0.261799,1.74533,0.436332,1.5708,-2.14136e-10]},"id":1}
691 *
692 * @par JSON-RPC响应示例
693 * {"id":1,"jsonrpc":"2.0","result":[[[0.0010004,0.0,0.122,0.0,0.0,3.141592653589793],
694 * [0.0010003999910823934,-0.12166795404953117,0.12205392567412496,1.5690838552993878,-1.3089969602251492,0.0016541204887245322],
695 * [0.10659809449330016,-0.12166124765791932,0.5161518260534821,-1.5718540206872664,0.43633111081725523,-0.002370419930605744],
696 * [0.4482255342315581,-0.1226390142692,0.3568490758201224,-0.000788980482890453,1.5665204619271216,-1.5719618592940798],
697 * [0.5519603828181741,-0.12282266347465487,0.35639753697117343,1.5707938201843654,0.0042721909279596635,1.569044569428874],
698 * [0.5513243939877184,-0.12401224959696328,0.2615193425222568,-3.1349118101994096,0.004272190926529066,1.569044569643007],
699 * [0.7494883076798231,-0.025647479212994567,-0.04023458911333461,-3.1349118101994096,0.004272190926529066,1.569044569643007]],0]}
700 * \endchinese
701 * \english
702 * Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset)
703 * Input joint angles, output links poses
704 *
705 * @param q Joint angles
706 * @return links poses and whether the result is valid
707 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
708 * 0 - Success
709 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
710 * -5 - The input joint angles is invalid (dimension error)
711 * @throws arcs::common_interface::AuboException
712 *
713 * @par Python function prototype
714 * forwardKinematicsAll(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
715 * Tuple[List[List[float]], int]
716 *
717 * @par Lua function prototype
718 * forwardKinematicsAll(q: table) -> table, number
719 *
720 * @par Lua example
721 * pose, fk_result = forwardKinematicsAll({3.083,1.227,1.098,0.670,-1.870,-0.397})
722 *
723 * @par JSON-RPC request example
724 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematicsAll","params":{"q":[-7.32945e-11,-0.261799,1.74533,0.436332,1.5708,-2.14136e-10]},"id":1}
725 *
726 * @par JSON-RPC response example
727 * {"id":1,"jsonrpc":"2.0","result":[[[0.0010004,0.0,0.122,0.0,0.0,3.141592653589793],
728 * [0.0010003999910823934,-0.12166795404953117,0.12205392567412496,1.5690838552993878,-1.3089969602251492,0.0016541204887245322],
729 * [0.10659809449330016,-0.12166124765791932,0.5161518260534821,-1.5718540206872664,0.43633111081725523,-0.002370419930605744],
730 * [0.4482255342315581,-0.1226390142692,0.3568490758201224,-0.000788980482890453,1.5665204619271216,-1.5719618592940798],
731 * [0.5519603828181741,-0.12282266347465487,0.35639753697117343,1.5707938201843654,0.0042721909279596635,1.569044569428874],
732 * [0.5513243939877184,-0.12401224959696328,0.2615193425222568,-3.1349118101994096,0.004272190926529066,1.569044569643007],
733 * [0.7494883076798231,-0.025647479212994567,-0.04023458911333461,-3.1349118101994096,0.004272190926529066,1.569044569643007]],0]}
734 * \endenglish
735 */
736 ResultWithErrno1 forwardKinematicsAll(const std::vector<double> &q);
737
738 /**
739 * @ingroup RobotAlgorithm
740 * \chinese
741 * 运动学逆解
742 * 输入TCP位姿和参考关节角度,输出关节角度
743 *
744 * @param qnear 参考关节角
745 * @param pose TCP位姿
746 * @return 关节角和逆解结果是否有效
747 * 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下
748 * 0 - 成功
749 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
750 * -5 - 输入的参考关节角或TCP位姿无效(维度错误)
751 * -23 - 逆解计算不收敛,计算出错
752 * -24 - 逆解计算超出机器人最大限制
753 * -25 - 逆解输入配置存在错误
754 * -26 - 逆解雅可比矩阵计算失败
755 * -27 - 目标点存在解析解,但均不满足选解条件
756 * -28 - 逆解返回未知类型错误
757 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
758 *
759 * @throws arcs::common_interface::AuboException
760 *
761 * @par Python函数原型
762 * inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
763 * arg1: List[float]) -> Tuple[List[float], int]
764 *
765 * @par Lua函数原型
766 * inverseKinematics(qnear: table, pose: table) -> table, int
767 *
768 * @par Lua示例
769 * joint,ik_result = inverseKinematics({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
770 *
771 * @par JSON-RPC请求示例
772 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
773 *
774 * @par JSON-RPC响应示例
775 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
776 * \endchinese
777 * \english
778 * Inverse kinematics
779 * Input TCP pose and reference joint angles, output joint angles
780 *
781 * @param qnear Reference joint angles
782 * @param pose TCP pose
783 * @return Joint angles and whether the inverse kinematics result is valid
784 * The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows:
785 * 0 - Success
786 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
787 * -5 - The input reference joint angles or tcp pose is invalid (dimension error)
788 * -23 - Inverse kinematics calculation does not converge, calculation error
789 * -24 - Inverse kinematics calculation exceeds robot limits
790 * -25 - Inverse kinematics input configuration error
791 * -26 - Inverse kinematics Jacobian calculation failed
792 * -27 - Analytical solution exists but none satisfy the selection criteria
793 * -28 - Unknown error in inverse kinematics
794 * If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
795 *
796 * @throws arcs::common_interface::AuboException
797 *
798 * @par Python function prototype
799 * inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
800 * arg1: List[float]) -> Tuple[List[float], int]
801 *
802 * @par Lua function prototype
803 * inverseKinematics(qnear: table, pose: table) -> table, int
804 *
805 * @par Lua example
806 * joint,ik_result = inverseKinematics({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
807 *
808 * @par JSON-RPC request example
809 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
810 *
811 * @par JSON-RPC response example
812 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
813 * \endenglish
814 */
815 ResultWithErrno inverseKinematics(const std::vector<double> &qnear,
816 const std::vector<double> &pose);
817
818 /**
819 * @ingroup RobotAlgorithm
820 * \chinese
821 * 运动学逆解
822 * 输入TCP位姿和参考关节角度,输出关节角度
823 *
824 * @param qnear 参考关节角
825 * @param pose TCP位姿
826 * @param tcp_offset TCP偏移
827 * @return 关节角和逆解结果是否有效,同 inverseKinematics
828 * @throws arcs::common_interface::AuboException
829 *
830 * @par Python函数原型
831 * inverseKinematics1(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
832 * arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
833 *
834 * @par Lua函数原型
835 * inverseKinematics1(qnear: table, pose: table, tcp_offset: table) -> table, int
836 *
837 * @par Lua示例
838 * joint,ik_result = inverseKinematics1({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569},{0.04,-0.035,0.1,0,0,0})
839 *
840 * @par JSON-RPC请求示例
841 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics1","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0,
842 * 0.13201,0.03879,0,0,0]],"id":1}
843 *
844 * @par JSON-RPC响应示例
845 * {"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}
846 * \endchinese
847 * \english
848 * Inverse kinematics
849 * Input TCP pose and reference joint angles, output joint angles
850 *
851 * @param qnear Reference joint angles
852 * @param pose TCP pose
853 * @param tcp_offset TCP offset
854 * @return Joint angles and whether the result is valid, same as inverseKinematics
855 * @throws arcs::common_interface::AuboException
856 *
857 * @par Python function prototype
858 * inverseKinematics1(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
859 * arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
860 *
861 * @par Lua function prototype
862 * inverseKinematics1(qnear: table, pose: table, tcp_offset: table) -> table, int
863 *
864 * @par Lua example
865 * joint,ik_result = inverseKinematics1({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569},{0.04,-0.035,0.1,0,0,0})
866 *
867 * @par JSON-RPC request example
868 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics1","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0,
869 * 0.13201,0.03879,0,0,0]],"id":1}
870 *
871 * @par JSON-RPC response example
872 * {"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}
873 * \endenglish
874 */
875 ResultWithErrno inverseKinematics1(const std::vector<double> &qnear,
876 const std::vector<double> &pose,
877 const std::vector<double> &tcp_offset);
878
879 /**
880 * @ingroup RobotAlgorithm
881 * \chinese
882 * 同构型最小关节变化逆解
883 * 按照 qnear 的机械臂构型计算目标 TCP 位姿逆解,并在同构型逆解中选择相对 qnear 关节变化最小的一组
884 * 基于激活的 TCP 偏移(最近的通过 setTcpOffset 设置的参数)
885 *
886 * @param qnear 参考关节角
887 * @param pose TCP位姿,基于激活的 TCP 偏移(最近的通过 setTcpOffset 设置的参数)
888 * @return 关节角和逆解结果是否有效
889 * 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下
890 * 0 - 成功
891 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
892 * -5 - 输入的参考关节角或TCP位姿无效(维度错误)
893 * -23 - 逆解计算不收敛,计算出错
894 * -24 - 逆解计算超出机器人最大限制
895 * -25 - 逆解输入配置存在错误
896 * -26 - 逆解雅可比矩阵计算失败
897 * -27 - 目标点存在解析解,但均不满足同构型最小关节变化选解条件
898 * -28 - 逆解返回未知类型错误
899 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
900 * @throws arcs::common_interface::AuboException
901 *
902 * @par Python函数原型
903 * inverseKinematics2(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
904 * arg1: List[float]) -> Tuple[List[float], int]
905 *
906 * @par Lua函数原型
907 * inverseKinematics2(qnear: table, pose: table) -> table, int
908 *
909 * @par Lua示例
910 * joint,ik_result = inverseKinematics2({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
911 *
912 * @par JSON-RPC请求示例
913 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics2","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
914 *
915 * @par JSON-RPC响应示例
916 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
917 * \endchinese
918 * \english
919 * Inverse kinematics with the same robot configuration and minimum joint change
920 * Calculate the inverse kinematics solution for the target TCP pose according to the robot configuration of qnear, and select the solution with the minimum joint change relative to qnear among solutions with the same configuration.
921 * This interface is based on the activated TCP offset, which is the latest parameter set by setTcpOffset.
922 *
923 * @param qnear Reference joint angles
924 * @param pose TCP pose, based on the activated TCP offset, which is the latest parameter set by setTcpOffset
925 * @return Joint angles and whether the result is valid
926 * The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows:
927 * 0 - Success
928 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
929 * -5 - The input reference joint angles or tcp pose is invalid (dimension error)
930 * -23 - Inverse kinematics calculation does not converge, calculation error
931 * -24 - Inverse kinematics calculation exceeds robot limits
932 * -25 - Inverse kinematics input configuration error
933 * -26 - Inverse kinematics Jacobian calculation failed
934 * -27 - Analytical solution exists but none satisfy the same-configuration minimum-joint-change selection criteria
935 * -28 - Unknown error in inverse kinematics
936 * If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
937 * @throws arcs::common_interface::AuboException
938 *
939 * @par Python function prototype
940 * inverseKinematics2(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
941 * arg1: List[float]) -> Tuple[List[float], int]
942 *
943 * @par Lua function prototype
944 * inverseKinematics2(qnear: table, pose: table) -> table, int
945 *
946 * @par Lua example
947 * joint,ik_result = inverseKinematics2({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
948 *
949 * @par JSON-RPC request example
950 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics2","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
951 *
952 * @par JSON-RPC response example
953 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
954 * \endenglish
955 */
956 ResultWithErrno inverseKinematics2(const std::vector<double> &qnear,
957 const std::vector<double> &pose);
958
959 /**
960 * @ingroup RobotAlgorithm
961 * \chinese
962 * 求出所有的逆解, 基于激活的 TCP 偏移
963 *
964 * @param pose TCP位姿
965 * @return 关节角和逆解结果是否有效
966 * 返回的错误码同inverseKinematics
967 *
968 * @throws arcs::common_interface::AuboException
969 *
970 * @par JSON-RPC请求示例
971 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
972 *
973 * @par JSON-RPC响应示例
974 * {"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],
975 * [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411],
976 * [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845],
977 * [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}
978 * \endchinese
979 * \english
980 * Solve all inverse kinematics solutions based on the activated TCP offset
981 *
982 * @param pose TCP pose
983 * @return Joint angles and whether the result is valid
984 * The returned error code is the same as inverseKinematics
985 *
986 * @throws arcs::common_interface::AuboException
987 *
988 * @par JSON-RPC request example
989 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
990 *
991 * @par JSON-RPC response example
992 * {"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],
993 * [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411],
994 * [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845],
995 * [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}
996 * \endenglish
997 */
998 ResultWithErrno1 inverseKinematicsAll(const std::vector<double> &pose);
999
1000 /**
1001 * @ingroup RobotAlgorithm
1002 * \chinese
1003 * 求出所有的逆解, 基于提供的 TCP 偏移
1004 *
1005 * @param pose TCP位姿
1006 * @param tcp_offset TCP偏移
1007 * @return 关节角和逆解结果是否有效,同 inverseKinematicsAll
1008 * 返回的错误码同inverseKinematics
1009 *
1010 * @throws arcs::common_interface::AuboException
1011 *
1012 * @par JSON-RPC请求示例
1013 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll1","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0,
1014 * 0.13201,0.03879,0,0,0]],"id":1}
1015 *
1016 * @par JSON-RPC响应示例
1017 * {"id":1,"jsonrpc":"2.0","result":[[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],
1018 * [3.0818224058231602,0.17980369843203092,-1.0997576631122077,-0.48102131527371267,-1.8697135490338517,-0.40149459722060593],
1019 * [0.40972960018231047,-0.16226026285489026,1.0823403816496,0.2700204411869427,0.9734251963887868,0.0012903686498106507],
1020 * [0.41236549588802296,-1.193621392918341,-1.0828346680836718,-0.8671097369314354,0.972815367289568,0.007206851371073478]],0]}
1021 * \endchinese
1022 * \english
1023 * Solve all inverse kinematics solutions based on the provided TCP offset
1024 *
1025 * @param pose TCP pose
1026 * @param tcp_offset TCP offset
1027 * @return Joint angles and whether the result is valid, same as inverseKinematicsAll
1028 * The returned error code is the same as inverseKinematics
1029 *
1030 * @throws arcs::common_interface::AuboException
1031 *
1032 * @par JSON-RPC request example
1033 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll1","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0,
1034 * 0.13201,0.03879,0,0,0]],"id":1}
1035 *
1036 * @par JSON-RPC response example
1037 * {"id":1,"jsonrpc":"2.0","result":[[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],
1038 * [3.0818224058231602,0.17980369843203092,-1.0997576631122077,-0.48102131527371267,-1.8697135490338517,-0.40149459722060593],
1039 * [0.40972960018231047,-0.16226026285489026,1.0823403816496,0.2700204411869427,0.9734251963887868,0.0012903686498106507],
1040 * [0.41236549588802296,-1.193621392918341,-1.0828346680836718,-0.8671097369314354,0.972815367289568,0.007206851371073478]],0]}
1041 * \endenglish
1042 */
1044 const std::vector<double> &pose, const std::vector<double> &tcp_offset);
1045
1046 /**
1047 * @ingroup RobotAlgorithm
1048 * \chinese
1049 * 运动学逆解(忽略 TCP 偏移值)
1050 *
1051 * @param qnear 参考关节角
1052 * @param pose 法兰盘中心的位姿
1053 * @return 关节角和逆解结果是否有效
1054 * 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下
1055 * 0 - 成功
1056 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
1057 * -5 - 输入的参考关节角或位姿无效(维度错误)
1058 *
1059 * @throws arcs::common_interface::AuboException
1060 *
1061 * @par Lua函数原型
1062 * inverseToolKinematics(qnear: table, pose: table) -> table, int
1063 *
1064 * @par Lua示例
1065 * joint, ik_result = inverseToolKinematics({0,0,0,0,0,0},{0.58815,0.0532,0.62391,2.46,0.479,1.619})
1066 *
1067 * @par JSON-RPC请求示例
1068 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematics","params":[[0,0,0,0,0,0],[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
1069 *
1070 * @par JSON-RPC响应示例
1071 * {"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}
1072 * \endchinese
1073 * \english
1074 * Inverse kinematics (ignoring TCP offset)
1075 *
1076 * @param qnear Reference joint angles
1077 * @param pose Flange center pose
1078 * @return Joint angles and whether the result is valid
1079 * The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows:
1080 * 0 - Success
1081 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
1082 * -5 - The input reference joint angles or pose is invalid (dimension error)
1083 * @throws arcs::common_interface::AuboException
1084 *
1085 * @par Lua function prototype
1086 * inverseToolKinematics(qnear: table, pose: table) -> table, int
1087 *
1088 * @par Lua example
1089 * joint, ik_result = inverseToolKinematics({0,0,0,0,0,0},{0.58815,0.0532,0.62391,2.46,0.479,1.619})
1090 *
1091 * @par JSON-RPC request example
1092 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematics","params":[[0,0,0,0,0,0],[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
1093 *
1094 * @par JSON-RPC response example
1095 * {"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}
1096 * \endenglish
1097 */
1098 ResultWithErrno inverseToolKinematics(const std::vector<double> &qnear,
1099 const std::vector<double> &pose);
1100
1101 /**
1102 * @ingroup RobotAlgorithm
1103 * \chinese
1104 * 运动学逆解(忽略 TCP 偏移值)
1105 *
1106 * @param qnear 参考关节角
1107 * @param pose 法兰盘中心的位姿
1108 * @return 关节角和逆解结果是否有效
1109 *
1110 * @throws arcs::common_interface::AuboException
1111 *
1112 * @par JSON-RPC请求示例
1113 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
1114 *
1115 * @par JSON-RPC响应示例
1116 * {"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],
1117 * [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814],
1118 * [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287],
1119 * [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}
1120 * \endchinese
1121 * \english
1122 * Inverse kinematics (ignoring TCP offset)
1123 *
1124 * @param qnear Reference joint angles
1125 * @param pose Flange center pose
1126 * @return Joint angles and whether the result is valid
1127 *
1128 * @throws arcs::common_interface::AuboException
1129 *
1130 * @par JSON-RPC request example
1131 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
1132 *
1133 * @par JSON-RPC response example
1134 * {"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],
1135 * [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814],
1136 * [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287],
1137 * [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}
1138 * \endenglish
1139 */
1140 ResultWithErrno1 inverseToolKinematicsAll(const std::vector<double> &pose);
1141
1142 /**
1143 * @ingroup RobotAlgorithm
1144 * \chinese
1145 * 根据输入的关节角计算并返回对应的机械臂构型
1146 *
1147 * 机械臂构型由三个维度的状态组合而成,各维度定义如下:
1148 * - 肩部方向:LEFT(肩部朝左) / RIGHT(肩部朝右)
1149 * - 肘部方向:UP(肘部朝上) / DOWN(肘部朝下)
1150 * - 腕部状态:FLIP(腕部翻转) / NOFLIP(腕部不翻转)
1151 *
1152 * 三个维度两两组合共形成8种基础构型(L/R + U/D + F/N),该接口会根据输入的关节角解析出当前对应的构型类型,
1153 * 并返回其枚举值对应的整数形式及错误码(注:接口返回的是组合构型值,如LUF对应0,而非单独的LEFT/UP/FLIP枚举值)。
1154 *
1155 * @param q 输入的关节角数组,6轴机械臂为6个元素,单位:弧度(rad)
1156 * @return 机械臂构型结果及错误码(类型为ResultWithErrno3,即std::tuple<int, int>):
1157 * - 第一个int:机械臂构型枚举(RobotConfiguration)对应的整数值,取值范围及含义:
1158 * -1 (NONE) - 无效构型
1159 * 0 (LUF) - LEFT+UP+FLIP(左肩、肘上、腕翻转)
1160 * 1 (LUN) - LEFT+UP+NOFLIP(左肩、肘上、腕不翻转)
1161 * 2 (LDF) - LEFT+DOWN+FLIP(左肩、肘下、腕翻转)
1162 * 3 (LDN) - LEFT+DOWN+NOFLIP(左肩、肘下、腕不翻转)
1163 * 4 (RUF) - RIGHT+UP+FLIP(右肩、肘上、腕翻转)
1164 * 5 (RUN) - RIGHT+UP+NOFLIP(右肩、肘上、腕不翻转)
1165 * 6 (RDF) - RIGHT+DOWN+FLIP(右肩、肘下、腕翻转)
1166 * 7 (RDN) - RIGHT+DOWN+NOFLIP(右肩、肘下、腕不翻转)
1167 * - 第二个int:错误码,错误码含义如下:
1168 * 0 - 成功:构型计算完成,返回有效构型值
1169 * -1 - 机械臂状态异常:未初始化完成,可尝试重新初始化后调用
1170 * -5 - 输入参数无效:关节角数组维度错误(非6个元素)或数值超出合理范围
1171 *
1172 * @throws arcs::common_interface::AuboException 输入参数非法(如空数组、元素数量错误)时抛出
1173 *
1174 * @par Python函数原型
1175 * getRobotConfiguration(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[int, int]
1176 *
1177 * @par Lua函数原型
1178 * getRobotConfiguration(q: table) -> number, number
1179 *
1180 * @par Lua示例
1181 * -- 输入6轴关节角(单位:rad),获取构型及错误码
1182 * local joint_angles = {3.083,1.227,1.098,0.670,-1.870,-0.397}
1183 * local config_val, err_code = getRobotConfiguration(joint_angles)
1184 * if err_code == 0 then
1185 * print("机械臂构型值:", config_val) -- 示例输出:4(对应RUF,右肩、肘上、腕翻转)
1186 * else
1187 * print("获取构型失败,错误码:", err_code)
1188 * end
1189 *
1190 * @par JSON-RPC请求示例
1191 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getRobotConfiguration","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
1192 *
1193 * @par JSON-RPC响应示例
1194 * {"id":1,"jsonrpc":"2.0","result":[4,0]}
1195 * \endchinese
1196 * \english
1197 * Calculate and return the corresponding robot configuration based on input joint angles
1198 *
1199 * The robot configuration consists of three dimensions of states, with the following definitions for each dimension:
1200 * - Shoulder direction: LEFT (Shoulder to the left) / RIGHT (Shoulder to the right)
1201 * - Elbow direction: UP (Elbow up) / DOWN (Elbow down)
1202 * - Wrist state: FLIP (Wrist flipped) / NOFLIP (Wrist not flipped)
1203 *
1204 * The combination of the three dimensions forms 8 basic configurations (L/R + U/D + F/N). This interface parses the current
1205 * configuration type from the input joint angles and returns its integer value corresponding to the RobotConfiguration enumeration
1206 * and an error code (Note: The interface returns combined configuration values, e.g., LUF corresponds to 0, not the individual
1207 * enumeration values of LEFT/UP/FLIP).
1208 *
1209 * @param q Input joint angle array, 6 elements for 6-axis robot, unit: radians (rad)
1210 * @return Robot configuration result and error code (type: ResultWithErrno3, i.e., std::tuple<int, int>):
1211 * - First int: Integer value corresponding to the RobotConfiguration enumeration, value range and meanings:
1212 * -1 (NONE) - Invalid configuration
1213 * 0 (LUF) - LEFT+UP+FLIP (Left shoulder, elbow up, wrist flipped)
1214 * 1 (LUN) - LEFT+UP+NOFLIP (Left shoulder, elbow up, wrist not flipped)
1215 * 2 (LDF) - LEFT+DOWN+FLIP (Left shoulder, elbow down, wrist flipped)
1216 * 3 (LDN) - LEFT+DOWN+NOFLIP (Left shoulder, elbow down, wrist not flipped)
1217 * 4 (RUF) - RIGHT+UP+FLIP (Right shoulder, elbow up, wrist flipped)
1218 * 5 (RUN) - RIGHT+UP+NOFLIP (Right shoulder, elbow up, wrist not flipped)
1219 * 6 (RDF) - RIGHT+DOWN+FLIP (Right shoulder, elbow down, wrist flipped)
1220 * 7 (RDN) - RIGHT+DOWN+NOFLIP (Right shoulder, elbow down, wrist not flipped)
1221 * - Second int: Error code with the following meanings:
1222 * 0 - Success: Configuration calculation completed, valid configuration value returned
1223 * -1 - Abnormal robot state: Not initialized completely, try reinitializing before calling
1224 * -5 - Invalid input parameters: Incorrect dimension of joint angle array (not 6 elements) or values out of reasonable range
1225 *
1226 * @throws arcs::common_interface::AuboException Thrown when input parameters are illegal (e.g., empty array, wrong number of elements)
1227 *
1228 * @par Python function prototype
1229 * getRobotConfiguration(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[int, int]
1230 *
1231 * @par Lua function prototype
1232 * getRobotConfiguration(q: table) -> number, number
1233 *
1234 * @par Lua example
1235 * -- Input 6-axis joint angles (unit: rad) to get configuration and error code
1236 * local joint_angles = {3.083,1.227,1.098,0.670,-1.870,-0.397}
1237 * local config_val, err_code = getRobotConfiguration(joint_angles)
1238 * if err_code == 0 then
1239 * print("Robot configuration value: ", config_val) -- Example output: 4 (corresponding to RUF, Right shoulder, elbow up, wrist flipped)
1240 * else
1241 * print("Failed to get configuration, error code: ", err_code)
1242 * end
1243 *
1244 * @par JSON-RPC request example
1245 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getRobotConfiguration","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
1246 *
1247 * @par JSON-RPC response example
1248 * {"id":1,"jsonrpc":"2.0","result":[4,0]}
1249 * \endenglish
1250 */
1251 ResultWithErrno3 getRobotConfiguration(const std::vector<double>& q);
1252
1253 /**
1254 * \chinese
1255 * 求解movej之间的轨迹点
1256 *
1257 * @param q1 movej的起点
1258 * @param r1 在q1处的交融半径
1259 * @param q2 movej的终点
1260 * @param r2 在q2处的交融半径
1261 * @param d 采样距离
1262 * @return q1~q2 之间笛卡尔空间离散轨迹点(x,y,z,rx,ry,rz)集合
1263 *
1264 * @throws arcs::common_interface::AuboException
1265 *
1266 * @par Python函数原型
1267 * pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
1268 * float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
1269 *
1270 * @par Lua函数原型
1271 * pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) ->
1272 * table, number
1273 *
1274 * @par Lua示例
1275 * path , num = pathMovej({0.0,-0.2618,1.7453,0.4364,1.5711,0.0},0.25,{0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.03,0.2)
1276 *
1277 * \endchinese
1278 * \english
1279 * Solve the trajectory points between movej
1280 *
1281 * @param q1 Start point of movej
1282 * @param r1 Blend radius at q1
1283 * @param q2 End point of movej
1284 * @param r2 Blend radius at q2
1285 * @param d Sampling distance
1286 * @return Discrete trajectory points (x, y, z, rx, ry, rz) between q1 and q2 in Cartesian space
1287 *
1288 * @throws arcs::common_interface::AuboException
1289 *
1290 * @par Python function prototype
1291 * pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
1292 * float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
1293 *
1294 * @par Lua function prototype
1295 * pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) ->
1296 * table, number
1297 *
1298 * @par Lua example
1299 * path , num = pathMovej({0.0,-0.2618,1.7453,0.4364,1.5711,0.0},0.25,{0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.03,0.2)
1300 *
1301 * \endenglish
1302 */
1303 std::vector<std::vector<double>> pathMovej(const std::vector<double> &q1,
1304 double r1,
1305 const std::vector<double> &q2,
1306 double r2, double d);
1307 /**
1308 * @ingroup RobotAlgorithm
1309 * \chinese
1310 * 计算机械臂末端的雅克比矩阵
1311 *
1312 * @param q 关节角
1313 * @param base_or_end 参考坐标系为基坐标系(或者末端坐标系)
1314 * true: 在 base 下描述
1315 * false: 在 末端坐标系 下描述
1316 * @return 雅克比矩阵是否有效
1317 * 返回值的第一个参数为该构型下对应的雅克比矩阵,第二个为逆解错误码
1318 * 此接口的错误码返回值在0.28.1-rc.21 0.29.0-alpha.25版本之后做了修改。
1319 * 此前逆解错误时返回 30082 ,修改后错误码返回列表如下
1320 * 0 - 成功
1321 * -23 - 逆解计算不收敛,计算出错
1322 * -24 - 逆解计算超出机器人最大限制
1323 * -25 - 逆解输入配置存在错误
1324 * -26 - 逆解雅可比矩阵计算失败
1325 * -27 - 目标点存在解析解,但均不满足选解条件
1326 * -28 - 逆解返回未知类型错误
1327 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
1328 *
1329 * @throws arcs::common_interface::AuboException
1330 *
1331 * @par Python函数原型
1332 * calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
1333 * arg1: bool) -> Tuple[List[float], int]
1334 *
1335 * @par Lua函数原型
1336 * calJacobian(q: table, base_or_end: boolean) -> table
1337 *
1338 * @par Lua示例
1339 * calJ_result = calJacobian({0.58815,0.0532,0.62391,2.46,0.479,1.619},true)
1340 *
1341 * @par JSON-RPC请求示例
1342 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
1343 *
1344 * @par JSON-RPC响应示例
1345 * {"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487,
1346 * 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346,
1347 * 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867,
1348 * -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091,
1349 * -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894,
1350 * 0.43771285536682175],0]}
1351 * \endchinese
1352 * \english
1353 * Calculate the Jacobian matrix at the robot end-effector
1354 *
1355 * @param q Joint angles
1356 * @param base_or_end Reference frame: base (or end-effector)
1357 * true: described in base frame
1358 * false: described in end-effector frame
1359 * @return Whether the Jacobian matrix is valid
1360 * The first parameter of the return value is the Jacobian matrix for this configuration, the second is the error code.
1361 * The error code list was updated after versions 0.28.1-rc.21 and 0.29.0-alpha.25.
1362 * Previously, inverse kinematics errors returned 30082. The updated error codes are:
1363 * 0 - Success
1364 * -23 - Inverse kinematics calculation does not converge, calculation error
1365 * -24 - Inverse kinematics calculation exceeds robot limits
1366 * -25 - Inverse kinematics input configuration error
1367 * -26 - Inverse kinematics Jacobian calculation failed
1368 * -27 - Analytical solution exists but none satisfy the selection criteria
1369 * -28 - Unknown error in inverse kinematics
1370 * If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
1371 *
1372 * @throws arcs::common_interface::AuboException
1373 *
1374 * @par Python function prototype
1375 * calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
1376 * arg1: bool) -> Tuple[List[float], int]
1377 *
1378 * @par Lua function prototype
1379 * calJacobian(q: table, base_or_end: boolean) -> table
1380 *
1381 * @par Lua example
1382 * calJ_result = calJacobian({0.58815,0.0532,0.62391,2.46,0.479,1.619},true)
1383 *
1384 * @par JSON-RPC request example
1385 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
1386 *
1387 * @par JSON-RPC response example
1388 * {"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487,
1389 * 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346,
1390 * 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867,
1391 * -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091,
1392 * -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894,
1393 * 0.43771285536682175],0]}
1394 * \endenglish
1395 */
1396 ResultWithErrno calcJacobian(const std::vector<double> &q,
1397 bool base_or_end);
1398
1399 /**
1400 * @ingroup RobotAlgorithm
1401 * \chinese
1402 * 求解交融的轨迹点
1403 *
1404 * @param type
1405 * 0-movej 和 movej
1406 * 1-movej 和 movel
1407 * 2-movel 和 movej
1408 * 3-movel 和 movel
1409 * @param q_start 交融前路径的起点
1410 * @param q_via 交融点
1411 * @param q_to 交融后路径的终点
1412 * @param r 在q_via处的交融半径
1413 * @param d 采样距离
1414 * @return q_via处的交融段笛卡尔空间离散轨迹点(x,y,z)集合
1415 *
1416 * @throws arcs::common_interface::AuboException
1417 *
1418 * @par Python函数原型
1419 * pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1:
1420 * List[float], arg2: List[float], arg3: List[float], arg4: float, arg5:
1421 * float) -> List[List[float]]
1422 *
1423 * @par Lua函数原型
1424 * pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table,
1425 * r: number, d: number) -> table, number
1426 *
1427 * @par Lua示例
1428 * q_via , num = pathBlend3Points(1,{0.58815,0.0532,0.62391,2.46,0.479,1.619},{0.0,-0.2618,1.7453,0.4364,1.5711,0.0},
1429 * {0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.25,0.02)
1430 *
1431 * \endchinese
1432 * \english
1433 * Solve the blended trajectory points
1434 *
1435 * @param type
1436 * 0-movej and movej
1437 * 1-movej and movel
1438 * 2-movel and movej
1439 * 3-movel and movel
1440 * @param q_start Start point before blending
1441 * @param q_via Blending point
1442 * @param q_to End point after blending
1443 * @param r Blend radius at q_via
1444 * @param d Sampling distance
1445 * @return Discrete trajectory points (x, y, z) of the blend segment at q_via in Cartesian space
1446 *
1447 * @throws arcs::common_interface::AuboException
1448 *
1449 * @par Python function prototype
1450 * pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1:
1451 * List[float], arg2: List[float], arg3: List[float], arg4: float, arg5:
1452 * float) -> List[List[float]]
1453 *
1454 * @par Lua function prototype
1455 * pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table,
1456 * r: number, d: number) -> table, number
1457 *
1458 * @par Lua example
1459 * q_via , num = pathBlend3Points(1,{0.58815,0.0532,0.62391,2.46,0.479,1.619},{0.0,-0.2618,1.7453,0.4364,1.5711,0.0},
1460 * {0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.25,0.02)
1461 *
1462 * \endenglish
1463 */
1464 std::vector<std::vector<double>> pathBlend3Points(
1465 int type, const std::vector<double> &q_start,
1466 const std::vector<double> &q_via, const std::vector<double> &q_to,
1467 double r, double d);
1468
1469 /**
1470 * @ingroup RobotAlgorithm
1471 * \chinese
1472 * 生成用于负载辨识的激励轨迹
1473 * 此接口内部调用pathBufferAppend
1474 * 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
1475 * @param name 轨迹名字
1476 * @param traj_conf 各关节轨迹的限制条件
1477 * traj_conf.move_axis: 运动的轴
1478 * 由于实际用户现场可能不希望在负载辨识时控制机械臂多关节大幅度运动,故最好选用traj_conf.move_axis=LoadIdentifyMoveAxis::Joint_4_6;
1479 * traj_conf.init_joint:
1480 * 运动初始关节角,为了避免关节5接近零位时的奇异问题,应设置traj_conf.init_joint[4]的绝对值不小于0.3(rad),接近1.57(rad)为宜。其余关节的关节角可任意设置
1481 * traj_conf.lower_joint_bound, traj_conf.upper_joint_bound:
1482 * 关节角上下限,维度应与config.move_axis维度保持一致,推荐设置upper_joint_bound为2,lower_joint_bound为-2
1483 * config.max_velocity, config.max_acceleration:
1484 * 关节角速度角加速度限制,维度应与config.move_axis维度保持一致,出于安全和驱动器跟随性能的考虑,推荐设置max_velocity=3,max_acceleration=5
1485 *
1486 * @return 成功返回0;失败返回错误码
1487 * AUBO_BUSY
1488 * AUBO_BAD_STATE
1489 * -AUBO_INVL_ARGUMENT
1490 * -AUBO_BAD_STATE
1491 *
1492 * @throws arcs::common_interface::AuboException
1493 * \endchinese
1494 * \english
1495 * Generate excitation trajectory for payload identification
1496 * This interface internally calls pathBufferAppend
1497 * The offline trajectory is stored in the buffer, and can be executed later via movePathBuffer
1498 * @param name Trajectory name
1499 * @param traj_conf Joint trajectory constraints
1500 * traj_conf.move_axis: Moving axes
1501 * Since users may not want large multi-joint movements during payload identification, it is recommended to use traj_conf.move_axis=LoadIdentifyMoveAxis::Joint_4_6;
1502 * traj_conf.init_joint:
1503 * Initial joint angles. To avoid singularity issues near joint 5 zero position, set abs(traj_conf.init_joint[4]) >= 0.3(rad), preferably close to 1.57(rad). Other joints can be set arbitrarily.
1504 * traj_conf.lower_joint_bound, traj_conf.upper_joint_bound:
1505 * Joint angle limits, dimensions should match config.move_axis. Recommended: upper_joint_bound=2, lower_joint_bound=-2
1506 * config.max_velocity, config.max_acceleration:
1507 * Joint velocity and acceleration limits, dimensions should match config.move_axis. For safety and driver performance, recommended: max_velocity=3, max_acceleration=5
1508 *
1509 * @return Returns 0 on success; error code on failure
1510 * AUBO_BUSY
1511 * AUBO_BAD_STATE
1512 * -AUBO_INVL_ARGUMENT
1513 * -AUBO_BAD_STATE
1514 *
1515 * @throws arcs::common_interface::AuboException
1516 * \endenglish
1517 */
1518 int generatePayloadIdentifyTraj(const std::string &name,
1519 const TrajConfig &traj_conf);
1520 /**
1521 * @ingroup RobotAlgorithm
1522 * \chinese
1523 * 负载辨识轨迹是否生成完成
1524 *
1525 * @return 完成返回0; 正在进行中返回1; 计算失败返回<0;
1526 *
1527 * @throws arcs::common_interface::AuboException
1528 *
1529 * @par JSON-RPC请求示例
1530 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
1531 *
1532 * @par JSON-RPC响应示例
1533 * {"id":1,"jsonrpc":"2.0","result":0}
1534 *
1535 * \endchinese
1536 * \english
1537 * Whether payload identification trajectory generation is finished
1538 *
1539 * @return 0 if finished; 1 if in progress; <0 if failed;
1540 *
1541 * @throws arcs::common_interface::AuboException
1542 *
1543 * @par JSON-RPC request example
1544 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
1545 *
1546 * @par JSON-RPC response example
1547 * {"id":1,"jsonrpc":"2.0","result":0}
1548 *
1549 * \endenglish
1550 */
1552
1553 /**
1554 * @ingroup RobotAlgorithm
1555 * \chinese
1556 * 求解 moveS 的轨迹点
1557 *
1558 * @brief pathMoveS
1559 * @param qs 样条轨迹生成点集合
1560 * @param d 采样距离
1561 * @return
1562 *
1563 * @throws arcs::common_interface::AuboException
1564 * \endchinese
1565 * \english
1566 * Solve the trajectory points for moveS
1567 *
1568 * @brief pathMoveS
1569 * @param qs Spline trajectory generation point set
1570 * @param d Sampling distance
1571 * @return
1572 *
1573 * @throws arcs::common_interface::AuboException
1574 * \endenglish
1575 */
1576 std::vector<std::vector<double>> pathMoveS(
1577 const std::vector<std::vector<double>> &qs, double d);
1578
1579 /**
1580 * @ingroup RobotAlgorithm
1581 * \chinese
1582 * 振动抑制参数辨识算法接口
1583 *
1584 * @param q 当前关节角度
1585 * @param qd 当前关节速度
1586 * @param target_q 目标关节角度
1587 * @param target_qd 关节速度
1588 * @param target_qdd 关节加速度
1589 * @param tool_offset 工具TCP信息
1590 * @param omega 振动频率
1591 * @param zeta 振动阻尼比
1592 * @return 振动抑制参数和是否辨识成功
1593 *
1594 * @throws arcs::common_interface::AuboException
1595 *
1596 * @par Python函数原型
1597 * calibVibrationParams(self: pyaubo_sdk.RobotAlgorithm, arg0:
1598 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]], arg3: List[List[float]],
1599 * arg4: List[List[float]], arg5: List[float]) -> list[list[float]],int
1600 *
1601 * @par Lua函数原型
1602 * calibVibrationParams(q: table,qd: table, target_q: table, target_qd: table,
1603 * target_qdd: table, tool_offset: table, omega: table, zeta: table) -> table,number
1604 * \endchinese
1605 */
1606 ResultWithErrno1 calibVibrationParams(const std::vector<std::vector<double>> &q,
1607 const std::vector<std::vector<double>> &qd,
1608 const std::vector<std::vector<double>> &target_q,
1609 const std::vector<std::vector<double>> &target_qd,
1610 const std::vector<std::vector<double>> &target_qdd,
1611 const std::vector<double> &tool_offset);
1612
1613 /**
1614 * @ingroup RobotAlgorithm
1615 * \chinese
1616 * 振动抑制参数辨识算法接口1
1617 *
1618 * @param record_cache_name 目标缓存名称
1619 * @param tool_offset 工具TCP信息
1620 * @return 振动抑制参数和是否辨识成功
1621 *
1622 * @throws arcs::common_interface::AuboException
1623 *
1624 * @par Python函数原型
1625 * calibVibrationParams(self: pyaubo_sdk.RobotAlgorithm, arg0:
1626 * string, arg1: List[float]) -> list[list[float]],int
1627 *
1628 * @par Lua函数原型
1629 * calibVibrationParams(record_cache_name: string, tool_offset: table) -> table,number
1630 * \endchinese
1631 */
1632 ResultWithErrno1 calibVibrationParams1(const std::string &record_cache_name, const std::vector<double> &tool_offset);
1633
1634 /**
1635 * @ingroup RobotAlgorithm
1636 * \chinese
1637 * 判断是否需要重新辨识振动参数
1638 *
1639 * @param param1 参考参数(如上一次辨识结果)
1640 * @param param2 当前参数(如新测量结果)
1641 * @param threshold 变化阈值(0~1),超过则需重新辨识
1642 * @return >0 需要重新辨识,=0 不需要,<0 出错
1643 *
1644 * @par Lua函数原型
1645 * needVibrationRecalib(param1: table, param2: table, threshold: number) -> number
1646 *
1647 * @par JSON-RPC示例
1648 * {"jsonrpc":"2.0","method":"VibrationController.needVibrationRecalib",
1649 * "params":[param1_obj, param2_obj, 0.1],"id":1}
1650 * \endchinese
1651 */
1653 const VibrationRecalibrationParameter &param2,
1654 double threshold);
1655
1656 /**
1657 * @ingroup RobotAlgorithm
1658 * \chinese
1659 * 添加立方体碰撞对象
1660 *
1661 * 该接口用于向当前机器人算法场景中添加一个命名的立方体碰撞对象组。
1662 *
1663 * @param name 碰撞对象唯一标识
1664 * @param link_name 碰撞对象挂载的参考 link 名称。常用名称包括:
1665 * `world`、`base_link`、`shoulder_Link`、`upperArm_Link`、
1666 * `foreArm_Link`、`wrist1_Link`、`wrist2_Link`、`wrist3_Link`、
1667 * `end_effector`
1668 * @param sizes 立方体尺寸列表。每个元素格式为
1669 * `[length, width, height]`,单位:m
1670 * @param poses 碰撞对象位姿列表。每个元素表示相对参考 link 的位姿,
1671 * 格式为 `[x, y, z, rx, ry, rz]`
1672 * @return 0 表示成功,非 0 表示失败
1673 *
1674 * @par Lua函数原型
1675 * addCollisionBox(name, link_name, sizes, poses) -> integer
1676 *
1677 * @par Lua示例
1678 * -- 添加挂载到 world 的环境碰撞体
1679 * addCollisionBox("env_box", "world",
1680 * {{0.4, 0.4, 0.2}},
1681 * {{0.6, 0.0, 0.1, 0.0, 0.0, 0.0}})
1682 *
1683 * -- 添加挂载到 end_effector 的末端碰撞体
1684 * addCollisionBox("tool_box", "end_effector",
1685 * {{0.1, 0.08, 0.06}},
1686 * {{0.0, 0.0, 0.05, 0.0, 0.0, 0.0}})
1687 *
1688 * @par Python函数原型
1689 * addCollisionBox(name: str, link_name: str, sizes: list[list[float]],
1690 * poses: list[list[float]]) -> int
1691 *
1692 * @par Python示例
1693 * # 添加挂载到 world 的环境碰撞体
1694 * robot_algorithm.addCollisionBox(
1695 * "env_box", "world",
1696 * [[0.4, 0.4, 0.2]],
1697 * [[0.6, 0.0, 0.1, 0.0, 0.0, 0.0]]
1698 * )
1699 *
1700 * # 添加挂载到 end_effector 的末端碰撞体
1701 * robot_algorithm.addCollisionBox(
1702 * "tool_box", "end_effector",
1703 * [[0.1, 0.08, 0.06]],
1704 * [[0.0, 0.0, 0.05, 0.0, 0.0, 0.0]]
1705 * )
1706 *
1707 * @par JSON-RPC请求示例
1708 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.addCollisionBox",
1709 * "params":["env_box","world",[[0.4,0.4,0.2]],
1710 * [[0.6,0.0,0.1,0.0,0.0,0.0]]],"id":1}
1711 *
1712 * @par JSON-RPC响应示例
1713 * {"id":1,"jsonrpc":"2.0","result":0}
1714 * \endchinese
1715 *
1716 * \english
1717 * Add a box collision object
1718 *
1719 * This interface adds a named group of box collision objects into the
1720 * current robot algorithm scene.
1721 *
1722 * @param name Unique identifier of the collision object
1723 * @param link_name Name of the reference link the collision object is
1724 * attached to. Common names include: `world`, `base_link`,
1725 * `shoulder_Link`, `upperArm_Link`, `foreArm_Link`, `wrist1_Link`,
1726 * `wrist2_Link`, `wrist3_Link`, and `end_effector`
1727 * @param sizes List of box sizes. Each element is in the format
1728 * `[length, width, height]`, unit: m
1729 * @param poses List of collision object poses. Each element is a pose
1730 * relative to the reference link in the format `[x, y, z, rx, ry, rz]`
1731 * @return 0 on success, non-zero on failure
1732 *
1733 * @par Lua function prototype
1734 * addCollisionBox(name, link_name, sizes, poses) -> integer
1735 *
1736 * @par Lua example
1737 * -- Add an environment collision box attached to world
1738 * addCollisionBox("env_box", "world",
1739 * {{0.4, 0.4, 0.2}},
1740 * {{0.6, 0.0, 0.1, 0.0, 0.0, 0.0}})
1741 *
1742 * -- Add a tool collision box attached to end_effector
1743 * addCollisionBox("tool_box", "end_effector",
1744 * {{0.1, 0.08, 0.06}},
1745 * {{0.0, 0.0, 0.05, 0.0, 0.0, 0.0}})
1746 *
1747 * @par Python function prototype
1748 * addCollisionBox(name: str, link_name: str, sizes: list[list[float]],
1749 * poses: list[list[float]]) -> int
1750 *
1751 * @par Python example
1752 * # Add an environment collision box attached to world
1753 * robot_algorithm.addCollisionBox(
1754 * "env_box", "world",
1755 * [[0.4, 0.4, 0.2]],
1756 * [[0.6, 0.0, 0.1, 0.0, 0.0, 0.0]]
1757 * )
1758 *
1759 * # Add a tool collision box attached to end_effector
1760 * robot_algorithm.addCollisionBox(
1761 * "tool_box", "end_effector",
1762 * [[0.1, 0.08, 0.06]],
1763 * [[0.0, 0.0, 0.05, 0.0, 0.0, 0.0]]
1764 * )
1765 *
1766 * @par JSON-RPC request example
1767 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.addCollisionBox",
1768 * "params":["env_box","world",[[0.4,0.4,0.2]],
1769 * [[0.6,0.0,0.1,0.0,0.0,0.0]]],"id":1}
1770 *
1771 * @par JSON-RPC response example
1772 * {"id":1,"jsonrpc":"2.0","result":0}
1773 * \endenglish
1774 */
1775 int addCollisionBox(const std::string &name,
1776 const std::string &link_name,
1777 const std::vector<std::vector<double>> &sizes,
1778 const std::vector<std::vector<double>> &poses);
1779
1780 /**
1781 * @ingroup RobotAlgorithm
1782 * \chinese
1783 * 删除指定的碰撞对象
1784 *
1785 * @param name 需要删除的碰撞对象名称
1786 * @return 0 表示成功,非 0 表示失败
1787 *
1788 * @par Lua函数原型
1789 * removeCollisionObject(name) -> integer
1790 *
1791 * @par Lua示例
1792 * removeCollisionObject("tool_box")
1793 *
1794 * @par Python函数原型
1795 * removeCollisionObject(name: str) -> int
1796 *
1797 * @par Python示例
1798 * robot_algorithm.removeCollisionObject("tool_box")
1799 *
1800 * @par JSON-RPC请求示例
1801 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.removeCollisionObject",
1802 * "params":["tool_box"],"id":1}
1803 *
1804 * @par JSON-RPC响应示例
1805 * {"id":1,"jsonrpc":"2.0","result":0}
1806 * \endchinese
1807 *
1808 * \english
1809 * Remove a collision object by name
1810 *
1811 * @param name Name of the collision object to remove
1812 * @return 0 on success, non-zero on failure
1813 *
1814 * @par Lua function prototype
1815 * removeCollisionObject(name) -> integer
1816 *
1817 * @par Lua example
1818 * removeCollisionObject("tool_box")
1819 *
1820 * @par Python function prototype
1821 * removeCollisionObject(name: str) -> int
1822 *
1823 * @par Python example
1824 * robot_algorithm.removeCollisionObject("tool_box")
1825 *
1826 * @par JSON-RPC request example
1827 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.removeCollisionObject",
1828 * "params":["tool_box"],"id":1}
1829 *
1830 * @par JSON-RPC response example
1831 * {"id":1,"jsonrpc":"2.0","result":0}
1832 * \endenglish
1833 */
1834 int removeCollisionObject(const std::string &name);
1835
1836 /**
1837 * @ingroup RobotAlgorithm
1838 * \chinese
1839 * 验证机器人运动路径从起点到终点的可达性,不启用外部碰撞检测。
1840 *
1841 * 该接口保留用于兼容旧版 SDK、Lua、JSON-RPC 和 ROS 服务调用。
1842 *
1843 * @param type 路径类型标识,用于指定起点和终点的数据类型:
1844 * 0 - 起点:关节角,终点:关节角
1845 * 1 - 起点:位姿,终点:位姿
1846 * @param start 路径起点数据
1847 * @param r1 起点交融半径,单位:m(米)
1848 * @param end 路径终点数据
1849 * @param r2 终点交融半径,单位:m(米)
1850 * @param d 路径采样间隔,单位:m(米),间隔越小验证精度越高,但耗时越长
1851 * @return 路径可达性结果码
1852 *
1853 * \endchinese
1854 *
1855 * \english
1856 * Validate the reachability of the robot's motion path from start point to
1857 * end point without external collision checks.
1858 *
1859 * This interface is kept for compatibility with existing SDK, Lua,
1860 * JSON-RPC, and ROS service calls.
1861 *
1862 * @param type Path type identifier, used to specify the data types of
1863 * start and end:
1864 * 0 - Start: Joint angles, End: Joint angles
1865 * 1 - Start: Pose, End: Pose
1866 * @param start Start point data of the path
1867 * @param r1 Start point blending radius, unit: m (meters)
1868 * @param end End point data of the path
1869 * @param r2 End point blending radius, unit: m (meters)
1870 * @param d Path sampling interval, unit: m (meters). A smaller interval
1871 * improves validation accuracy but takes more time.
1872 * @return Path reachability result code
1873 *
1874 * \endenglish
1875 */
1876 int validatePath(int type, const std::vector<double> &start, double r1,
1877 const std::vector<double> &end, double r2, double d);
1878
1879 /**
1880 * @ingroup RobotAlgorithm
1881 * \chinese
1882 * 验证机器人运动路径从起点到终点的可达性,可选择是否启用外部碰撞检测。
1883 *
1884 * 该接口通过采样的方式验证指定路径是否存在超限、自碰撞、外部碰撞、
1885 * 奇异等不可达情况,支持关节角<->关节角、位姿<->位姿两种路径类型验证。
1886 *
1887 * @param type 路径类型标识,用于指定起点和终点的数据类型:
1888 * 0 - 起点:关节角,终点:关节角
1889 * 1 - 起点:位姿,终点:位姿
1890 * @param start 路径起点数据
1891 * @param r1 起点交融半径,单位:m(米)
1892 * @param end 路径终点数据
1893 * @param r2 终点交融半径,单位:m(米)
1894 * @param d 路径采样间隔,单位:m(米),间隔越小验证精度越高,但耗时越长
1895 * @param check_external_collision 是否启用外部碰撞检测:
1896 * false - 保持原有路径可达性与自碰撞校验
1897 * true - 在原有校验基础上增加与外部对象的碰撞检测
1898 * @return 路径可达性结果码:
1899 * 0 - 可达:路径无异常,可正常运动
1900 * -18 - 路径中存在关节超限/笛卡尔空间超限
1901 * -21 - 轨迹生成失败
1902 * -22 - 路径中机器人本体发生自碰撞
1903 * -24 - 路径中经过机器人奇异位形
1904 * -27 - 目标点有解但超出关节限位
1905 *
1906 * @throws arcs::common_interface::AuboException
1907 *
1908 * @par Lua函数原型
1909 * validatePath1(type, start, r1, end, r2, d, check_external_collision) -> number
1910 *
1911 * @par Lua示例
1912 * local result =
1913 * validatePath1(0, start_joint, 0.01, end_joint, 0.01, 0.05, true)
1914 *
1915 * @par Python函数原型
1916 * validatePath1(type: int, start: list[float], r1: float, end: list[float],
1917 * r2: float, d: float, check_external_collision: bool) -> int
1918 *
1919 * @par Python示例
1920 * result = validatePath1(1, start_joint, 0.01, end_pose, 0.01, 0.05, True)
1921 *
1922 * @par JSON-RPC请求示例
1923 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.validatePath1","params":[0,
1924 * [0.0,0.0,1.57,0.0,1.57,0.0], 0.01, [0.52,0.0,1.57,0.0,1.57,0.0], 0.01,
1925 * 0.05, true],"id":1}
1926 *
1927 * @par JSON-RPC响应示例
1928 * {"id":1,"jsonrpc":"2.0","result":0}
1929 * \endchinese
1930 *
1931 * \english
1932 * Validate the reachability of the robot's motion path from start point to
1933 * end point, with optional external collision checks.
1934 *
1935 * This interface verifies whether the specified path has unreachable
1936 * conditions such as out-of-limit, self-collision, collision with external
1937 * objects, singularity, etc., by sampling. It supports two path type
1938 * validations: Joint-Joint and Pose-Pose.
1939 *
1940 * @param type Path type identifier, used to specify the data types of
1941 * start and end:
1942 * 0 - Start: Joint angles, End: Joint angles
1943 * 1 - Start: Pose, End: Pose
1944 * @param start Start point data of the path
1945 * @param r1 Start point blending radius, unit: m (meters)
1946 * @param end End point data of the path
1947 * @param r2 End point blending radius, unit: m (meters)
1948 * @param d Path sampling interval, unit: m (meters). A smaller interval
1949 * improves validation accuracy but takes more time.
1950 * @param check_external_collision Whether to enable external collision
1951 * checks:
1952 * false - Keep the original reachability and self-collision checks
1953 * true - Add collision checks against external objects
1954 *
1955 * @return Path reachability result code:
1956 * 0 - Reachable: Path is normal, movement is possible
1957 * -18 - Joint/Cartesian space limits exceeded in the path
1958 * -21 - Trajectory generation failed
1959 * -22 - Self-collision of the robot body in the path
1960 * -24 - Path passing through robot singular configuration
1961 * -27 - The target point has a solution but exceeds joint limits
1962 *
1963 * @throws arcs::common_interface::AuboException Thrown when parameters are
1964 * invalid.
1965 *
1966 * @par Lua function prototype
1967 * validatePath1(type, start, r1, end, r2, d, check_external_collision) -> integer
1968 *
1969 * @par Lua example
1970 * result = validatePath1(0, start_joint, 0.01, end_joint, 0.01, 0.05, true)
1971 *
1972 * @par Python function prototype
1973 * validatePath1(type: int, start: list[float], r1: float, end: list[float],
1974 * r2: float, d: float, check_external_collision: bool) -> int
1975 *
1976 * @par Python example
1977 * result = validatePath1(1, start_joint, 0.01, end_pose, 0.01, 0.005, True)
1978 *
1979 * @par JSON-RPC request example
1980 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.validatePath1","params":[0,
1981 * [0.0,0.0,1.57,0.0,1.57,0.0], 0.01, [0.52,0.0,1.57,0.0,1.57,0.0], 0.01,
1982 * 0.005, true],"id":1}
1983 *
1984 * @par JSON-RPC response example {"id":1,"jsonrpc":"2.0","result":0}
1985 * \endenglish
1986 */
1987 int validatePath1(int type, const std::vector<double> &start, double r1,
1988 const std::vector<double> &end, double r2, double d,
1989 bool check_external_collision);
1990
1991protected:
1992 void *d_;
1993};
1994using RobotAlgorithmPtr = std::shared_ptr<RobotAlgorithm>;
1995
1996} // namespace common_interface
1997} // namespace arcs
1998
1999#endif // AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
std::vector< std::vector< double > > pathMovej(const std::vector< double > &q1, double r1, const std::vector< double > &q2, double r2, double d)
求解movej之间的轨迹点
ResultWithErrno forwardDynamics1(const std::vector< double > &q, const std::vector< double > &torqs, const std::vector< double > &tcp_offset)
动力学正解,基于给定的TCP偏移
ResultWithErrno calibrateTcpForceSensor3(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses, const double &mass, const std::vector< double > &cog)
力传感器偏置标定算法
ResultWithErrno forwardKinematics1(const std::vector< double > &q, const std::vector< double > &tcp_offset)
运动学正解 输入关节角度,输出TCP位姿
ResultWithErrno forwardToolKinematics(const std::vector< double > &q)
运动学正解(忽略 TCP 偏移值)
ResultWithErrno1 calibVibrationParams1(const std::string &record_cache_name, const std::vector< double > &tool_offset)
振动抑制参数辨识算法接口1
std::vector< std::vector< double > > pathBlend3Points(int type, const std::vector< double > &q_start, const std::vector< double > &q_via, const std::vector< double > &q_to, double r, double d)
求解交融的轨迹点
ResultWithErrno calibWorkpieceCoordinatePara(const std::vector< std::vector< double > > &q, int type)
工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移) 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
bool frictionModelIdentify(const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &qdd, const std::vector< std::vector< double > > &temp)
关节摩擦力模型辨识算法接口
int removeCollisionObject(const std::string &name)
删除指定的碰撞对象
int payloadIdentify1(const std::string &file_name)
新版基于电流的负载辨识算法接口
ResultWithErrno inverseKinematics1(const std::vector< double > &qnear, const std::vector< double > &pose, const std::vector< double > &tcp_offset)
运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
int validatePath(int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d)
验证机器人运动路径从起点到终点的可达性,不启用外部碰撞检测。
int payloadCalculateFinished()
负载辨识是否计算完成
int needVibrationRecalib(const VibrationRecalibrationParameter &param1, const VibrationRecalibrationParameter &param2, double threshold)
判断是否需要重新辨识振动参数
Payload getPayloadIdentifyResult()
获取负载辨识结果
ResultWithErrno forwardDynamics(const std::vector< double > &q, const std::vector< double > &torqs)
动力学正解
ResultWithErrno1 inverseKinematicsAll1(const std::vector< double > &pose, const std::vector< double > &tcp_offset)
求出所有的逆解, 基于提供的 TCP 偏移
ResultWithErrno inverseToolKinematics(const std::vector< double > &qnear, const std::vector< double > &pose)
运动学逆解(忽略 TCP 偏移值)
std::vector< std::vector< double > > pathMoveS(const std::vector< std::vector< double > > &qs, double d)
求解 moveS 的轨迹点
ResultWithErrno calcJacobian(const std::vector< double > &q, bool base_or_end)
计算机械臂末端的雅克比矩阵
int payloadIdentify(const std::string &data_file_no_payload, const std::string &data_file_with_payload)
基于电流的负载辨识算法接口
ResultWithErrno1 inverseKinematicsAll(const std::vector< double > &pose)
求出所有的逆解, 基于激活的 TCP 偏移
ResultWithErrno1 inverseToolKinematicsAll(const std::vector< double > &pose)
运动学逆解(忽略 TCP 偏移值)
ResultWithErrno forwardKinematics(const std::vector< double > &q)
运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出TCP位姿
ForceSensorCalibResult calibrateTcpForceSensor(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
力传感器标定算法(三点标定法)
int validatePath1(int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d, bool check_external_collision)
验证机器人运动路径从起点到终点的可达性,可选择是否启用外部碰撞检测。
ResultWithErrno inverseKinematics2(const std::vector< double > &qnear, const std::vector< double > &pose)
同构型最小关节变化逆解 按照 qnear 的机械臂构型计算目标 TCP 位姿逆解,并在同构型逆解中选择相对 qnear 关节变化最小的一组 基于激活的 TCP 偏移(最近的通过 setTcpOffset...
int payloadIdentifyTrajGenFinished()
负载辨识轨迹是否生成完成
ResultWithErrno inverseKinematics(const std::vector< double > &qnear, const std::vector< double > &pose)
运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
int generatePayloadIdentifyTraj(const std::string &name, const TrajConfig &traj_conf)
生成用于负载辨识的激励轨迹 此接口内部调用pathBufferAppend 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
ResultWithErrno1 calibVibrationParams(const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &target_q, const std::vector< std::vector< double > > &target_qd, const std::vector< std::vector< double > > &target_qdd, const std::vector< double > &tool_offset)
振动抑制参数辨识算法接口
ForceSensorCalibResultWithError calibrateTcpForceSensor2(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
力传感器标定算法(三点标定法)
int addCollisionBox(const std::string &name, const std::string &link_name, const std::vector< std::vector< double > > &sizes, const std::vector< std::vector< double > > &poses)
添加立方体碰撞对象
ResultWithErrno3 getRobotConfiguration(const std::vector< double > &q)
根据输入的关节角计算并返回对应的机械臂构型
ResultWithErrno1 forwardKinematicsAll(const std::vector< double > &q)
运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出各连杆位姿
std::tuple< std::vector< std::vector< double > >, int > ResultWithErrno1
std::tuple< double, std::vector< double >, std::vector< double >, std::vector< double > > Payload
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double >, double > ForceSensorCalibResultWithError
std::tuple< int, int > ResultWithErrno3
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double > > ForceSensorCalibResult
std::tuple< std::vector< double >, int > ResultWithErrno
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
用于负载辨识的轨迹配置
数据类型的定义