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 * 机器人算法相关的对外接口
23 * \endchinese
24 * \english
25 * Interfaces related to robot algorithms
26 * \endenglish
27 */
28
29class ARCS_ABI_EXPORT RobotAlgorithm
30{
31public:
33 virtual ~RobotAlgorithm();
34
35 /**
36 * \chinese
37 * 力传感器标定算法(三点标定法)
38 *
39 * @param force 力数据
40 * @param q 关节角度
41 * @return 标定结果
42 *
43 * @throws arcs::common_interface::AuboException
44 *
45 * @par Python函数原型
46 * calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0:
47 * List[List[float]], arg1: List[List[float]]) -> Tuple[List[float],
48 * List[float], float, List[float]]
49 *
50 * @par Lua函数原型
51 * calibrateTcpForceSensor(force: table, q: table) -> table
52 *
53 * @par Lua示例
54 * 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})
55 *
56 * \endchinese
57 * \english
58 * Force sensor calibration algorithm (three-point calibration method)
59 *
60 * @param force Force data
61 * @param q Joint angles
62 * @return Calibration result
63 *
64 * @throws arcs::common_interface::AuboException
65 *
66 * @par Python function prototype
67 * calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0:
68 * List[List[float]], arg1: List[List[float]]) -> Tuple[List[float],
69 * List[float], float, List[float]]
70 *
71 * @par Lua function prototype
72 * calibrateTcpForceSensor(force: table, q: table) -> table
73 *
74 * @par Lua example
75 * 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})
76 *
77 * \endenglish
78 */
80 const std::vector<std::vector<double>> &forces,
81 const std::vector<std::vector<double>> &poses);
82
83 /**
84 * \chinese
85 * 力传感器标定算法(三点标定法)
86 * @param forces
87 * @param poses
88 * @return force_offset, com, mass, angle error
89 *
90 * @throws arcs::common_interface::AuboException
91 * \endchinese
92 * \english
93 * Force sensor calibration algorithm (three-point calibration method)
94 * @param forces
95 * @param poses
96 * @return force_offset, com, mass, angle error
97 *
98 * @throws arcs::common_interface::AuboException
99 * \endenglish
100 */
102 const std::vector<std::vector<double>> &forces,
103 const std::vector<std::vector<double>> &poses);
104
105 /**
106 * \chinese
107 * 力传感器偏置标定算法
108 *
109 * @param force 力数据
110 * @param poses 位姿
111 * @param mass 质量, 单位: kg
112 * @param cog 重心, 单位: m, 形式为(CoGx, CoGy, CoGz)
113 * @return 标定结果
114 *
115 * @throws arcs::common_interface::AuboException
116 * \endchinese
117 * \english
118 * Force sensor offset calibration algorithm
119 *
120 * @param forces Force data
121 * @param poses
122 * @param m Mass, unit: kg
123 * @param cog Center of gravity, unit: m, format (CoGx, CoGy, CoGz)
124 * @return Calibration result
125 *
126 * @throws arcs::common_interface::AuboException
127 * \endenglish
128 */
130 const std::vector<std::vector<double>> &forces,
131 const std::vector<std::vector<double>> &poses, const double &mass,
132 const std::vector<double>&cog);
133
134 /**
135 * \chinese
136 * 基于电流的负载辨识算法接口
137 *
138 * 需要采集空载时运行激励轨迹的位置、速度、电流以及带负载时运行激励轨迹的位置、速度、电流
139 *
140 * @param data_file_no_payload
141 * 空载时运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
142 * @param data_file_with_payload
143 * 带负载运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
144 * @return 辨识的结果
145 *
146 * @throws arcs::common_interface::AuboException
147 *
148 * @par Python函数原型
149 * payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]],
150 * arg1: List[List[float]]) -> Tuple[List[float], List[float], float,
151 * List[float]]
152 *
153 * @par Lua函数原型
154 * payloadIdentify(data_with_payload: table, data_with_payload: table) ->
155 * table
156 * \endchinese
157 * \english
158 * Payload identification algorithm interface based on current
159 *
160 * Requires collecting position, velocity, and current data when running the excitation trajectory without load, as well as with load.
161 *
162 * @param data_file_no_payload
163 * 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
164 * @param data_file_with_payload
165 * 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
166 * @return Identification result
167 *
168 * @throws arcs::common_interface::AuboException
169 *
170 * @par Python function prototype
171 * payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]],
172 * arg1: List[List[float]]) -> Tuple[List[float], List[float], float,
173 * List[float]]
174 *
175 * @par Lua function prototype
176 * payloadIdentify(data_with_payload: table, data_with_payload: table) ->
177 * table
178 * \endenglish
179 */
180 int payloadIdentify(const std::string &data_file_no_payload,
181 const std::string &data_file_with_payload);
182
183 /**
184 * \chinese
185 * 新版基于电流的负载辨识算法接口
186 *
187 * 需要采集带载时运行最少三个点的位置、速度、加速度、电流、温度、末端传感器数据、底座数据
188 *
189 * @param data
190 * 带负载的各关节数据的文件路径(.csv格式),共42列,末端传感器数据、底座数据默认为0
191 * @return 辨识的结果
192 * \endchinese
193 * \english
194 * New version of payload identification algorithm interface based on current
195 *
196 * Requires collecting at least three points of position, velocity, acceleration, current, temperature, end sensor data, and base data when running with load
197 *
198 * @param data
199 * File path of joint data with load (.csv format), 42 columns in total, end sensor data and base data default to 0
200 * @return Identification result
201 * \endenglish
202 */
203 int payloadIdentify1(const std::string &file_name);
204
205 /**
206 * \chinese
207 * 负载辨识是否计算完成
208 * @return 完成返回0; 正在进行中返回1; 计算失败返回<0;
209 *
210 * @throws arcs::common_interface::AuboException
211 *
212 * @par JSON-RPC请求示例
213 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
214 *
215 * @par JSON-RPC响应示例
216 * {"id":1,"jsonrpc":"2.0","result":0}
217 *
218 * \endchinese
219 * \english
220 * Whether payload identification calculation is finished
221 * @return 0 if finished; 1 if in progress; <0 if failed;
222 *
223 * @throws arcs::common_interface::AuboException
224 *
225 * @par JSON-RPC request example
226 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
227 *
228 * @par JSON-RPC response example
229 * {"id":1,"jsonrpc":"2.0","result":0}
230 *
231 * \endenglish
232 */
234
235 /**
236 * \chinese
237 * 获取负载辨识结果
238 * @return
239 *
240 * @throws arcs::common_interface::AuboException
241 *
242 * @par JSON-RPC请求示例
243 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
244 *
245 * @par JSON-RPC响应示例
246 * {"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}
247 *
248 * \endchinese
249 * \english
250 * Get the result of payload identification
251 * @return
252 *
253 * @throws arcs::common_interface::AuboException
254 *
255 * @par JSON-RPC request example
256 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
257 *
258 * @par JSON-RPC response example
259 * {"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}
260 *
261 * \endenglish
262 */
264
265 /**
266 * \chinese
267 * 关节摩擦力模型辨识算法接口
268 *
269 * @param q 关节角度
270 * @param qd 关节速度
271 * @param qdd 关节加速度
272 * @param temp 关节温度
273 * @return 是否辨识成功
274 *
275 * @throws arcs::common_interface::AuboException
276 *
277 * @par Python函数原型
278 * frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0:
279 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]],
280 * arg3: List[List[float]]) -> bool
281 *
282 * @par Lua函数原型
283 * frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) ->
284 * boolean
285 *
286 * @par Lua示例
287 * Identify_result = frictionModelIdentify({3.083,1.227,1.098,0.670,-1.870,-0.397},
288 * {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})
289 *
290 * \endchinese
291 * \english
292 * Joint friction model identification algorithm interface
293 *
294 * @param q Joint positions
295 * @param qd Joint velocities
296 * @param qdd Joint accelerations
297 * @param temp Joint temperatures
298 * @return Whether identification succeeded
299 *
300 * @throws arcs::common_interface::AuboException
301 *
302 * @par Python function prototype
303 * frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0:
304 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]],
305 * arg3: List[List[float]]) -> bool
306 *
307 * @par Lua function prototype
308 * frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) ->
309 * boolean
310 *
311 * @par Lua example
312 * Identify_result = frictionModelIdentify({3.083,1.227,1.098,0.670,-1.870,-0.397},
313 * {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})
314 *
315 * \endenglish
316 */
317 bool frictionModelIdentify(const std::vector<std::vector<double>> &q,
318 const std::vector<std::vector<double>> &qd,
319 const std::vector<std::vector<double>> &qdd,
320 const std::vector<std::vector<double>> &temp);
321
322 /**
323 * \chinese
324 * 工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移)
325 * 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
326 *
327 * @param q 关节角度
328 * @param type 标定类型
329 * @return 计算结果(工件坐标系位姿)以及错误代码
330 *
331 * @throws arcs::common_interface::AuboException
332 *
333 * @par Python函数原型
334 * calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0:
335 * List[List[float]], arg1: int) -> Tuple[List[float], int]
336 *
337 * @par Lua函数原型
338 * calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
339 *
340 * @par Lua示例
341 * coord_pose,coord_num = calibWorkpieceCoordinatePara({3.083,1.227,1.098,0.670,-1.870,-0.397},1)
342 *
343 * \endchinese
344 * \english
345 * Workpiece coordinate calibration algorithm interface (requires correct TCP offset set before calling)
346 * Input multiple sets of joint angles and calibration type, output workpiece coordinate pose (relative to robot base)
347 *
348 * @param q Joint angles
349 * @param type Calibration type
350 * @return Calculation result (workpiece coordinate pose) and error code
351 *
352 * @throws arcs::common_interface::AuboException
353 *
354 * @par Python function prototype
355 * calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0:
356 * List[List[float]], arg1: int) -> Tuple[List[float], int]
357 *
358 * @par Lua function prototype
359 * calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
360 *
361 * @par Lua example
362 * coord_pose,coord_num = calibWorkpieceCoordinatePara({3.083,1.227,1.098,0.670,-1.870,-0.397},1)
363 *
364 * \endenglish
365 */
367 const std::vector<std::vector<double>> &q, int type);
368
369 /**
370 * \chinese
371 * 动力学正解
372 *
373 * @param q 关节角
374 * @param torqs
375 * @return 计算结果以及错误代码
376 *
377 * @throws arcs::common_interface::AuboException
378 *
379 * @par Python函数原型
380 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
381 * List[float]) -> Tuple[List[float], int]
382 *
383 * @par Lua函数原型
384 * forwardDynamics(q: table, torqs: table) -> table, number
385 *
386 * @par Lua示例
387 * 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})
388 *
389 * \endchinese
390 * \english
391 * Forward dynamics
392 *
393 * @param q Joint angles
394 * @param torqs
395 * @return Calculation result and error code
396 *
397 * @throws arcs::common_interface::AuboException
398 *
399 * @par Python function prototype
400 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
401 * List[float]) -> Tuple[List[float], int]
402 *
403 * @par Lua function prototype
404 * forwardDynamics(q: table, torqs: table) -> table, number
405 *
406 * @par Lua example
407 * 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})
408 *
409 * \endenglish
410 */
411 ResultWithErrno forwardDynamics(const std::vector<double> &q,
412 const std::vector<double> &torqs);
413
414 /**
415 * \chinese
416 * 动力学正解,基于给定的TCP偏移
417 *
418 * @param q 关节角
419 * @param torqs
420 * @param tcp_offset TCP偏移
421 * @return 计算结果以及错误代码,同forwardDynamics
422 *
423 * @throws arcs::common_interface::AuboException
424 *
425 * @par Python函数原型
426 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
427 * List[float], arg2: List[float]) -> Tuple[List[float], int]
428 *
429 * @par Lua函数原型
430 * forwardDynamics1(q: table, torqs: table, tcp_offset: table) -> table, number
431 *
432 * @par Lua示例
433 * 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})
434 *
435 * \endchinese
436 * \english
437 * Forward dynamics based on the given TCP offset
438 *
439 * @param q Joint angles
440 * @param torqs
441 * @param tcp_offset TCP offset
442 * @return Calculation result and error code, same as forwardDynamics
443 *
444 * @throws arcs::common_interface::AuboException
445 *
446 * @par Python function prototype
447 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
448 * List[float], arg2: List[float]) -> Tuple[List[float], int]
449 *
450 * @par Lua function prototype
451 * forwardDynamics1(q: table, torqs: table, tcp_offset: table) -> table, number
452 *
453 * @par Lua example
454 * 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})
455 *
456 * \endenglish
457 */
458 ResultWithErrno forwardDynamics1(const std::vector<double> &q,
459 const std::vector<double> &torqs,
460 const std::vector<double> &tcp_offset);
461
462 /**
463 * \chinese
464 * 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数)
465 * 输入关节角度,输出TCP位姿
466 *
467 * @param q 关节角
468 * @return TCP位姿和正解结果是否有效
469 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
470 * 0 - 成功
471 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
472 * -5 - 输入的关节角无效(维度错误)
473 * @throws arcs::common_interface::AuboException
474 *
475 * @par Python函数原型
476 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
477 * Tuple[List[float], int]
478 *
479 * @par Lua函数原型
480 * forwardKinematics(q: table) -> table, number
481 *
482 * @par Lua示例
483 * pose, fk_result = forwardKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
484 *
485 * @par JSON-RPC请求示例
486 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
487 *
488 * @par JSON-RPC响应示例
489 * {"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
490 * \endchinese
491 * \english
492 * Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset)
493 * Input joint angles, output TCP pose
494 *
495 * @param q Joint angles
496 * @return TCP pose and whether the result is valid
497 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
498 * 0 - Success
499 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
500 * -5 - The input joint angles is invalid (dimension error)
501 * @throws arcs::common_interface::AuboException
502 *
503 * @par Python function prototype
504 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
505 * Tuple[List[float], int]
506 *
507 * @par Lua function prototype
508 * forwardKinematics(q: table) -> table, number
509 *
510 * @par Lua example
511 * pose, fk_result = forwardKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
512 *
513 * @par JSON-RPC request example
514 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
515 *
516 * @par JSON-RPC response example
517 * {"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
518 * \endenglish
519 */
520 ResultWithErrno forwardKinematics(const std::vector<double> &q);
521
522 /**
523 * \chinese
524 * 运动学正解
525 * 输入关节角度,输出TCP位姿
526 * @param q 关节角
527 * @param tcp_offset tcp偏移
528 * @return TCP位姿和正解结果是否有效
529 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
530 * 0 - 成功
531 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
532 * -5 - 输入的关节角或tcp偏移无效(维度错误)
533 * @throws arcs::common_interface::AuboException
534 *
535 * @par Python函数原型
536 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
537 * arg1: List[float]) -> Tuple[List[float], int]
538 *
539 * @par Lua函数原型
540 * forwardKinematics1(q: table, tcp_offset: table) -> table, number
541 *
542 * @par Lua示例
543 * 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})
544 *
545 * @par JSON-RPC请求示例
546 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0,
547 * 0.13201,0.03879,0,0,0]],"id":1}
548 *
549 * @par JSON-RPC响应示例
550 * {"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
551 *
552 * @since 0.24.1
553 * \endchinese
554 * \english
555 * Forward kinematics
556 * Input joint angles, output TCP pose
557 *
558 * @param q Joint angles
559 * @param tcp_offset TCP offset
560 * @return TCP pose and whether the result is valid
561 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
562 * 0 - Success
563 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
564 * -5 - The input joint angles or tcp offset is invalid (dimension error)
565 * @throws arcs::common_interface::AuboException
566 *
567 * @par Python function prototype
568 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
569 * arg1: List[float]) -> Tuple[List[float], int]
570 *
571 * @par Lua function prototype
572 * forwardKinematics1(q: table, tcp_offset: table) -> table, number
573 *
574 * @par Lua example
575 * 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})
576 *
577 * @par JSON-RPC request example
578 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0,
579 * 0.13201,0.03879,0,0,0]],"id":1}
580 *
581 * @par JSON-RPC response example
582 * {"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
583 *
584 * @since 0.24.1
585 * \endenglish
586 */
587 ResultWithErrno forwardKinematics1(const std::vector<double> &q,
588 const std::vector<double> &tcp_offset);
589
590 /**
591 * \chinese
592 * 运动学正解(忽略 TCP 偏移值)
593 *
594 * @param q 关节角
595 * @return 法兰盘中心位姿和正解结果是否有效
596 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
597 * 0 - 成功
598 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
599 * -5 - 输入的关节角无效(维度错误)
600 *
601 * @throws arcs::common_interface::AuboException
602 *
603 * @par Lua函数原型
604 * forwardToolKinematics(q: table) -> table, number
605 *
606 * @par Lua示例
607 * pose, fk_result = forwardToolKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
608 *
609 * @par JSON-RPC请求示例
610 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
611 *
612 * @par JSON-RPC响应示例
613 * {"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
614 * \endchinese
615 * \english
616 * Forward kinematics (ignoring TCP offset)
617 *
618 * @param q Joint angles
619 * @return Flange center pose and whether the result is valid
620 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
621 * 0 - Success
622 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
623 * -5 - The input joint angles is invalid (dimension error)
624 *
625 * @par Lua function prototype
626 * forwardToolKinematics(q: table) -> table, number
627 *
628 * @par Lua example
629 * pose, fk_result = forwardToolKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
630 *
631 * @throws arcs::common_interface::AuboException
632 *
633 * @par JSON-RPC request example
634 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
635 *
636 * @par JSON-RPC response example
637 * {"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
638 * \endenglish
639 */
640 ResultWithErrno forwardToolKinematics(const std::vector<double> &q);
641
642 /**
643 * \chinese
644 * 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数)
645 * 输入关节角度,输出各连杆位姿
646 *
647 * @param q 关节角
648 * @return 各个连杆位姿和正解结果是否有效
649 * 返回值的第一个参数为正解结果,第二个为正解错误码,错误码返回值列表如下
650 * 0 - 成功
651 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
652 * -5 - 输入的关节角无效(维度错误)
653 * @throws arcs::common_interface::AuboException
654 *
655 * @par Python函数原型
656 * forwardKinematicsAll(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
657 * Tuple[List[List[float]], int]
658 *
659 * @par Lua函数原型
660 * forwardKinematicsAll(q: table) -> table, number
661 *
662 * @par Lua示例
663 * poses, fk_result = forwardKinematicsAll({3.083,1.227,1.098,0.670,-1.870,-0.397})
664 *
665 * @par JSON-RPC请求示例
666 * {"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}
667 *
668 * @par JSON-RPC响应示例
669 * {"id":1,"jsonrpc":"2.0","result":[[[0.0010004,0.0,0.122,0.0,0.0,3.141592653589793],
670 * [0.0010003999910823934,-0.12166795404953117,0.12205392567412496,1.5690838552993878,-1.3089969602251492,0.0016541204887245322],
671 * [0.10659809449330016,-0.12166124765791932,0.5161518260534821,-1.5718540206872664,0.43633111081725523,-0.002370419930605744],
672 * [0.4482255342315581,-0.1226390142692,0.3568490758201224,-0.000788980482890453,1.5665204619271216,-1.5719618592940798],
673 * [0.5519603828181741,-0.12282266347465487,0.35639753697117343,1.5707938201843654,0.0042721909279596635,1.569044569428874],
674 * [0.5513243939877184,-0.12401224959696328,0.2615193425222568,-3.1349118101994096,0.004272190926529066,1.569044569643007],
675 * [0.7494883076798231,-0.025647479212994567,-0.04023458911333461,-3.1349118101994096,0.004272190926529066,1.569044569643007]],0]}
676 * \endchinese
677 * \english
678 * Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset)
679 * Input joint angles, output links poses
680 *
681 * @param q Joint angles
682 * @return links poses and whether the result is valid
683 * The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows:
684 * 0 - Success
685 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
686 * -5 - The input joint angles is invalid (dimension error)
687 * @throws arcs::common_interface::AuboException
688 *
689 * @par Python function prototype
690 * forwardKinematicsAll(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
691 * Tuple[List[List[float]], int]
692 *
693 * @par Lua function prototype
694 * forwardKinematicsAll(q: table) -> table, number
695 *
696 * @par Lua example
697 * pose, fk_result = forwardKinematicsAll({3.083,1.227,1.098,0.670,-1.870,-0.397})
698 *
699 * @par JSON-RPC request example
700 * {"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}
701 *
702 * @par JSON-RPC response example
703 * {"id":1,"jsonrpc":"2.0","result":[[[0.0010004,0.0,0.122,0.0,0.0,3.141592653589793],
704 * [0.0010003999910823934,-0.12166795404953117,0.12205392567412496,1.5690838552993878,-1.3089969602251492,0.0016541204887245322],
705 * [0.10659809449330016,-0.12166124765791932,0.5161518260534821,-1.5718540206872664,0.43633111081725523,-0.002370419930605744],
706 * [0.4482255342315581,-0.1226390142692,0.3568490758201224,-0.000788980482890453,1.5665204619271216,-1.5719618592940798],
707 * [0.5519603828181741,-0.12282266347465487,0.35639753697117343,1.5707938201843654,0.0042721909279596635,1.569044569428874],
708 * [0.5513243939877184,-0.12401224959696328,0.2615193425222568,-3.1349118101994096,0.004272190926529066,1.569044569643007],
709 * [0.7494883076798231,-0.025647479212994567,-0.04023458911333461,-3.1349118101994096,0.004272190926529066,1.569044569643007]],0]}
710 * \endenglish
711 */
712 ResultWithErrno1 forwardKinematicsAll(const std::vector<double> &q);
713
714 /**
715 * \chinese
716 * 运动学逆解
717 * 输入TCP位姿和参考关节角度,输出关节角度
718 *
719 * @param qnear 参考关节角
720 * @param pose TCP位姿
721 * @return 关节角和逆解结果是否有效
722 * 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下
723 * 0 - 成功
724 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
725 * -5 - 输入的参考关节角或TCP位姿无效(维度错误)
726 * -23 - 逆解计算不收敛,计算出错
727 * -24 - 逆解计算超出机器人最大限制
728 * -25 - 逆解输入配置存在错误
729 * -26 - 逆解雅可比矩阵计算失败
730 * -27 - 目标点存在解析解,但均不满足选解条件
731 * -28 - 逆解返回未知类型错误
732 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
733 *
734 * @throws arcs::common_interface::AuboException
735 *
736 * @par Python函数原型
737 * inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
738 * arg1: List[float]) -> Tuple[List[float], int]
739 *
740 * @par Lua函数原型
741 * inverseKinematics(qnear: table, pose: table) -> table, int
742 *
743 * @par Lua示例
744 * joint,ik_result = inverseKinematics({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
745 *
746 * @par JSON-RPC请求示例
747 * {"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}
748 *
749 * @par JSON-RPC响应示例
750 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
751 * \endchinese
752 * \english
753 * Inverse kinematics
754 * Input TCP pose and reference joint angles, output joint angles
755 *
756 * @param qnear Reference joint angles
757 * @param pose TCP pose
758 * @return Joint angles and whether the inverse kinematics result is valid
759 * The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows:
760 * 0 - Success
761 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
762 * -5 - The input reference joint angles or tcp pose is invalid (dimension error)
763 * -23 - Inverse kinematics calculation does not converge, calculation error
764 * -24 - Inverse kinematics calculation exceeds robot limits
765 * -25 - Inverse kinematics input configuration error
766 * -26 - Inverse kinematics Jacobian calculation failed
767 * -27 - Analytical solution exists but none satisfy the selection criteria
768 * -28 - Unknown error in inverse kinematics
769 * If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
770 *
771 * @throws arcs::common_interface::AuboException
772 *
773 * @par Python function prototype
774 * inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
775 * arg1: List[float]) -> Tuple[List[float], int]
776 *
777 * @par Lua function prototype
778 * inverseKinematics(qnear: table, pose: table) -> table, int
779 *
780 * @par Lua example
781 * joint,ik_result = inverseKinematics({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
782 *
783 * @par JSON-RPC request example
784 * {"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}
785 *
786 * @par JSON-RPC response example
787 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
788 * \endenglish
789 */
790 ResultWithErrno inverseKinematics(const std::vector<double> &qnear,
791 const std::vector<double> &pose);
792
793 /**
794 * \chinese
795 * 运动学逆解
796 * 输入TCP位姿和参考关节角度,输出关节角度
797 *
798 * @param qnear 参考关节角
799 * @param pose TCP位姿
800 * @param tcp_offset TCP偏移
801 * @return 关节角和逆解结果是否有效,同 inverseKinematics
802 * @throws arcs::common_interface::AuboException
803 *
804 * @par Python函数原型
805 * inverseKinematics1(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
806 * arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
807 *
808 * @par Lua函数原型
809 * inverseKinematics1(qnear: table, pose: table, tcp_offset: table) -> table, int
810 *
811 * @par Lua示例
812 * 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})
813 *
814 * @par JSON-RPC请求示例
815 * {"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,
816 * 0.13201,0.03879,0,0,0]],"id":1}
817 *
818 * @par JSON-RPC响应示例
819 * {"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}
820 * \endchinese
821 * \english
822 * Inverse kinematics
823 * Input TCP pose and reference joint angles, output joint angles
824 *
825 * @param qnear Reference joint angles
826 * @param pose TCP pose
827 * @param tcp_offset TCP offset
828 * @return Joint angles and whether the result is valid, same as inverseKinematics
829 * @throws arcs::common_interface::AuboException
830 *
831 * @par Python function prototype
832 * inverseKinematics1(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
833 * arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
834 *
835 * @par Lua function prototype
836 * inverseKinematics1(qnear: table, pose: table, tcp_offset: table) -> table, int
837 *
838 * @par Lua example
839 * 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})
840 *
841 * @par JSON-RPC request example
842 * {"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,
843 * 0.13201,0.03879,0,0,0]],"id":1}
844 *
845 * @par JSON-RPC response example
846 * {"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}
847 * \endenglish
848 */
849 ResultWithErrno inverseKinematics1(const std::vector<double> &qnear,
850 const std::vector<double> &pose,
851 const std::vector<double> &tcp_offset);
852
853 /**
854 * \chinese
855 * 求出所有的逆解, 基于激活的 TCP 偏移
856 *
857 * @param pose TCP位姿
858 * @return 关节角和逆解结果是否有效
859 * 返回的错误码同inverseKinematics
860 *
861 * @throws arcs::common_interface::AuboException
862 *
863 * @par JSON-RPC请求示例
864 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
865 *
866 * @par JSON-RPC响应示例
867 * {"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],
868 * [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411],
869 * [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845],
870 * [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}
871 * \endchinese
872 * \english
873 * Solve all inverse kinematics solutions based on the activated TCP offset
874 *
875 * @param pose TCP pose
876 * @return Joint angles and whether the result is valid
877 * The returned error code is the same as inverseKinematics
878 *
879 * @throws arcs::common_interface::AuboException
880 *
881 * @par JSON-RPC request example
882 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
883 *
884 * @par JSON-RPC response example
885 * {"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],
886 * [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411],
887 * [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845],
888 * [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}
889 * \endenglish
890 */
891 ResultWithErrno1 inverseKinematicsAll(const std::vector<double> &pose);
892
893 /**
894 * \chinese
895 * 求出所有的逆解, 基于提供的 TCP 偏移
896 *
897 * @param pose TCP位姿
898 * @param tcp_offset TCP偏移
899 * @return 关节角和逆解结果是否有效,同 inverseKinematicsAll
900 * 返回的错误码同inverseKinematics
901 *
902 * @throws arcs::common_interface::AuboException
903 *
904 * @par JSON-RPC请求示例
905 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll1","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0,
906 * 0.13201,0.03879,0,0,0]],"id":1}
907 *
908 * @par JSON-RPC响应示例
909 * {"id":1,"jsonrpc":"2.0","result":[[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],
910 * [3.0818224058231602,0.17980369843203092,-1.0997576631122077,-0.48102131527371267,-1.8697135490338517,-0.40149459722060593],
911 * [0.40972960018231047,-0.16226026285489026,1.0823403816496,0.2700204411869427,0.9734251963887868,0.0012903686498106507],
912 * [0.41236549588802296,-1.193621392918341,-1.0828346680836718,-0.8671097369314354,0.972815367289568,0.007206851371073478]],0]}
913 * \endchinese
914 * \english
915 * Solve all inverse kinematics solutions based on the provided TCP offset
916 *
917 * @param pose TCP pose
918 * @param tcp_offset TCP offset
919 * @return Joint angles and whether the result is valid, same as inverseKinematicsAll
920 * The returned error code is the same as inverseKinematics
921 *
922 * @throws arcs::common_interface::AuboException
923 *
924 * @par JSON-RPC request example
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 response example
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 * \endenglish
934 */
936 const std::vector<double> &pose, const std::vector<double> &tcp_offset);
937
938 /**
939 * \chinese
940 * 运动学逆解(忽略 TCP 偏移值)
941 *
942 * @param qnear 参考关节角
943 * @param pose 法兰盘中心的位姿
944 * @return 关节角和逆解结果是否有效
945 * 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下
946 * 0 - 成功
947 * -1 - 机械臂状态不对(未初始化完成,可尝试再次调用)
948 * -5 - 输入的参考关节角或位姿无效(维度错误)
949 *
950 * @throws arcs::common_interface::AuboException
951 *
952 * @par Lua函数原型
953 * inverseToolKinematics(qnear: table, pose: table) -> table, int
954 *
955 * @par Lua示例
956 * joint, ik_result = inverseToolKinematics({0,0,0,0,0,0},{0.58815,0.0532,0.62391,2.46,0.479,1.619})
957 *
958 * @par JSON-RPC请求示例
959 * {"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}
960 *
961 * @par JSON-RPC响应示例
962 * {"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}
963 * \endchinese
964 * \english
965 * Inverse kinematics (ignoring TCP offset)
966 *
967 * @param qnear Reference joint angles
968 * @param pose Flange center pose
969 * @return Joint angles and whether the result is valid
970 * The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows:
971 * 0 - Success
972 * -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again)
973 * -5 - The input reference joint angles or pose is invalid (dimension error)
974 * @throws arcs::common_interface::AuboException
975 *
976 * @par Lua function prototype
977 * inverseToolKinematics(qnear: table, pose: table) -> table, int
978 *
979 * @par Lua example
980 * joint, ik_result = inverseToolKinematics({0,0,0,0,0,0},{0.58815,0.0532,0.62391,2.46,0.479,1.619})
981 *
982 * @par JSON-RPC request example
983 * {"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}
984 *
985 * @par JSON-RPC response example
986 * {"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}
987 * \endenglish
988 */
989 ResultWithErrno inverseToolKinematics(const std::vector<double> &qnear,
990 const std::vector<double> &pose);
991
992 /**
993 * \chinese
994 * 运动学逆解(忽略 TCP 偏移值)
995 *
996 * @param qnear 参考关节角
997 * @param pose 法兰盘中心的位姿
998 * @return 关节角和逆解结果是否有效
999 *
1000 * @throws arcs::common_interface::AuboException
1001 *
1002 * @par JSON-RPC请求示例
1003 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
1004 *
1005 * @par JSON-RPC响应示例
1006 * {"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],
1007 * [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814],
1008 * [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287],
1009 * [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}
1010 * \endchinese
1011 * \english
1012 * Inverse kinematics (ignoring TCP offset)
1013 *
1014 * @param qnear Reference joint angles
1015 * @param pose Flange center pose
1016 * @return Joint angles and whether the result is valid
1017 *
1018 * @throws arcs::common_interface::AuboException
1019 *
1020 * @par JSON-RPC request example
1021 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
1022 *
1023 * @par JSON-RPC response example
1024 * {"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],
1025 * [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814],
1026 * [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287],
1027 * [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}
1028 * \endenglish
1029 */
1030 ResultWithErrno1 inverseToolKinematicsAll(const std::vector<double> &pose);
1031
1032 /**
1033 * \chinese
1034 * 求解movej之间的轨迹点
1035 *
1036 * @param q1 movej的起点
1037 * @param r1 在q1处的交融半径
1038 * @param q2 movej的终点
1039 * @param r2 在q2处的交融半径
1040 * @param d 采样距离
1041 * @return q1~q2 之间笛卡尔空间离散轨迹点(x,y,z,rx,ry,rz)集合
1042 *
1043 * @throws arcs::common_interface::AuboException
1044 *
1045 * @par Python函数原型
1046 * pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
1047 * float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
1048 *
1049 * @par Lua函数原型
1050 * pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) ->
1051 * table, number
1052 *
1053 * @par Lua示例
1054 * 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)
1055 *
1056 * \endchinese
1057 * \english
1058 * Solve the trajectory points between movej
1059 *
1060 * @param q1 Start point of movej
1061 * @param r1 Blend radius at q1
1062 * @param q2 End point of movej
1063 * @param r2 Blend radius at q2
1064 * @param d Sampling distance
1065 * @return Discrete trajectory points (x, y, z, rx, ry, rz) between q1 and q2 in Cartesian space
1066 *
1067 * @throws arcs::common_interface::AuboException
1068 *
1069 * @par Python function prototype
1070 * pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
1071 * float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
1072 *
1073 * @par Lua function prototype
1074 * pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) ->
1075 * table, number
1076 *
1077 * @par Lua example
1078 * 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)
1079 *
1080 * \endenglish
1081 */
1082 std::vector<std::vector<double>> pathMovej(const std::vector<double> &q1,
1083 double r1,
1084 const std::vector<double> &q2,
1085 double r2, double d);
1086 /**
1087 * \chinese
1088 * 计算机械臂末端的雅克比矩阵
1089 *
1090 * @param q 关节角
1091 * @param base_or_end 参考坐标系为基坐标系(或者末端坐标系)
1092 * true: 在 base 下描述
1093 * false: 在 末端坐标系 下描述
1094 * @return 雅克比矩阵是否有效
1095 * 返回值的第一个参数为该构型下对应的雅克比矩阵,第二个为逆解错误码
1096 * 此接口的错误码返回值在0.28.1-rc.21 0.29.0-alpha.25版本之后做了修改。
1097 * 此前逆解错误时返回 30082 ,修改后错误码返回列表如下
1098 * 0 - 成功
1099 * -23 - 逆解计算不收敛,计算出错
1100 * -24 - 逆解计算超出机器人最大限制
1101 * -25 - 逆解输入配置存在错误
1102 * -26 - 逆解雅可比矩阵计算失败
1103 * -27 - 目标点存在解析解,但均不满足选解条件
1104 * -28 - 逆解返回未知类型错误
1105 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
1106 *
1107 * @throws arcs::common_interface::AuboException
1108 *
1109 * @par Python函数原型
1110 * calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
1111 * arg1: bool) -> Tuple[List[float], int]
1112 *
1113 * @par Lua函数原型
1114 * calJacobian(q: table, base_or_end: boolean) -> table
1115 *
1116 * @par Lua示例
1117 * calJ_result = calJacobian({0.58815,0.0532,0.62391,2.46,0.479,1.619},true)
1118 *
1119 * @par JSON-RPC请求示例
1120 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
1121 *
1122 * @par JSON-RPC响应示例
1123 * {"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487,
1124 * 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346,
1125 * 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867,
1126 * -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091,
1127 * -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894,
1128 * 0.43771285536682175],0]}
1129 * \endchinese
1130 * \english
1131 * Calculate the Jacobian matrix at the robot end-effector
1132 *
1133 * @param q Joint angles
1134 * @param base_or_end Reference frame: base (or end-effector)
1135 * true: described in base frame
1136 * false: described in end-effector frame
1137 * @return Whether the Jacobian matrix is valid
1138 * The first parameter of the return value is the Jacobian matrix for this configuration, the second is the error code.
1139 * The error code list was updated after versions 0.28.1-rc.21 and 0.29.0-alpha.25.
1140 * Previously, inverse kinematics errors returned 30082. The updated error codes are:
1141 * 0 - Success
1142 * -23 - Inverse kinematics calculation does not converge, calculation error
1143 * -24 - Inverse kinematics calculation exceeds robot limits
1144 * -25 - Inverse kinematics input configuration error
1145 * -26 - Inverse kinematics Jacobian calculation failed
1146 * -27 - Analytical solution exists but none satisfy the selection criteria
1147 * -28 - Unknown error in inverse kinematics
1148 * If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
1149 *
1150 * @throws arcs::common_interface::AuboException
1151 *
1152 * @par Python function prototype
1153 * calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
1154 * arg1: bool) -> Tuple[List[float], int]
1155 *
1156 * @par Lua function prototype
1157 * calJacobian(q: table, base_or_end: boolean) -> table
1158 *
1159 * @par Lua example
1160 * calJ_result = calJacobian({0.58815,0.0532,0.62391,2.46,0.479,1.619},true)
1161 *
1162 * @par JSON-RPC request example
1163 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
1164 *
1165 * @par JSON-RPC response example
1166 * {"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487,
1167 * 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346,
1168 * 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867,
1169 * -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091,
1170 * -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894,
1171 * 0.43771285536682175],0]}
1172 * \endenglish
1173 */
1174 ResultWithErrno calcJacobian(const std::vector<double> &q,
1175 bool base_or_end);
1176
1177 /**
1178 * \chinese
1179 * 求解交融的轨迹点
1180 *
1181 * @param type
1182 * 0-movej 和 movej
1183 * 1-movej 和 movel
1184 * 2-movel 和 movej
1185 * 3-movel 和 movel
1186 * @param q_start 交融前路径的起点
1187 * @param q_via 交融点
1188 * @param q_to 交融后路径的终点
1189 * @param r 在q_via处的交融半径
1190 * @param d 采样距离
1191 * @return q_via处的交融段笛卡尔空间离散轨迹点(x,y,z)集合
1192 *
1193 * @throws arcs::common_interface::AuboException
1194 *
1195 * @par Python函数原型
1196 * pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1:
1197 * List[float], arg2: List[float], arg3: List[float], arg4: float, arg5:
1198 * float) -> List[List[float]]
1199 *
1200 * @par Lua函数原型
1201 * pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table,
1202 * r: number, d: number) -> table, number
1203 *
1204 * @par Lua示例
1205 * 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},
1206 * {0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.25,0.02)
1207 *
1208 * \endchinese
1209 * \english
1210 * Solve the blended trajectory points
1211 *
1212 * @param type
1213 * 0-movej and movej
1214 * 1-movej and movel
1215 * 2-movel and movej
1216 * 3-movel and movel
1217 * @param q_start Start point before blending
1218 * @param q_via Blending point
1219 * @param q_to End point after blending
1220 * @param r Blend radius at q_via
1221 * @param d Sampling distance
1222 * @return Discrete trajectory points (x, y, z) of the blend segment at q_via in Cartesian space
1223 *
1224 * @throws arcs::common_interface::AuboException
1225 *
1226 * @par Python function prototype
1227 * pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1:
1228 * List[float], arg2: List[float], arg3: List[float], arg4: float, arg5:
1229 * float) -> List[List[float]]
1230 *
1231 * @par Lua function prototype
1232 * pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table,
1233 * r: number, d: number) -> table, number
1234 *
1235 * @par Lua example
1236 * 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},
1237 * {0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.25,0.02)
1238 *
1239 * \endenglish
1240 */
1241 std::vector<std::vector<double>> pathBlend3Points(
1242 int type, const std::vector<double> &q_start,
1243 const std::vector<double> &q_via, const std::vector<double> &q_to,
1244 double r, double d);
1245
1246 /**
1247 * \chinese
1248 * 生成用于负载辨识的激励轨迹
1249 * 此接口内部调用pathBufferAppend
1250 * 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
1251 * @param name 轨迹名字
1252 * @param traj_conf 各关节轨迹的限制条件
1253 * traj_conf.move_axis: 运动的轴
1254 * 由于实际用户现场可能不希望在负载辨识时控制机械臂多关节大幅度运动,故最好选用traj_conf.move_axis=LoadIdentifyMoveAxis::Joint_4_6;
1255 * traj_conf.init_joint:
1256 * 运动初始关节角,为了避免关节5接近零位时的奇异问题,应设置traj_conf.init_joint[4]的绝对值不小于0.3(rad),接近1.57(rad)为宜。其余关节的关节角可任意设置
1257 * traj_conf.lower_joint_bound, traj_conf.upper_joint_bound:
1258 * 关节角上下限,维度应与config.move_axis维度保持一致,推荐设置upper_joint_bound为2,lower_joint_bound为-2
1259 * config.max_velocity, config.max_acceleration:
1260 * 关节角速度角加速度限制,维度应与config.move_axis维度保持一致,出于安全和驱动器跟随性能的考虑,推荐设置max_velocity=3,max_acceleration=5
1261 *
1262 * @return 成功返回0;失败返回错误码
1263 * AUBO_BUSY
1264 * AUBO_BAD_STATE
1265 * -AUBO_INVL_ARGUMENT
1266 * -AUBO_BAD_STATE
1267 *
1268 * @throws arcs::common_interface::AuboException
1269 * \endchinese
1270 * \english
1271 * Generate excitation trajectory for payload identification
1272 * This interface internally calls pathBufferAppend
1273 * The offline trajectory is stored in the buffer, and can be executed later via movePathBuffer
1274 * @param name Trajectory name
1275 * @param traj_conf Joint trajectory constraints
1276 * traj_conf.move_axis: Moving axes
1277 * 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;
1278 * traj_conf.init_joint:
1279 * 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.
1280 * traj_conf.lower_joint_bound, traj_conf.upper_joint_bound:
1281 * Joint angle limits, dimensions should match config.move_axis. Recommended: upper_joint_bound=2, lower_joint_bound=-2
1282 * config.max_velocity, config.max_acceleration:
1283 * Joint velocity and acceleration limits, dimensions should match config.move_axis. For safety and driver performance, recommended: max_velocity=3, max_acceleration=5
1284 *
1285 * @return Returns 0 on success; error code on failure
1286 * AUBO_BUSY
1287 * AUBO_BAD_STATE
1288 * -AUBO_INVL_ARGUMENT
1289 * -AUBO_BAD_STATE
1290 *
1291 * @throws arcs::common_interface::AuboException
1292 * \endenglish
1293 */
1294 int generatePayloadIdentifyTraj(const std::string &name,
1295 const TrajConfig &traj_conf);
1296 /**
1297 * \chinese
1298 * 负载辨识轨迹是否生成完成
1299 *
1300 * @return 完成返回0; 正在进行中返回1; 计算失败返回<0;
1301 *
1302 * @throws arcs::common_interface::AuboException
1303 *
1304 * @par JSON-RPC请求示例
1305 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
1306 *
1307 * @par JSON-RPC响应示例
1308 * {"id":1,"jsonrpc":"2.0","result":0}
1309 *
1310 * \endchinese
1311 * \english
1312 * Whether payload identification trajectory generation is finished
1313 *
1314 * @return 0 if finished; 1 if in progress; <0 if failed;
1315 *
1316 * @throws arcs::common_interface::AuboException
1317 *
1318 * @par JSON-RPC request example
1319 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
1320 *
1321 * @par JSON-RPC response example
1322 * {"id":1,"jsonrpc":"2.0","result":0}
1323 *
1324 * \endenglish
1325 */
1327
1328 /**
1329 * \chinese
1330 * 求解 moveS 的轨迹点
1331 *
1332 * @brief pathMoveS
1333 * @param qs 样条轨迹生成点集合
1334 * @param d 采样距离
1335 * @return
1336 *
1337 * @throws arcs::common_interface::AuboException
1338 * \endchinese
1339 * \english
1340 * Solve the trajectory points for moveS
1341 *
1342 * @brief pathMoveS
1343 * @param qs Spline trajectory generation point set
1344 * @param d Sampling distance
1345 * @return
1346 *
1347 * @throws arcs::common_interface::AuboException
1348 * \endenglish
1349 */
1350 std::vector<std::vector<double>> pathMoveS(
1351 const std::vector<std::vector<double>> &qs, double d);
1352
1353 /**
1354 * \chinese
1355 * 振动抑制参数辨识算法接口
1356 *
1357 * @param q 当前关节角度
1358 * @param qd 当前关节速度
1359 * @param target_q 目标关节角度
1360 * @param target_qd 关节速度
1361 * @param target_qdd 关节加速度
1362 * @param tool_offset 工具TCP信息
1363 * @param omega 振动频率
1364 * @param zeta 振动阻尼比
1365 * @return 振动抑制参数和是否辨识成功
1366 *
1367 * @throws arcs::common_interface::AuboException
1368 *
1369 * @par Python函数原型
1370 * calibVibrationParams(self: pyaubo_sdk.RobotAlgorithm, arg0:
1371 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]], arg3: List[List[float]],
1372 * arg4: List[List[float]], arg5: List[float]) -> list[list[float]],int
1373 *
1374 * @par Lua函数原型
1375 * calibVibrationParams(q: table,qd: table, target_q: table, target_qd: table,
1376 * target_qdd: table, tool_offset: table, omega: table, zeta: table) -> table,number
1377 * \endchinese
1378 */
1379 ResultWithErrno1 calibVibrationParams(const std::vector<std::vector<double>> &q,
1380 const std::vector<std::vector<double>> &qd,
1381 const std::vector<std::vector<double>> &target_q,
1382 const std::vector<std::vector<double>> &target_qd,
1383 const std::vector<std::vector<double>> &target_qdd,
1384 const std::vector<double> &tool_offset);
1385
1386protected:
1387 void *d_;
1388};
1389using RobotAlgorithmPtr = std::shared_ptr<RobotAlgorithm>;
1390
1391} // namespace common_interface
1392} // namespace arcs
1393
1394#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 偏移值)
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 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 payloadCalculateFinished()
负载辨识是否计算完成
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 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)
力传感器标定算法(三点标定法)
ResultWithErrno1 forwardKinematicsAll(const std::vector< double > &q)
运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出各连杆位姿
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double > > ForceSensorCalibResult
Definition type_def.h:773
std::tuple< std::vector< std::vector< double > >, int > ResultWithErrno1
Definition type_def.h:764
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double >, double > ForceSensorCalibResultWithError
Definition type_def.h:778
std::tuple< double, std::vector< double >, std::vector< double >, std::vector< double > > Payload
Definition type_def.h:768
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
std::tuple< std::vector< double >, int > ResultWithErrno
Definition type_def.h:763
用于负载辨识的轨迹配置
Definition type_def.h:747
数据类型的定义