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