4#ifndef AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
5#define AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
12#include <aubo/global_config.h>
16namespace common_interface {
80 const std::vector<std::vector<double>> &forces,
81 const std::vector<std::vector<double>> &poses);
102 const std::vector<std::vector<double>> &forces,
103 const std::vector<std::vector<double>> &poses);
130 const std::vector<std::vector<double>> &forces,
131 const std::vector<std::vector<double>> &poses,
const double &mass,
132 const std::vector<double>&cog);
181 const std::string &data_file_with_payload);
318 const std::vector<std::vector<double>> &qd,
319 const std::vector<std::vector<double>> &qdd,
320 const std::vector<std::vector<double>> &temp);
367 const std::vector<std::vector<double>> &q,
int type);
412 const std::vector<double> &torqs);
459 const std::vector<double> &torqs,
460 const std::vector<double> &tcp_offset);
588 const std::vector<double> &tcp_offset);
719 const std::vector<double> &pose);
778 const std::vector<double> &pose,
779 const std::vector<double> &tcp_offset);
864 const std::vector<double> &pose,
const std::vector<double> &tcp_offset);
918 const std::vector<double> &pose);
1010 std::vector<std::vector<double>>
pathMovej(
const std::vector<double> &q1,
1012 const std::vector<double> &q2,
1013 double r2,
double d);
1170 int type,
const std::vector<double> &q_start,
1171 const std::vector<double> &q_via,
const std::vector<double> &q_to,
1172 double r,
double d);
1279 const std::vector<std::vector<double>> &qs,
double d);
1308 const std::vector<std::vector<double>> &qd,
1309 const std::vector<std::vector<double>> &target_q,
1310 const std::vector<std::vector<double>> &target_qd,
1311 const std::vector<std::vector<double>> &target_qdd,
1312 const std::vector<double> &tool_offset);
std::vector< std::vector< double > > pathMovej(const std::vector< double > &q1, double r1, const std::vector< double > &q2, double r2, double d)
求解movej之间的轨迹点
ResultWithErrno forwardDynamics1(const std::vector< double > &q, const std::vector< double > &torqs, const std::vector< double > &tcp_offset)
动力学正解,基于给定的TCP偏移
ResultWithErrno calibrateTcpForceSensor3(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses, const double &mass, const std::vector< double > &cog)
力传感器偏置标定算法
ResultWithErrno forwardKinematics1(const std::vector< double > &q, const std::vector< double > &tcp_offset)
运动学正解 输入关节角度,输出TCP位姿
ResultWithErrno forwardToolKinematics(const std::vector< double > &q)
运动学正解(忽略 TCP 偏移值)
std::vector< std::vector< double > > pathBlend3Points(int type, const std::vector< double > &q_start, const std::vector< double > &q_via, const std::vector< double > &q_to, double r, double d)
求解交融的轨迹点
ResultWithErrno calibWorkpieceCoordinatePara(const std::vector< std::vector< double > > &q, int type)
工件坐标系标定算法接口(需要在调用之前正确的设置机器人的TCP偏移) 输入多组关节角度和标定类型,输出工件坐标系位姿(相对于机器人基坐标系)
bool frictionModelIdentify(const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &qdd, const std::vector< std::vector< double > > &temp)
关节摩擦力模型辨识算法接口
int payloadIdentify1(const std::string &file_name)
新版基于电流的负载辨识算法接口
ResultWithErrno inverseKinematics1(const std::vector< double > &qnear, const std::vector< double > &pose, const std::vector< double > &tcp_offset)
运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
int payloadCalculateFinished()
负载辨识是否计算完成
Payload getPayloadIdentifyResult()
获取负载辨识结果
ResultWithErrno forwardDynamics(const std::vector< double > &q, const std::vector< double > &torqs)
动力学正解
ResultWithErrno1 inverseKinematicsAll1(const std::vector< double > &pose, const std::vector< double > &tcp_offset)
求出所有的逆解, 基于提供的 TCP 偏移
ResultWithErrno inverseToolKinematics(const std::vector< double > &qnear, const std::vector< double > &pose)
运动学逆解(忽略 TCP 偏移值)
std::vector< std::vector< double > > pathMoveS(const std::vector< std::vector< double > > &qs, double d)
求解 moveS 的轨迹点
ResultWithErrno calcJacobian(const std::vector< double > &q, bool base_or_end)
计算机械臂末端的雅克比矩阵
int payloadIdentify(const std::string &data_file_no_payload, const std::string &data_file_with_payload)
基于电流的负载辨识算法接口
ResultWithErrno1 inverseKinematicsAll(const std::vector< double > &pose)
求出所有的逆解, 基于激活的 TCP 偏移
ResultWithErrno1 inverseToolKinematicsAll(const std::vector< double > &pose)
运动学逆解(忽略 TCP 偏移值)
ResultWithErrno forwardKinematics(const std::vector< double > &q)
运动学正解, 基于激活的TCP偏移(最近的通过 setTcpOffset 设置的参数) 输入关节角度,输出TCP位姿
ForceSensorCalibResult calibrateTcpForceSensor(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
力传感器标定算法(三点标定法)
int payloadIdentifyTrajGenFinished()
负载辨识轨迹是否生成完成
ResultWithErrno inverseKinematics(const std::vector< double > &qnear, const std::vector< double > &pose)
运动学逆解 输入TCP位姿和参考关节角度,输出关节角度
int generatePayloadIdentifyTraj(const std::string &name, const TrajConfig &traj_conf)
生成用于负载辨识的激励轨迹 此接口内部调用pathBufferAppend 将离线轨迹存入buffer中,后续可通过movePathBuffer运行离线轨迹
ResultWithErrno1 calibVibrationParams(const std::vector< std::vector< double > > &q, const std::vector< std::vector< double > > &qd, const std::vector< std::vector< double > > &target_q, const std::vector< std::vector< double > > &target_qd, const std::vector< std::vector< double > > &target_qdd, const std::vector< double > &tool_offset)
振动抑制参数辨识算法接口
virtual ~RobotAlgorithm()
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
std::tuple< std::vector< std::vector< double > >, int > ResultWithErrno1
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double >, double > ForceSensorCalibResultWithError
std::tuple< double, std::vector< double >, std::vector< double >, std::vector< double > > Payload
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
std::tuple< std::vector< double >, int > ResultWithErrno