4 #ifndef AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H 5 #define AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H 12 #include <aubo/global_config.h> 16 namespace 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);
85 int payloadIdentify(
const std::string &data_file_no_payload,
86 const std::string &data_file_with_payload);
98 int payloadIdentify1(
const std::string &file_name);
113 int payloadCalculateFinished();
128 Payload getPayloadIdentifyResult();
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);
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);
416 ResultWithErrno inverseToolKinematics(
const std::vector<double> &qnear,
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);
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,
563 int generatePayloadIdentifyTraj(
const std::string &name,
579 int payloadIdentifyTrajGenFinished();
591 std::vector<std::vector<double>> pathMoveS(
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) 632 #endif // AUBO_SDK_ROBOT_ALGORITHM_INTERFACE_H
std::tuple< std::vector< double >, int > ResultWithErrno
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 >> 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::shared_ptr< RobotAlgorithm > RobotAlgorithmPtr