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);
791 const std::vector<double> &pose);
850 const std::vector<double> &pose,
851 const std::vector<double> &tcp_offset);
936 const std::vector<double> &pose,
const std::vector<double> &tcp_offset);
990 const std::vector<double> &pose);
1082 std::vector<std::vector<double>>
pathMovej(
const std::vector<double> &q1,
1084 const std::vector<double> &q2,
1085 double r2,
double d);
1242 int type,
const std::vector<double> &q_start,
1243 const std::vector<double> &q_via,
const std::vector<double> &q_to,
1244 double r,
double d);
1351 const std::vector<std::vector<double>> &qs,
double d);
1380 const std::vector<std::vector<double>> &qd,
1381 const std::vector<std::vector<double>> &target_q,
1382 const std::vector<std::vector<double>> &target_qd,
1383 const std::vector<std::vector<double>> &target_qdd,
1384 const std::vector<double> &tool_offset);
Interfaces related to robot algorithms
std::vector< std::vector< double > > pathMovej(const std::vector< double > &q1, double r1, const std::vector< double > &q2, double r2, double d)
Solve the trajectory points between movej
ResultWithErrno forwardDynamics1(const std::vector< double > &q, const std::vector< double > &torqs, const std::vector< double > &tcp_offset)
Forward dynamics based on the given TCP offset
ResultWithErrno calibrateTcpForceSensor3(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses, const double &mass, const std::vector< double > &cog)
Force sensor offset calibration algorithm
ResultWithErrno forwardKinematics1(const std::vector< double > &q, const std::vector< double > &tcp_offset)
Forward kinematics Input joint angles, output TCP pose
ResultWithErrno forwardToolKinematics(const std::vector< double > &q)
Forward kinematics (ignoring TCP offset)
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)
Solve the blended trajectory points
ResultWithErrno calibWorkpieceCoordinatePara(const std::vector< std::vector< double > > &q, int type)
Workpiece coordinate calibration algorithm interface (requires correct TCP offset set before calling)...
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)
Joint friction model identification algorithm interface
int payloadIdentify1(const std::string &file_name)
New version of payload identification algorithm interface based on current
ResultWithErrno inverseKinematics1(const std::vector< double > &qnear, const std::vector< double > &pose, const std::vector< double > &tcp_offset)
Inverse kinematics Input TCP pose and reference joint angles, output joint angles
int payloadCalculateFinished()
Whether payload identification calculation is finished
Payload getPayloadIdentifyResult()
Get the result of payload identification
ResultWithErrno forwardDynamics(const std::vector< double > &q, const std::vector< double > &torqs)
Forward dynamics
ResultWithErrno1 inverseKinematicsAll1(const std::vector< double > &pose, const std::vector< double > &tcp_offset)
Solve all inverse kinematics solutions based on the provided TCP offset
ResultWithErrno inverseToolKinematics(const std::vector< double > &qnear, const std::vector< double > &pose)
Inverse kinematics (ignoring TCP offset)
std::vector< std::vector< double > > pathMoveS(const std::vector< std::vector< double > > &qs, double d)
Solve the trajectory points for moveS
ResultWithErrno calcJacobian(const std::vector< double > &q, bool base_or_end)
Calculate the Jacobian matrix at the robot end-effector
int payloadIdentify(const std::string &data_file_no_payload, const std::string &data_file_with_payload)
Payload identification algorithm interface based on current
ResultWithErrno1 inverseKinematicsAll(const std::vector< double > &pose)
Solve all inverse kinematics solutions based on the activated TCP offset
ResultWithErrno1 inverseToolKinematicsAll(const std::vector< double > &pose)
Inverse kinematics (ignoring TCP offset)
ResultWithErrno forwardKinematics(const std::vector< double > &q)
Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input ...
ForceSensorCalibResult calibrateTcpForceSensor(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
Force sensor calibration algorithm (three-point calibration method)
int payloadIdentifyTrajGenFinished()
Whether payload identification trajectory generation is finished
ResultWithErrno inverseKinematics(const std::vector< double > &qnear, const std::vector< double > &pose)
Inverse kinematics Input TCP pose and reference joint angles, output joint angles
int generatePayloadIdentifyTraj(const std::string &name, const TrajConfig &traj_conf)
Generate excitation trajectory for payload identification This interface internally calls pathBufferA...
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)
Force sensor calibration algorithm (three-point calibration method)
ResultWithErrno1 forwardKinematicsAll(const std::vector< double > &q)
Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input ...
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
Trajectory configuration for payload identification.