AUBO SDK  0.26.0
Loading...
Searching...
No Matches
arcs::common_interface::RobotAlgorithm Class Reference

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_
 

Detailed Description

Interfaces related to robot algorithms

Definition at line 29 of file robot_algorithm.h.

Constructor & Destructor Documentation

◆ RobotAlgorithm()

arcs::common_interface::RobotAlgorithm::RobotAlgorithm ( )

◆ ~RobotAlgorithm()

virtual arcs::common_interface::RobotAlgorithm::~RobotAlgorithm ( )
virtual

Member Function Documentation

◆ calcJacobian()

ResultWithErrno arcs::common_interface::RobotAlgorithm::calcJacobian ( const std::vector< double > &  q,
bool  base_or_end 
)

Calculate the Jacobian matrix at the robot end-effector

Parameters
qJoint angles
base_or_endReference frame: base (or end-effector) true: described in base frame false: described in end-effector frame
Returns
Whether the Jacobian matrix is valid The first parameter of the return value is the Jacobian matrix for this configuration, the second is the error code. The error code list was updated after versions 0.28.1-rc.21 and 0.29.0-alpha.25. Previously, inverse kinematics errors returned 30082. The updated error codes are: 0 - Success -23 - Inverse kinematics calculation does not converge, calculation error -24 - Inverse kinematics calculation exceeds robot limits -25 - Inverse kinematics input configuration error -26 - Inverse kinematics Jacobian calculation failed -27 - Analytical solution exists but none satisfy the selection criteria -28 - Unknown error in inverse kinematics If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
Exceptions
arcs::common_interface::AuboException
Python function prototype
calJacobian(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: bool) -> Tuple[List[float], int]
Lua function prototype
calJacobian(q: table, base_or_end: boolean) -> table
Lua example
calJ_result = calJacobian({0.58815,0.0532,0.62391,2.46,0.479,1.619},true)
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.calcJacobian","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619],true],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[0.20822779551242535,-0.5409416184208162,0.2019786999613013,0.061264982268770196,-0.026269884327316487, 0.10131708699859962,0.26388933410019777,-0.36074292664199115,0.1346954733416397,0.04085636647597124,-0.07244204452918337,0.0708466286633346, 0.0,0.10401808481666497,-0.12571344758923886,-0.07741290545882097,0.18818543519232858,0.04628646442706299,0.0,0.5548228314607867, -0.5548228314607868,0.5548228314607868,-0.7901273140338193,0.37230961532208007,0.0,-0.8319685244586092,0.8319685244586091,-0.8319685244586091, -0.5269197820578843,-0.8184088260676008,1.0,3.749399456654644e-33,-6.512048180336603e-18,1.0956823467534067e-16,-0.31313634553301894, 0.43771285536682175],0]}

◆ calibrateTcpForceSensor()

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)

Parameters
forceForce data
qJoint angles
Returns
Calibration result
Exceptions
arcs::common_interface::AuboException
Python function prototype
calibrateTcpForceSensor(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]]) -> Tuple[List[float], List[float], float, List[float]]
Lua function prototype
calibrateTcpForceSensor(force: table, q: table) -> table
Lua example
cal_table = calibrateTcpForceSensor({10.0,10.0,10.0,-1.2,-1.2,-1.2}, {3.083,1.227,1.098,0.670,-1.870,-0.397})

◆ calibrateTcpForceSensor2()

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)

Parameters
forces
poses
Returns
force_offset, com, mass, angle error
Exceptions
arcs::common_interface::AuboException

◆ calibrateTcpForceSensor3()

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

Parameters
forcesForce data
poses
mMass, unit: kg
cogCenter of gravity, unit: m, format (CoGx, CoGy, CoGz)
Returns
Calibration result
Exceptions
arcs::common_interface::AuboException

◆ calibVibrationParams()

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 
)

◆ calibWorkpieceCoordinatePara()

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)

