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