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