ARCS SDK API  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 */
21class ARCS_ABI_EXPORT RobotAlgorithm
22{
23public:
25 virtual ~RobotAlgorithm();
26
27 /**
28 * 力传感器标定算法(三点标定法)
29 *
30 * @param force
31 * @param q
32 * @return
33 *
34 * @throws arcs::common_interface::AuboException
35 *
36 * @par Python函数原型
37 * calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0:
38 * List[List[float]], arg1: List[List[float]]) -> Tuple[List[float],
39 * List[float], float, List[float]]
40 *
41 * @par Lua函数原型
42 * calibrateTcpForceSensor(force: table, q: table) -> table
43 *
44 */
46 const std::vector<std::vector<double>> &forces,
47 const std::vector<std::vector<double>> &poses);
48
49 /**
50 * 力传感器标定算法(三点标定法)
51 * @param forces
52 * @param poses
53 * @return force_offset, com, mass, angle error
54 *
55 * @throws arcs::common_interface::AuboException
56 *
57 */
59 const std::vector<std::vector<double>> &forces,
60 const std::vector<std::vector<double>> &poses);
61
62 /**
63 * 基于电流的负载辨识算法接口
64 *
65 * 需要采集空载时运行激励轨迹的位置、速度、电流以及带负载时运行激励轨迹的位置、速度、电流
66 *
67 * @param data_file_no_payload
68 * 空载时运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
69 * @param data_file_with_payload
70 * 带负载运行激励轨迹各关节数据的文件路径(.csv格式),共18列,依次为6个关节位置、6个关节速度、6个关节电流
71 * @return 辨识的结果
72 *
73 * @throws arcs::common_interface::AuboException
74 *
75 * @par Python函数原型
76 * payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]],
77 * arg1: List[List[float]]) -> Tuple[List[float], List[float], float,
78 * List[float]]
79 *
80 * @par Lua函数原型
81 * payloadIdentify(data_with_payload: table, data_with_payload: table) ->
82 * table
83 *
84 */
85 int payloadIdentify(const std::string &data_file_no_payload,
86 const std::string &data_file_with_payload);
87
88 /**
89 * 新版基于电流的负载辨识算法接口
90 *
91 * 需要采集带载时运行最少三个点的位置、速度、加速度、电流、温度、末端传感器数据、底座数据
92 *
93 * @param data
94 * 带负载的各关节数据的文件路径(.csv格式),共42列,末端传感器数据、底座数据默认为0
95 * @return 辨识的结果
96 *
97 */
98 int payloadIdentify1(const std::string &file_name);
99
100 /**
101 * 负载辨识是否计算完成
102 * @return 完成返回0; 正在进行中返回1; 计算失败返回<0;
103 *
104 * @throws arcs::common_interface::AuboException
105 *
106 * @par JSON-RPC请求示例
107 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
108 *
109 * @par JSON-RPC响应示例
110 * {"id":1,"jsonrpc":"2.0","result":0}
111 *
112 */
114
115 /**
116 * 获取负载辨识结果
117 * @return
118 *
119 * @throws arcs::common_interface::AuboException
120 *
121 * @par JSON-RPC请求示例
122 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
123 *
124 * @par JSON-RPC响应示例
125 * {"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}
126 *
127 */
129
130 /**
131 * 关节摩擦力模型辨识算法接口
132 *
133 * @param q
134 * @param qd
135 * @param qdd
136 * @param temp
137 * @return
138 *
139 * @throws arcs::common_interface::AuboException
140 *
141 * @par Python函数原型
142 * frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0:
143 * List[List[float]], arg1: List[List[float]], arg2: List[List[float]],
144 * arg3: List[List[float]]) -> bool
145 *
146 * @par Lua函数原型
147 * frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) ->
148 * boolean
149 *
150 */
151 bool frictionModelIdentify(const std::vector<std::vector<double>> &q,
152 const std::vector<std::vector<double>> &qd,
153 const std::vector<std::vector<double>> &qdd,
154 const std::vector<std::vector<double>> &temp);
155
156 /**
157 * 工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移)
158 * 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
159 *
160 * @param q 关节角度
161 * @param type 标定类型
162 * @return 计算结果(工件坐标系位姿)以及错误代码
163 *
164 * @throws arcs::common_interface::AuboException
165 *
166 * @par Python函数原型
167 * calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0:
168 * List[List[float]], arg1: int) -> Tuple[List[float], int]
169 *
170 * @par Lua函数原型
171 * calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
172 *
173 */
175 const std::vector<std::vector<double>> &q, int type);
176
177 /**
178 * 动力学正解
179 *
180 * @param q 关节角
181 * @param torqs
182 * @return 计算结果以及错误代码
183 *
184 * @throws arcs::common_interface::AuboException
185 *
186 * @par Python函数原型
187 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
188 * List[float]) -> Tuple[List[float], int]
189 *
190 * @par Lua函数原型
191 * forwardDynamics(q: table, torqs: table) -> table, number
192 *
193 */
194 ResultWithErrno forwardDynamics(const std::vector<double> &q,
195 const std::vector<double> &torqs);
196
197 /**
198 * 动力学正解,基于给定的TCP偏移
199 *
200 * @param q 关节角
201 * @param torqs
202 * @return 计算结果以及错误代码,同forwardDynamics
203 *
204 * @throws arcs::common_interface::AuboException
205 *
206 * @par Python函数原型
207 * forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
208 * List[float]) -> Tuple[List[float], int]
209 *
210 * @par Lua函数原型
211 * forwardDynamics(q: table, torqs: table) -> table, number
212 *
213 */
214 ResultWithErrno forwardDynamics1(const std::vector<double> &q,
215 const std::vector<double> &torqs,
216 const std::vector<double> &tcp_offset);
217
218 /**
219 * 运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数)
220 * 输入关节角度,输出TCP位姿
221 *
222 * @param q 关节角
223 * @return TCP位姿和正解结果是否有效
224 *
225 * @throws arcs::common_interface::AuboException
226 *
227 * @par Python函数原型
228 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) ->
229 * Tuple[List[float], int]
230 *
231 * @par Lua函数原型
232 * forwardKinematics(q: table) -> table, number
233 *
234 * @par JSON-RPC请求示例
235 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
236 *
237 * @par JSON-RPC响应示例
238 * {"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}s
239 *
240 */
241 ResultWithErrno forwardKinematics(const std::vector<double> &q);
242
243 /**
244 * 运动学正解
245 * 输入关节角度,输出TCP位姿
246 *
247 * @param q 关节角
248 * @param tcp_offset tcp偏移
249 * @return TCP位姿和正解结果是否有效
250 *
251 * @throws arcs::common_interface::AuboException
252 *
253 * @par Python函数原型
254 * forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
255 * arg1: List[float]) -> Tuple[List[float], int]
256 *
257 * @par Lua函数原型
258 * forwardKinematics1(q: table, tcp_offset: table) -> table, number
259 *
260 * @par JSON-RPC请求示例
261 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0,
262 * 0.13201,0.03879,0,0,0]],"id":1}
263 *
264 * @par JSON-RPC响应示例
265 * {"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
266 *
267 * @since 0.24.1
268 *
269 */
270 ResultWithErrno forwardKinematics1(const std::vector<double> &q,
271 const std::vector<double> &tcp_offset);
272
273 /**
274 * 运动学正解(忽略 TCP 偏移值)
275 *
276 * @param q 关节角
277 * @return 法兰盘中心位姿和正解结果是否有效
278 *
279 * @throws arcs::common_interface::AuboException
280 *
281 * @par JSON-RPC请求示例
282 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
283 *
284 * @par JSON-RPC响应示例
285 * {"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}
286 *
287 */
288 ResultWithErrno forwardToolKinematics(const std::vector<double> &q);
289
290 /**
291 * 运动学逆解
292 * 输入TCP位姿和参考关节角度,输出关节角度
293 *
294 * @param qnear 参考关节角
295 * @param pose TCP位姿
296 * @return 关节角和逆解结果是否有效
297 * 返回值的第一个参数为逆解结果,第二个为逆解错误码,错误码返回列表如下
298 * 0 - 成功
299 * -23 - 逆解计算不收敛,计算出错
300 * -24 - 逆解计算超出机器人最大限制
301 * -25 - 逆解输入配置存在错误
302 * -26 - 逆解雅可比矩阵计算失败
303 * -27 - 目标点存在解析解,但均不满足选解条件
304 * -28 - 逆解返回未知类型错误
305 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
306 *
307 * @throws arcs::common_interface::AuboException
308 *
309 * @par Python函数原型
310 * inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
311 * arg1: List[float]) -> Tuple[List[float], int]
312 *
313 * @par Lua函数原型
314 * inverseKinematics(qnear: table, pose: table) -> table, int
315 *
316 * @par JSON-RPC请求示例
317 * {"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}
318 *
319 * @par JSON-RPC响应示例
320 * {"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}
321 *
322 */
323 ResultWithErrno inverseKinematics(const std::vector<double> &qnear,
324 const std::vector<double> &pose);
325
326 /**
327 * 运动学逆解
328 * 输入TCP位姿和参考关节角度,输出关节角度
329 *
330 * @param qnear 参考关节角
331 * @param pose TCP位姿
332 * @param tcp_offset TCP偏移
333 * @return 关节角和逆解结果是否有效,同 inverseKinematics
334 * @throws arcs::common_interface::AuboException
335 *
336 * @par Python函数原型
337 * inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
338 * arg1: List[float]) -> Tuple[List[float], int]
339 *
340 * @par Lua函数原型
341 * inverseKinematics(qnear: table, pose: table) -> table, int
342 *
343 * @par JSON-RPC请求示例
344 * {"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,
345 * 0.13201,0.03879,0,0,0]],"id":1}
346 *
347 * @par JSON-RPC响应示例
348 * {"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}
349 *
350 */
351 ResultWithErrno inverseKinematics1(const std::vector<double> &qnear,
352 const std::vector<double> &pose,
353 const std::vector<double> &tcp_offset);
354
355 /**
356 * 求出所有的逆解, 基于激活的 TCP 偏移
357 *
358 * @param pose TCP位姿
359 * @return 关节角和逆解结果是否有效
360 * 返回的错误码同inverseKinematics
361 *
362 * @throws arcs::common_interface::AuboException
363 *
364 * @par JSON-RPC请求示例
365 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
366 *
367 * @par JSON-RPC响应示例
368 * {"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],
369 * [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411],
370 * [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845],
371 * [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}
372 *
373 */
374 ResultWithErrno1 inverseKinematicsAll(const std::vector<double> &pose);
375
376 /**
377 * 求出所有的逆解, 基于提供的 TCP 偏移
378 *
379 * @param pose TCP位姿
380 * @param tcp_offset TCP偏移
381 * @return 关节角和逆解结果是否有效,同 inverseKinematicsAll
382 * 返回的错误码同inverseKinematics
383 *
384 * @throws arcs::common_interface::AuboException
385 *
386 * @par JSON-RPC请求示例
387 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll1","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0,
388 * 0.13201,0.03879,0,0,0]],"id":1}
389 *
390 * @par JSON-RPC响应示例
391 * {"id":1,"jsonrpc":"2.0","result":[[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],
392 * [3.0818224058231602,0.17980369843203092,-1.0997576631122077,-0.48102131527371267,-1.8697135490338517,-0.40149459722060593],
393 * [0.40972960018231047,-0.16226026285489026,1.0823403816496,0.2700204411869427,0.9734251963887868,0.0012903686498106507],
394 * [0.41236549588802296,-1.193621392918341,-1.0828346680836718,-0.8671097369314354,0.972815367289568,0.007206851371073478]],0]}
395 *
396 */
398 const std::vector<double> &pose, const std::vector<double> &tcp_offset);
399
400 /**
401 * 运动学逆解(忽略 TCP 偏移值)
402 *
403 * @param qnear 参考关节角
404 * @param pose 法兰盘中心的位姿
405 * @return 关节角和逆解结果是否有效
406 *
407 * @throws arcs::common_interface::AuboException
408 *
409 * @par JSON-RPC请求示例
410 * {"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}
411 *
412 * @par JSON-RPC响应示例
413 * {"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}
414 *
415 */
416 ResultWithErrno inverseToolKinematics(const std::vector<double> &qnear,
417 const std::vector<double> &pose);
418
419 /**
420 * 运动学逆解(忽略 TCP 偏移值)
421 *
422 * @param qnear 参考关节角
423 * @param pose 法兰盘中心的位姿
424 * @return 关节角和逆解结果是否有效
425 *
426 * @throws arcs::common_interface::AuboException
427 *
428 * @par JSON-RPC请求示例
429 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
430 *
431 * @par JSON-RPC响应示例
432 * {"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],
433 * [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814],
434 * [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287],
435 * [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}
436 */
437 ResultWithErrno1 inverseToolKinematicsAll(const std::vector<double> &pose);
438
439 /**
440 * 求解movej之间的轨迹点
441 *
442 * @param q1 movej的起点
443 * @param r1 在q1处的交融半径
444 * @param q2 movej的终点
445 * @param r2 在q2处的交融半径
446 * @param d 采样距离
447 * @return q1~q2 之间笛卡尔空间离散轨迹点(x,y,z,rx,ry,rz)集合
448 *
449 * @throws arcs::common_interface::AuboException
450 *
451 * @par Python函数原型
452 * pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1:
453 * float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
454 *
455 * @par Lua函数原型
456 * pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) ->
457 * table, number
458 */
459 std::vector<std::vector<double>> pathMovej(const std::vector<double> &q1,
460 double r1,
461 const std::vector<double> &q2,
462 double r2, double d);
463 /**
464 * 计算机械臂末端的雅克比矩阵
465 *
466 * @param q 关节角
467 * @param base_or_end 参考坐标系为基坐标系(或者末端坐标系)
468 * true: 在 base 下描述
469 * false: 在 末端坐标系 下描述
470 * @return 雅克比矩阵是否有效
471 * 返回值的第一个参数为该构型下对应的雅克比矩阵,第二个为逆解错误码
472 * 此接口的错误码返回值在0.28.1-rc.21 0.29.0-alpha.25版本之后做了修改。
473 * 此前逆解错误时返回 30082 ,修改后错误码返回列表如下
474 * 0 - 成功
475 * -23 - 逆解计算不收敛,计算出错
476 * -24 - 逆解计算超出机器人最大限制
477 * -25 - 逆解输入配置存在错误
478 * -26 - 逆解雅可比矩阵计算失败
479 * -27 - 目标点存在解析解,但均不满足选解条件
480 * -28 - 逆解返回未知类型错误
481 * 若错误码非0,则返回值的第一个参数为输入参考关节角qnear
482 *
483 * @throws arcs::common_interface::AuboException
484 *
485 * @par Python函数原型
486 * calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float],
487 * arg1: bool) -> Tuple[List[float], int]
488 *
489 * @par Lua函数原型
490 * calJacobian(q: table, base_or_end: boolean) -> table
491 *
492 * @par JSON-RPC请求示例
493 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
494 *
495 * @par JSON-RPC响应示例
496 * {"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487,
497 * 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346,
498 * 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867,
499 * -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091,
500 * -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894,
501 * 0.43771285536682175],0]}
502 *
503 */
504 ResultWithErrno calcJacobian(const std::vector<double> &q,
505 bool base_or_end);
506
507 /**
508 * 求解交融的轨迹点
509 *
510 * @param type
511 * 0-movej and movej
512 * 1-movej and movel
513 * 2-movel and movej
514 * 3-movel and movel
515 * @param q_start 交融前路径的起点
516 * @param q_via 在q1处的交融半径
517 * @param q_to 交融后路径的终点
518 * @param r 在q_via处的交融半径
519 * @param d 采样距离
520 * @return q_via处的交融段笛卡尔空间离散轨迹点(x,y,z)集合
521 *
522 * @throws arcs::common_interface::AuboException
523 *
524 * @par Python函数原型
525 * pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1:
526 * List[float], arg2: List[float], arg3: List[float], arg4: float, arg5:
527 * float) -> List[List[float]]
528 *
529 *
530 * @par Lua函数原型
531 * pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table,
532 * r: number, d: number) -> table, number
533 */
534 std::vector<std::vector<double>> pathBlend3Points(
535 int type, const std::vector<double> &q_start,
536 const std::vector<double> &q_via, const std::vector<double> &q_to,
537 double r, double d);
538
539 /**
540 * 生成用于负载辨识的激励轨迹
541 * 此接口内部调用pathBufferAppend
542 * 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
543 * @param name 轨迹名字
544 * @param traj_conf 各关节轨迹的限制条件
545 * traj_conf.move_axis: 运动的轴
546 * 由于实际用户现场可能不希望在负载辨识时控制机械臂多关节大幅度运动,故最好选用traj_conf.move_axis=LoadIdentifyMoveAxis::Joint_4_6;
547 * traj_conf.init_joint:
548 * 运动初始关节角,为了避免关节5接近零位时的奇异问题,应设置traj_conf.init_joint[4]的绝对值不小于0.3(rad),接近1.57(rad)为宜。其余关节的关节角可任意设置
549 * traj_conf.lower_joint_bound, traj_conf.upper_joint_bound:
550 * 关节角上下限,维度应与config.move_axis维度保持一致,推荐设置upper_joint_bound为2,lower_joint_bound为-2
551 * config.max_velocity, config.max_acceleration:
552 * 关节角速度角加速度限制,维度应与config.move_axis维度保持一致,出于安全和驱动器跟随性能的考虑,推荐设置max_velocity=3,max_acceleration=5
553 *
554 * @return 成功返回0;失败返回错误码
555 * AUBO_BUSY
556 * AUBO_BAD_STATE
557 * -AUBO_INVL_ARGUMENT
558 * -AUBO_BAD_STATE
559 *
560 * @throws arcs::common_interface::AuboException
561 *
562 */
563 int generatePayloadIdentifyTraj(const std::string &name,
564 const TrajConfig &traj_conf);
565 /**
566 * 负载辨识轨迹是否生成完成
567 *
568 * @return 完成返回0; 正在进行中返回1; 计算失败返回<0;
569 *
570 * @throws arcs::common_interface::AuboException
571 *
572 * @par JSON-RPC请求示例
573 * {"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
574 *
575 * @par JSON-RPC响应示例
576 * {"id":1,"jsonrpc":"2.0","result":0}
577 *
578 */
580
581 /**
582 * 求解 moveS 的轨迹点
583 *
584 * @brief pathMoveS
585 * @param qs 样条轨迹生成点集合
586 * @param d 采样距离
587 * @return
588 *
589 * @throws arcs::common_interface::AuboException
590 */
591 std::vector<std::vector<double>> pathMoveS(
592 const std::vector<std::vector<double>> &qs, double d);
593
594protected:
595 void *d_;
596};
597using RobotAlgorithmPtr = std::shared_ptr<RobotAlgorithm>;
598
599// clang-format off
600#define RobotAlgorithm_DECLARES \
601 _FUNC(RobotAlgorithm, 2, calibrateTcpForceSensor, forces, poses) \
602 _FUNC(RobotAlgorithm, 2, calibrateTcpForceSensor2, forces, poses) \
603 _FUNC(RobotAlgorithm, 2, payloadIdentify, data_no_payload, data_with_payload) \
604 _FUNC(RobotAlgorithm, 1, payloadIdentify1, file_name) \
605 _FUNC(RobotAlgorithm, 0, payloadCalculateFinished) \
606 _FUNC(RobotAlgorithm, 0, getPayloadIdentifyResult) \
607 _FUNC(RobotAlgorithm, 2, generatePayloadIdentifyTraj, name, TrajConfig) \
608 _FUNC(RobotAlgorithm, 0, payloadIdentifyTrajGenFinished) \
609 _FUNC(RobotAlgorithm, 4, frictionModelIdentify, q, qd, qdd, temp) \
610 _FUNC(RobotAlgorithm, 2, calibWorkpieceCoordinatePara, q, type) \
611 _FUNC(RobotAlgorithm, 2, forwardDynamics, q, torqs) \
612 _FUNC(RobotAlgorithm, 1, forwardKinematics, q) \
613 _FUNC(RobotAlgorithm, 1, forwardToolKinematics, q) \
614 _FUNC(RobotAlgorithm, 3, forwardDynamics1, q, torqs, tcp_offset) \
615 _FUNC(RobotAlgorithm, 2, forwardKinematics1, q, tcp_offset) \
616 _FUNC(RobotAlgorithm, 2, inverseKinematics, qnear, pose) \
617 _FUNC(RobotAlgorithm, 1, inverseKinematicsAll, pose) \
618 _FUNC(RobotAlgorithm, 3, inverseKinematics1, qnear, pose, tcp_offset) \
619 _FUNC(RobotAlgorithm, 2, inverseKinematicsAll1, pose, tcp_offset) \
620 _FUNC(RobotAlgorithm, 2, inverseToolKinematics, qnear, pose) \
621 _FUNC(RobotAlgorithm, 1, inverseToolKinematicsAll, pose) \
622 _FUNC(RobotAlgorithm, 5, pathMovej, q1, r1, q2, r2, d) \
623 _FUNC(RobotAlgorithm, 6, pathBlend3Points, type, q_start, q_via, q_to, r, d) \
624 _FUNC(RobotAlgorithm, 2, calcJacobian, q, base_or_end) \
625 _FUNC(RobotAlgorithm, 2, pathMoveS, qs, d)
626
627// clang-format on
628
629} // namespace common_interface
630} // namespace arcs
631
632#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:671
std::tuple< std::vector< std::vector< double > >, int > ResultWithErrno1
Definition type_def.h:662
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double >, double > ForceSensorCalibResultWithError
Definition type_def.h:676
std::tuple< double, std::vector< double >, std::vector< double >, std::vector< double > > Payload
Definition type_def.h:666
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
std::tuple< std::vector< double >, int > ResultWithErrno
Definition type_def.h:661
用于负载辨识的轨迹配置
Definition type_def.h:645
数据类型的定义