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 {
46 const std::vector<std::vector<double>> &forces,
47 const std::vector<std::vector<double>> &poses);
59 const std::vector<std::vector<double>> &forces,
60 const std::vector<std::vector<double>> &poses);
86 const std::string &data_file_with_payload);
152 const std::vector<std::vector<double>> &qd,
153 const std::vector<std::vector<double>> &qdd,
154 const std::vector<std::vector<double>> &temp);
175 const std::vector<std::vector<double>> &q,
int type);
195 const std::vector<double> &torqs);
215 const std::vector<double> &torqs,
216 const std::vector<double> &tcp_offset);
271 const std::vector<double> &tcp_offset);
324 const std::vector<double> &pose);
352 const std::vector<double> &pose,
353 const std::vector<double> &tcp_offset);
398 const std::vector<double> &pose,
const std::vector<double> &tcp_offset);
417 const std::vector<double> &pose);
459 std::vector<std::vector<double>>
pathMovej(
const std::vector<double> &q1,
461 const std::vector<double> &q2,
462 double r2,
double d);
535 int type,
const std::vector<double> &q_start,
536 const std::vector<double> &q_via,
const std::vector<double> &q_to,
592 const std::vector<std::vector<double>> &qs,
double d);
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)
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运行离线轨迹
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