4#ifndef AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
5#define AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
12#include <aubo/global_config.h>
90 const std::vector<std::vector<double>> &forces,
91 const std::vector<std::vector<double>> &poses);
113 const std::vector<std::vector<double>> &forces,
114 const std::vector<std::vector<double>> &poses);
142 const std::vector<std::vector<double>> &forces,
143 const std::vector<std::vector<double>> &poses,
const double &mass,
144 const std::vector<double>&cog);
194 const std::string &data_file_with_payload);
335 const std::vector<std::vector<double>> &qd,
336 const std::vector<std::vector<double>> &qdd,
337 const std::vector<std::vector<double>> &temp);
385 const std::vector<std::vector<double>> &q,
int type);
431 const std::vector<double> &torqs);
479 const std::vector<double> &torqs,
480 const std::vector<double> &tcp_offset);
610 const std::vector<double> &tcp_offset);
816 const std::vector<double> &pose);
876 const std::vector<double> &pose,
877 const std::vector<double> &tcp_offset);
957 const std::vector<double> &pose);
1044 const std::vector<double> &pose,
const std::vector<double> &tcp_offset);
1099 const std::vector<double> &pose);
1303 std::vector<std::vector<double>>
pathMovej(
const std::vector<double> &q1,
1305 const std::vector<double> &q2,
1306 double r2,
double d);
1465 int type,
const std::vector<double> &q_start,
1466 const std::vector<double> &q_via,
const std::vector<double> &q_to,
1467 double r,
double d);
1577 const std::vector<std::vector<double>> &qs,
double d);
1607 const std::vector<std::vector<double>> &qd,
1608 const std::vector<std::vector<double>> &target_q,
1609 const std::vector<std::vector<double>> &target_qd,
1610 const std::vector<std::vector<double>> &target_qdd,
1611 const std::vector<double> &tool_offset);
1776 const std::string &link_name,
1777 const std::vector<std::vector<double>> &sizes,
1778 const std::vector<std::vector<double>> &poses);
1877 const std::vector<double> &end,
double r2,
double d);
1988 const std::vector<double> &end,
double r2,
double d,
1989 bool check_external_collision);
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
virtual ~RobotAlgorithm()
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)
ResultWithErrno1 calibVibrationParams1(const std::string &record_cache_name, const std::vector< double > &tool_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 removeCollisionObject(const std::string &name)
Remove a collision object by name
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 validatePath(int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d)
Validate the reachability of the robot's motion path from start point to end point without external c...
int payloadCalculateFinished()
Whether payload identification calculation is finished
int needVibrationRecalib(const VibrationRecalibrationParameter ¶m1, const VibrationRecalibrationParameter ¶m2, double threshold)
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 validatePath1(int type, const std::vector< double > &start, double r1, const std::vector< double > &end, double r2, double d, bool check_external_collision)
Validate the reachability of the robot's motion path from start point to end point,...
ResultWithErrno inverseKinematics2(const std::vector< double > &qnear, const std::vector< double > &pose)
Inverse kinematics with the same robot configuration and minimum joint change Calculate the inverse k...
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)
ForceSensorCalibResultWithError calibrateTcpForceSensor2(const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses)
Force sensor calibration algorithm (three-point calibration method)
int addCollisionBox(const std::string &name, const std::string &link_name, const std::vector< std::vector< double > > &sizes, const std::vector< std::vector< double > > &poses)
Add a box collision object
ResultWithErrno3 getRobotConfiguration(const std::vector< double > &q)
Calculate and return the corresponding robot configuration based on input joint angles
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< std::vector< double > >, int > ResultWithErrno1
std::tuple< double, std::vector< double >, std::vector< double >, std::vector< double > > Payload
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double >, double > ForceSensorCalibResultWithError
std::tuple< int, int > ResultWithErrno3
std::tuple< std::vector< double >, std::vector< double >, double, std::vector< double > > ForceSensorCalibResult
std::tuple< std::vector< double >, int > ResultWithErrno
std::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr
Trajectory configuration for payload identification.