![]() |
AUBO SDK
0.26.0
|
Interfaces related to robot algorithms More...
#include <robot_algorithm.h>
Public Member Functions | |
| RobotAlgorithm () | |
| virtual | ~RobotAlgorithm () |
| ForceSensorCalibResult | calibrateTcpForceSensor (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses) |
| Force sensor calibration algorithm (three-point calibration method) | |
| ForceSensorCalibResultWithError | calibrateTcpForceSensor2 (const std::vector< std::vector< double > > &forces, const std::vector< std::vector< double > > &poses) |
| Force sensor calibration algorithm (three-point calibration method) | |
| 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 | |
| int | payloadIdentify (const std::string &data_file_no_payload, const std::string &data_file_with_payload) |
| Payload identification algorithm interface based on current | |
| int | payloadIdentify1 (const std::string &file_name) |
| New version of payload identification algorithm interface based on current | |
| int | payloadCalculateFinished () |
| Whether payload identification calculation is finished | |
| Payload | getPayloadIdentifyResult () |
| Get the result of payload identification | |
| 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 | |
| ResultWithErrno | calibWorkpieceCoordinatePara (const std::vector< std::vector< double > > &q, int type) |
| Workpiece coordinate calibration algorithm interface (requires correct TCP offset set before calling) Input multiple sets of joint angles and calibration type, output workpiece coordinate pose (relative to robot base) | |
| ResultWithErrno | forwardDynamics (const std::vector< double > &q, const std::vector< double > &torqs) |
| Forward dynamics | |
| 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 | forwardKinematics (const std::vector< double > &q) |
| Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input joint angles, output TCP pose | |
| 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 | forwardKinematicsAll (const std::vector< double > &q) |
| Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input joint angles, output links poses | |
| ResultWithErrno | inverseKinematics (const std::vector< double > &qnear, const std::vector< double > &pose) |
| Inverse kinematics Input TCP pose and reference joint angles, output joint angles | |
| 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 | |
| ResultWithErrno1 | inverseKinematicsAll (const std::vector< double > &pose) |
| Solve all inverse kinematics solutions based on the activated TCP offset | |
| 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) | |
| ResultWithErrno1 | inverseToolKinematicsAll (const std::vector< double > &pose) |
| Inverse kinematics (ignoring TCP offset) | |
| 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 | calcJacobian (const std::vector< double > &q, bool base_or_end) |
| Calculate the Jacobian matrix at the robot end-effector | |
| 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 | |
| int | generatePayloadIdentifyTraj (const std::string &name, const TrajConfig &traj_conf) |
| Generate excitation trajectory for payload identification This interface internally calls pathBufferAppend The offline trajectory is stored in the buffer, and can be executed later via movePathBuffer | |
| int | payloadIdentifyTrajGenFinished () |
| Whether payload identification trajectory generation is finished | |
| std::vector< std::vector< double > > | pathMoveS (const std::vector< std::vector< double > > &qs, double d) |
| Solve the trajectory points for moveS | |
| 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) |
Protected Attributes | |
| void * | d_ |
Interfaces related to robot algorithms
Definition at line 29 of file robot_algorithm.h.
| arcs::common_interface::RobotAlgorithm::RobotAlgorithm | ( | ) |
|
virtual |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::calcJacobian | ( | const std::vector< double > & | q, |
| bool | base_or_end | ||
| ) |
Calculate the Jacobian matrix at the robot end-effector
| q | Joint angles |
| base_or_end | Reference frame: base (or end-effector) true: described in base frame false: described in end-effector frame |
| arcs::common_interface::AuboException |
| ForceSensorCalibResult arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor | ( | const std::vector< std::vector< double > > & | forces, |
| const std::vector< std::vector< double > > & | poses | ||
| ) |
Force sensor calibration algorithm (three-point calibration method)
| force | Force data |
| q | Joint angles |
| arcs::common_interface::AuboException |
| ForceSensorCalibResultWithError arcs::common_interface::RobotAlgorithm::calibrateTcpForceSensor2 | ( | const std::vector< std::vector< double > > & | forces, |
| const std::vector< std::vector< double > > & | poses | ||
| ) |
Force sensor calibration algorithm (three-point calibration method)
| forces | |
| poses |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::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
| forces | Force data |
| poses | |
| m | Mass, unit: kg |
| cog | Center of gravity, unit: m, format (CoGx, CoGy, CoGz) |
| arcs::common_interface::AuboException |
| ResultWithErrno1 arcs::common_interface::RobotAlgorithm::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 | ||
| ) |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::calibWorkpieceCoordinatePara | ( | const std::vector< std::vector< double > > & | q, |
| int | type | ||
| ) |
Workpiece coordinate calibration algorithm interface (requires correct TCP offset set before calling) Input multiple sets of joint angles and calibration type, output workpiece coordinate pose (relative to robot base)
| q | Joint angles |
| type | Calibration type |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardDynamics | ( | const std::vector< double > & | q, |
| const std::vector< double > & | torqs | ||
| ) |
Forward dynamics
| q | Joint angles |
| torqs |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::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
| q | Joint angles |
| torqs | |
| tcp_offset | TCP offset |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardKinematics | ( | const std::vector< double > & | q | ) |
Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input joint angles, output TCP pose
| q | Joint angles |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardKinematics1 | ( | const std::vector< double > & | q, |
| const std::vector< double > & | tcp_offset | ||
| ) |
Forward kinematics Input joint angles, output TCP pose
| q | Joint angles |
| tcp_offset | TCP offset |
| arcs::common_interface::AuboException |
| ResultWithErrno1 arcs::common_interface::RobotAlgorithm::forwardKinematicsAll | ( | const std::vector< double > & | q | ) |
Forward kinematics, based on the activated TCP offset (the most recently set via setTcpOffset) Input joint angles, output links poses
| q | Joint angles |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardToolKinematics | ( | const std::vector< double > & | q | ) |
Forward kinematics (ignoring TCP offset)
| q | Joint angles |
| arcs::common_interface::AuboException |
| bool arcs::common_interface::RobotAlgorithm::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
| q | Joint positions |
| qd | Joint velocities |
| qdd | Joint accelerations |
| temp | Joint temperatures |
| arcs::common_interface::AuboException |
| int arcs::common_interface::RobotAlgorithm::generatePayloadIdentifyTraj | ( | const std::string & | name, |
| const TrajConfig & | traj_conf | ||
| ) |
Generate excitation trajectory for payload identification This interface internally calls pathBufferAppend The offline trajectory is stored in the buffer, and can be executed later via movePathBuffer
| name | Trajectory name |
| traj_conf | Joint trajectory constraints traj_conf.move_axis: Moving axes Since users may not want large multi-joint movements during payload identification, it is recommended to use traj_conf.move_axis=LoadIdentifyMoveAxis::Joint_4_6; traj_conf.init_joint: Initial joint angles. To avoid singularity issues near joint 5 zero position, set abs(traj_conf.init_joint[4]) >= 0.3(rad), preferably close to 1.57(rad). Other joints can be set arbitrarily. traj_conf.lower_joint_bound, traj_conf.upper_joint_bound: Joint angle limits, dimensions should match config.move_axis. Recommended: upper_joint_bound=2, lower_joint_bound=-2 config.max_velocity, config.max_acceleration: Joint velocity and acceleration limits, dimensions should match config.move_axis. For safety and driver performance, recommended: max_velocity=3, max_acceleration=5 |
| arcs::common_interface::AuboException |
| Payload arcs::common_interface::RobotAlgorithm::getPayloadIdentifyResult | ( | ) |
Get the result of payload identification
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::inverseKinematics | ( | const std::vector< double > & | qnear, |
| const std::vector< double > & | pose | ||
| ) |
Inverse kinematics Input TCP pose and reference joint angles, output joint angles
| qnear | Reference joint angles |
| pose | TCP pose |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::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
| qnear | Reference joint angles |
| pose | TCP pose |
| tcp_offset | TCP offset |
| arcs::common_interface::AuboException |
| ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseKinematicsAll | ( | const std::vector< double > & | pose | ) |
Solve all inverse kinematics solutions based on the activated TCP offset
| pose | TCP pose |
| arcs::common_interface::AuboException |
| ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseKinematicsAll1 | ( | const std::vector< double > & | pose, |
| const std::vector< double > & | tcp_offset | ||
| ) |
Solve all inverse kinematics solutions based on the provided TCP offset
| pose | TCP pose |
| tcp_offset | TCP offset |
| arcs::common_interface::AuboException |
| ResultWithErrno arcs::common_interface::RobotAlgorithm::inverseToolKinematics | ( | const std::vector< double > & | qnear, |
| const std::vector< double > & | pose | ||
| ) |
Inverse kinematics (ignoring TCP offset)
| qnear | Reference joint angles |
| pose | Flange center pose |
| arcs::common_interface::AuboException |
| ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseToolKinematicsAll | ( | const std::vector< double > & | pose | ) |
Inverse kinematics (ignoring TCP offset)
| qnear | Reference joint angles |
| pose | Flange center pose |
| arcs::common_interface::AuboException |
| std::vector< std::vector< double > > arcs::common_interface::RobotAlgorithm::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
| type | 0-movej and movej 1-movej and movel 2-movel and movej 3-movel and movel |
| q_start | Start point before blending |
| q_via | Blending point |
| q_to | End point after blending |
| r | Blend radius at q_via |
| d | Sampling distance |
| arcs::common_interface::AuboException |
| std::vector< std::vector< double > > arcs::common_interface::RobotAlgorithm::pathMovej | ( | const std::vector< double > & | q1, |
| double | r1, | ||
| const std::vector< double > & | q2, | ||
| double | r2, | ||
| double | d | ||
| ) |
Solve the trajectory points between movej
| q1 | Start point of movej |
| r1 | Blend radius at q1 |
| q2 | End point of movej |
| r2 | Blend radius at q2 |
| d | Sampling distance |
| arcs::common_interface::AuboException |
| std::vector< std::vector< double > > arcs::common_interface::RobotAlgorithm::pathMoveS | ( | const std::vector< std::vector< double > > & | qs, |
| double | d | ||
| ) |
Solve the trajectory points for moveS
pathMoveS
| qs | Spline trajectory generation point set |
| d | Sampling distance |
| arcs::common_interface::AuboException |
| int arcs::common_interface::RobotAlgorithm::payloadCalculateFinished | ( | ) |
Whether payload identification calculation is finished
| arcs::common_interface::AuboException |
| int arcs::common_interface::RobotAlgorithm::payloadIdentify | ( | const std::string & | data_file_no_payload, |
| const std::string & | data_file_with_payload | ||
| ) |
Payload identification algorithm interface based on current
Requires collecting position, velocity, and current data when running the excitation trajectory without load, as well as with load.
| data_file_no_payload | File path of joint data when running the excitation trajectory without load (.csv format), 18 columns in total: 6 joint positions, 6 joint velocities, 6 joint currents |
| data_file_with_payload | File path of joint data when running the excitation trajectory with load (.csv format), 18 columns in total: 6 joint positions, 6 joint velocities, 6 joint currents |
| arcs::common_interface::AuboException |
| int arcs::common_interface::RobotAlgorithm::payloadIdentify1 | ( | const std::string & | file_name | ) |
New version of payload identification algorithm interface based on current
Requires collecting at least three points of position, velocity, acceleration, current, temperature, end sensor data, and base data when running with load
| data | File path of joint data with load (.csv format), 42 columns in total, end sensor data and base data default to 0 |
| int arcs::common_interface::RobotAlgorithm::payloadIdentifyTrajGenFinished | ( | ) |
Whether payload identification trajectory generation is finished
| arcs::common_interface::AuboException |
|
protected |
Definition at line 1387 of file robot_algorithm.h.