Parameters
qJoint angles
typeCalibration type
Returns
Calculation result (workpiece coordinate pose) and error code
Exceptions
arcs::common_interface::AuboException
Python function prototype
calibWorkpieceCoordinatePara(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: int) -> Tuple[List[float], int]
Lua function prototype
calibWorkpieceCoordinatePara(q: table, type: number) -> table, number
Lua example
coord_pose,coord_num = calibWorkpieceCoordinatePara({3.083,1.227,1.098,0.670,-1.870,-0.397},1)

◆ forwardDynamics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardDynamics ( const std::vector< double > &  q,
const std::vector< double > &  torqs 
)

Forward dynamics

Parameters
qJoint angles
torqs
Returns
Calculation result and error code
Exceptions
arcs::common_interface::AuboException
Python function prototype
forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float]) -> Tuple[List[float], int]
Lua function prototype
forwardDynamics(q: table, torqs: table) -> table, number
Lua example
Dynamics, fk_result = forwardDynamics({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0})

◆ forwardDynamics1()

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

Parameters
qJoint angles
torqs
tcp_offsetTCP offset
Returns
Calculation result and error code, same as forwardDynamics
Exceptions
arcs::common_interface::AuboException
Python function prototype
forwardDynamics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
Lua function prototype
forwardDynamics1(q: table, torqs: table, tcp_offset: table) -> table, number
Lua example
Dynamics, fk_result = forwardDynamics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.0,0.0,0.0,0.0,0.0},{0.0,0.13201,0.03879,0,0,0})

◆ forwardKinematics()

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

Parameters
qJoint angles
Returns
TCP pose and whether the result is valid The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows: 0 - Success -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again) -5 - The input joint angles is invalid (dimension error)
Exceptions
arcs::common_interface::AuboException
Python function prototype
forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[List[float], int]
Lua function prototype
forwardKinematics(q: table) -> table, number
Lua example
pose, fk_result = forwardKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[0.7137448715395925,0.08416057568819092,0.6707994191515292,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}

◆ forwardKinematics1()

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

Parameters
qJoint angles
tcp_offsetTCP offset
Returns
TCP pose and whether the result is valid The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows: 0 - Success -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again) -5 - The input joint angles or tcp offset is invalid (dimension error)
Exceptions
arcs::common_interface::AuboException
Python function prototype
forwardKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float]) -> Tuple[List[float], int]
Lua function prototype
forwardKinematics1(q: table, tcp_offset: table) -> table, number
Lua example
pose, fk_result = forwardKinematics1({3.083,1.227,1.098,0.670,-1.870,-0.397},{0.0,0.13201,0.03879,0,0,0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematics1","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],[0.0, 0.13201,0.03879,0,0,0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[0.7137636726659518,0.0837705432006433,0.6710022027216355,2.459981877690872,0.4789772388601267,1.6189630435878408],0]}
Since
0.24.1

◆ forwardKinematicsAll()

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

Parameters
qJoint angles
Returns
links poses and whether the result is valid The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows: 0 - Success -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again) -5 - The input joint angles is invalid (dimension error)
Exceptions
arcs::common_interface::AuboException
Python function prototype
forwardKinematicsAll(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float]) -> Tuple[List[List[float]], int]
Lua function prototype
forwardKinematicsAll(q: table) -> table, number
Lua example
pose, fk_result = forwardKinematicsAll({3.083,1.227,1.098,0.670,-1.870,-0.397})
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardKinematicsAll","params":{"q":[-7.32945e-11,-0.261799,1.74533,0.436332,1.5708,-2.14136e-10]},"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[[0.0010004,0.0,0.122,0.0,0.0,3.141592653589793], [0.0010003999910823934,-0.12166795404953117,0.12205392567412496,1.5690838552993878,-1.3089969602251492,0.0016541204887245322], [0.10659809449330016,-0.12166124765791932,0.5161518260534821,-1.5718540206872664,0.43633111081725523,-0.002370419930605744], [0.4482255342315581,-0.1226390142692,0.3568490758201224,-0.000788980482890453,1.5665204619271216,-1.5719618592940798], [0.5519603828181741,-0.12282266347465487,0.35639753697117343,1.5707938201843654,0.0042721909279596635,1.569044569428874], [0.5513243939877184,-0.12401224959696328,0.2615193425222568,-3.1349118101994096,0.004272190926529066,1.569044569643007], [0.7494883076798231,-0.025647479212994567,-0.04023458911333461,-3.1349118101994096,0.004272190926529066,1.569044569643007]],0]}

◆ forwardToolKinematics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::forwardToolKinematics ( const std::vector< double > &  q)

Forward kinematics (ignoring TCP offset)

Parameters
qJoint angles
Returns
Flange center pose and whether the result is valid The first parameter of the return value is the forward kinematics result, the second is the error code. Error codes are as follows: 0 - Success -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again) -5 - The input joint angles is invalid (dimension error)
Lua function prototype
forwardToolKinematics(q: table) -> table, number
Lua example
pose, fk_result = forwardToolKinematics({3.083,1.227,1.098,0.670,-1.870,-0.397})
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.forwardToolKinematics","params":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[0.5881351149440136,0.05323734739426938,0.623922550656701,2.4599818776908724,0.4789772388601265,1.6189630435878408],0]}

◆ frictionModelIdentify()

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

Parameters
qJoint positions
qdJoint velocities
qddJoint accelerations
tempJoint temperatures
Returns
Whether identification succeeded
Exceptions
arcs::common_interface::AuboException
Python function prototype
frictionModelIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]], arg2: List[List[float]], arg3: List[List[float]]) -> bool
Lua function prototype
frictionModelIdentify(q: table, qd: table, qdd: table, temp: table) -> boolean
Lua example
Identify_result = frictionModelIdentify({3.083,1.227,1.098,0.670,-1.870,-0.397}, {10.0,10.0,10.0,10.0,10.0,10.0},{20.0,20.0,20.0,20.0,20.0,20.0},{30.0,30.0,30.0,30.0,30.0,30.0})

◆ generatePayloadIdentifyTraj()

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

Parameters
nameTrajectory name
traj_confJoint 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
Returns
Returns 0 on success; error code on failure AUBO_BUSY AUBO_BAD_STATE -AUBO_INVL_ARGUMENT -AUBO_BAD_STATE
Exceptions
arcs::common_interface::AuboException

◆ getPayloadIdentifyResult()

Payload arcs::common_interface::RobotAlgorithm::getPayloadIdentifyResult ( )

Get the result of payload identification

Returns
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.getPayloadIdentifyResult","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.0,[],[],[]]}

◆ inverseKinematics()

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

Parameters
qnearReference joint angles
poseTCP pose
Returns
Joint angles and whether the inverse kinematics result is valid The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows: 0 - Success -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again) -5 - The input reference joint angles or tcp pose is invalid (dimension error) -23 - Inverse kinematics calculation does not converge, calculation error -24 - Inverse kinematics calculation exceeds robot limits -25 - Inverse kinematics input configuration error -26 - Inverse kinematics Jacobian calculation failed -27 - Analytical solution exists but none satisfy the selection criteria -28 - Unknown error in inverse kinematics If the error code is not 0, the first parameter of the return value is the input reference joint angles qnear
Exceptions
arcs::common_interface::AuboException
Python function prototype
inverseKinematics(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float]) -> Tuple[List[float], int]
Lua function prototype
inverseKinematics(qnear: table, pose: table) -> table, int
Lua example
joint,ik_result = inverseKinematics({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569})
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627],0]}

◆ inverseKinematics1()

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

Parameters
qnearReference joint angles
poseTCP pose
tcp_offsetTCP offset
Returns
Joint angles and whether the result is valid, same as inverseKinematics
Exceptions
arcs::common_interface::AuboException
Python function prototype
inverseKinematics1(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: List[float], arg2: List[float]) -> Tuple[List[float], int]
Lua function prototype
inverseKinematics1(qnear: table, pose: table, tcp_offset: table) -> table, int
Lua example
joint,ik_result = inverseKinematics1({0,0,0,0,0,0},{0.81665,-0.20419,0.43873,-3.135,0.004,1.569},{0.04,-0.035,0.1,0,0,0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematics1","params":[[0,0,0,0,0,0],[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0, 0.13201,0.03879,0,0,0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782],0]}

◆ inverseKinematicsAll()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseKinematicsAll ( const std::vector< double > &  pose)

Solve all inverse kinematics solutions based on the activated TCP offset

Parameters
poseTCP pose
Returns
Joint angles and whether the result is valid The returned error code is the same as inverseKinematics
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[[3.083688522170976,1.2273215976885394,1.098072739631141,0.6705738810610149,-1.870715392248607,-0.39708546603119627], [3.081056801097411,0.17985038037652645,-1.0991717292664145,-0.4806460200109001,-1.869182975312333,-0.402066016835411], [0.4090095277807992,-0.1623365054641728,1.081775890307679,0.26993250263224805,0.9738255833642309,0.000572556627720845], [0.4116449425067969,-1.1931664523907126,-1.0822709833775688,-0.8665964106161371,0.9732141569888207,0.006484919654891586]],0]}

◆ inverseKinematicsAll1()

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

Parameters
poseTCP pose
tcp_offsetTCP offset
Returns
Joint angles and whether the result is valid, same as inverseKinematicsAll The returned error code is the same as inverseKinematics
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseKinematicsAll1","params":[[0.71374,0.08417,0.6708,2.46,0.479,1.619],[0.0, 0.13201,0.03879,0,0,0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[[3.084454549595208,1.2278265883747776,1.0986586440159576,0.6708221281915528,-1.8712459848518375,-0.3965111476861782], [3.0818224058231602,0.17980369843203092,-1.0997576631122077,-0.48102131527371267,-1.8697135490338517,-0.40149459722060593], [0.40972960018231047,-0.16226026285489026,1.0823403816496,0.2700204411869427,0.9734251963887868,0.0012903686498106507], [0.41236549588802296,-1.193621392918341,-1.0828346680836718,-0.8671097369314354,0.972815367289568,0.007206851371073478]],0]}

◆ inverseToolKinematics()

ResultWithErrno arcs::common_interface::RobotAlgorithm::inverseToolKinematics ( const std::vector< double > &  qnear,
const std::vector< double > &  pose 
)

Inverse kinematics (ignoring TCP offset)

Parameters
qnearReference joint angles
poseFlange center pose
Returns
Joint angles and whether the result is valid The first parameter of the return value is the inverse kinematics result, the second is the error code. Error codes are as follows: 0 - Success -1 - The status of the robot is incorrect (not initialized yet, you can try calling it again) -5 - The input reference joint angles or pose is invalid (dimension error)
Exceptions
arcs::common_interface::AuboException
Lua function prototype
inverseToolKinematics(qnear: table, pose: table) -> table, int
Lua example
joint, ik_result = inverseToolKinematics({0,0,0,0,0,0},{0.58815,0.0532,0.62391,2.46,0.479,1.619})
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematics","params":[[0,0,0,0,0,0],[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465],0]}

◆ inverseToolKinematicsAll()

ResultWithErrno1 arcs::common_interface::RobotAlgorithm::inverseToolKinematicsAll ( const std::vector< double > &  pose)

Inverse kinematics (ignoring TCP offset)

Parameters
qnearReference joint angles
poseFlange center pose
Returns
Joint angles and whether the result is valid
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.inverseToolKinematicsAll","params":[[0.58815,0.0532,0.62391,2.46,0.479,1.619]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[[3.083609363838651,1.22736129158332,1.098095443698268,0.6705395395487186,-1.8706605026855632,-0.39714507002376465], [3.0809781797426523,0.17987122696706134,-1.0991932793263717,-0.4807053707530958,-1.8691282890274434,-0.40212516672751814], [0.40892195618737215,-0.16235398607358653,1.081812753177426,0.27003586475871766,0.9738744130114284,0.00048462518316674287], [0.41155633414333076,-1.1932173012004512,-1.082306542045813,-0.8665312056504818,0.9732632365861417,0.0063958311601771175]],0]}

◆ pathBlend3Points()

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

Parameters
type0-movej and movej 1-movej and movel 2-movel and movej 3-movel and movel
q_startStart point before blending
q_viaBlending point
q_toEnd point after blending
rBlend radius at q_via
dSampling distance
Returns
Discrete trajectory points (x, y, z) of the blend segment at q_via in Cartesian space
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathBlend3Points(self: pyaubo_sdk.RobotAlgorithm, arg0: int, arg1: List[float], arg2: List[float], arg3: List[float], arg4: float, arg5: float) -> List[List[float]]
Lua function prototype
pathBlend3Points(type: number, q_start: table, q_via: table, q_to: table, r: number, d: number) -> table, number
Lua example
q_via , num = pathBlend3Points(1,{0.58815,0.0532,0.62391,2.46,0.479,1.619},{0.0,-0.2618,1.7453,0.4364,1.5711,0.0}, {0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.25,0.02)

◆ pathMovej()

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

Parameters
q1Start point of movej
r1Blend radius at q1
q2End point of movej
r2Blend radius at q2
dSampling distance
Returns
Discrete trajectory points (x, y, z, rx, ry, rz) between q1 and q2 in Cartesian space
Exceptions
arcs::common_interface::AuboException
Python function prototype
pathMovej(self: pyaubo_sdk.RobotAlgorithm, arg0: List[float], arg1: float, arg2: List[float], arg3: float, arg4: float) -> List[List[float]]
Lua function prototype
pathMovej(q1: table, r1: number, q2: table, r2: number, d: number) -> table, number
Lua example
path , num = pathMovej({0.0,-0.2618,1.7453,0.4364,1.5711,0.0},0.25,{0.3234,-0.5405,1.5403,0.5881,1.2962,0.7435},0.03,0.2)

◆ pathMoveS()

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

Parameters
qsSpline trajectory generation point set
dSampling distance
Returns
Exceptions
arcs::common_interface::AuboException

◆ payloadCalculateFinished()

int arcs::common_interface::RobotAlgorithm::payloadCalculateFinished ( )

Whether payload identification calculation is finished

Returns
0 if finished; 1 if in progress; <0 if failed;
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadCalculateFinished","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

◆ payloadIdentify()

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.

Parameters
data_file_no_payloadFile 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_payloadFile 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
Returns
Identification result
Exceptions
arcs::common_interface::AuboException
Python function prototype
payloadIdentify(self: pyaubo_sdk.RobotAlgorithm, arg0: List[List[float]], arg1: List[List[float]]) -> Tuple[List[float], List[float], float, List[float]]
Lua function prototype
payloadIdentify(data_with_payload: table, data_with_payload: table) -> table

◆ payloadIdentify1()

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

Parameters
dataFile path of joint data with load (.csv format), 42 columns in total, end sensor data and base data default to 0
Returns
Identification result

◆ payloadIdentifyTrajGenFinished()

int arcs::common_interface::RobotAlgorithm::payloadIdentifyTrajGenFinished ( )

Whether payload identification trajectory generation is finished

Returns
0 if finished; 1 if in progress; <0 if failed;
Exceptions
arcs::common_interface::AuboException
JSON-RPC request example
{"jsonrpc":"2.0","method":"rob1.RobotAlgorithm.payloadIdentifyTrajGenFinished","params":[],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0}

Member Data Documentation

◆ d_

void* arcs::common_interface::RobotAlgorithm::d_
protected

Definition at line 1387 of file robot_algorithm.h.


The documentation for this class was generated from the following file: