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

#include <math.h>

Public Member Functions

 Math ()
 
virtual ~Math ()
 
std::vector< double > poseAdd (const std::vector< double > &p1, const std::vector< double > &p2)
 Pose addition
 
std::vector< double > poseSub (const std::vector< double > &p1, const std::vector< double > &p2)
 Pose subtraction
 
std::vector< double > interpolatePose (const std::vector< double > &p1, const std::vector< double > &p2, double alpha)
 Calculate linear interpolation
 
std::vector< double > poseTrans (const std::vector< double > &pose_from, const std::vector< double > &pose_from_to)
 Pose transformation
 
std::vector< double > poseTransInv (const std::vector< double > &pose_from, const std::vector< double > &pose_to_from)
 Pose inverse transformation
 
std::vector< double > poseInverse (const std::vector< double > &pose)
 Get the inverse of a pose
 
double poseDistance (const std::vector< double > &p1, const std::vector< double > &p2)
 Calculate distance between two poses
 
double poseAngleDistance (const std::vector< double > &p1, const std::vector< double > &p2)
 Calculate axis-angle difference between two poses
 
bool poseEqual (const std::vector< double > &p1, const std::vector< double > &p2, double eps=5e-5)
 Determine if two poses are equivalent
 
std::vector< double > transferRefFrame (const std::vector< double > &F_b_a_old, const Vector3d &V_in_a, int type)
 
std::vector< double > poseRotation (const std::vector< double > &pose, const std::vector< double > &rotv)
 Pose rotation
 
std::vector< double > rpyToQuaternion (const std::vector< double > &rpy)
 Euler angles to quaternions
 
std::vector< double > quaternionToRpy (const std::vector< double > &quat)
 Quaternions to euler angles
 
ResultWithErrno tcpOffsetIdentify (const std::vector< std::vector< double > > &poses)
 Four point method calibration for TCP offset
 
ResultWithErrno calibrateCoordinate (const std::vector< std::vector< double > > &poses, int type)
 Calibrate coordinate system with 3 points
 
ResultWithErrno calculateCircleFourthPoint (const std::vector< double > &p1, const std::vector< double > &p2, const std::vector< double > &p3, int mode)
 Based on three points on an arc, calculate the position of the midpoint of the other half of the fitted circle's arc
 
std::vector< double > forceTrans (const std::vector< double > &pose_a_in_b, const std::vector< double > &force_in_a)
 
std::vector< double > getDeltaPoseBySensorDistance (const std::vector< double > &distances, double position, double radius, double track_scale)
 
std::vector< double > deltaPoseTrans (const std::vector< double > &pose_a_in_b, const std::vector< double > &ft_in_a)
 
std::vector< double > deltaPoseAdd (const std::vector< double > &pose_a_in_b, const std::vector< double > &v_in_b)
 
std::vector< double > changePoseWithXYRef (const std::vector< double > &pose_tar, const std::vector< double > &pose_ref)
 
std::vector< double > homMatrixToPose (const std::vector< double > &homMatrix)
 
std::vector< double > poseToHomMatrix (const std::vector< double > &pose)
 

Protected Attributes

void * d_
 

Detailed Description

Definition at line 17 of file math.h.

Constructor & Destructor Documentation

◆ Math()

arcs::common_interface::Math::Math ( )

◆ ~Math()

virtual arcs::common_interface::Math::~Math ( )
virtual

Member Function Documentation

◆ calculateCircleFourthPoint()

ResultWithErrno arcs::common_interface::Math::calculateCircleFourthPoint ( const std::vector< double > &  p1,
const std::vector< double > &  p2,
const std::vector< double > &  p3,
int  mode 
)

Based on three points on an arc, calculate the position of the midpoint of the other half of the fitted circle's arc

Parameters
p1start point of the arc
p2middle point of the arc
p3end point of the arc
modewhen mode = 1, need to plan for orientation around arc; when mode = 0, do not need to plan for orientation around arc.
Returns
position of the midpoint of the other half of the fitted circle's arc and whether the result is valid.
Lua函数原型
calculateCircleFourthPoint(p1: table, p2: table, p3: table, mode: int)
Lua示例
center_pose, cal_result = calculateCircleFourthPoint({0.5488696249770836,-0.1214996547187204,0.2631931199112321,-3.14159198038469,-3.673205103150083e-06,1.570796326792424}, {0.5488696249770835,-0.1214996547187207,0.3599720701808493,-3.14159198038469,-3.6732051029273e-06,1.570796326792423}, {0.5488696249770836,-0.0389996547187214,0.3599720701808496,-3.141591980384691,-3.673205102557476e-06,1.570796326792422},1)
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.calculateCircleFourthPoint","params":[[0.5488696249770836,-0.1214996547187204,0.2631931199112321,-3.14159198038469,-3.673205103150083e-06,1.570796326792424], [0.5488696249770835,-0.1214996547187207,0.3599720701808493,-3.14159198038469,-3.6732051029273e-06,1.570796326792423], [0.5488696249770836,-0.0389996547187214,0.3599720701808496,-3.141591980384691,-3.673205102557476e-06, 1.570796326792422],1],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[0.5488696249770837,-0.031860179583911546,0.27033259504604207,-3.1415919803846903,-3.67320510285378e-06,1.570796326792423],1]}

◆ calibrateCoordinate()

ResultWithErrno arcs::common_interface::Math::calibrateCoordinate ( const std::vector< std::vector< double > > &  poses,
int  type 
)

Calibrate coordinate system with 3 points

Parameters
posesset of 3 poses
typetype:
0 - oxy origin, +x axis, xy plane (+y direction)
1 - oxz origin, +x axis, xz plane (+z direction)
2 - oyz origin, +y axis, yz plane (+z direction)
3 - oyx origin, +y axis, yx plane (+x direction)
4 - ozx origin, +z axis, zx plane (+x direction)
5 - ozy origin, +z axis, zy plane (+y direction)
Returns
Coordinate system calibration result and whether the calibration result is valid
Lua function prototype
calibrateCoordinate(poses: table, type: int) -> table, number
Lua example
p1 = {0.55462,0.06219,0.37175,-3.142,0.0,1.580}
p2 = {0.63746,0.11805,0.37175,-3.142,0.0,1.580}
p3 = {0.40441,0.28489,0.37174,-3.142,0.0,1.580}
p = {p1,p2,p3}
coord_pose, cal_result = calibrateCoordinate(p,0)
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.calibrateCoordinate","params":[[[0.55462,0.06219,0.37175,-3.142,0.0,1.580], [0.63746,0.11805,0.37175,-3.142,0.0,1.580],[0.40441,0.28489,0.37174,-3.142,0.0,1.580]],0],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[[0.55462,0.06219,0.37175,-3.722688983883945e-05,-1.6940658945086007e-21,0.5932768162455785],0]}

◆ changePoseWithXYRef()

std::vector< double > arcs::common_interface::Math::changePoseWithXYRef ( const std::vector< double > &  pose_tar,
const std::vector< double > &  pose_ref 
)

changePoseWithXYRef: Modify the XY axis direction of pose_tar to be as consistent as possible with pose_ref

Parameters
pose_tartarget pose to be modified
pose_refreference pose
Returns
Modified pose, using the xyz coordinates and z axis direction of pose_tar

◆ deltaPoseAdd()

std::vector< double > arcs::common_interface::Math::deltaPoseAdd ( const std::vector< double > &  pose_a_in_b,
const std::vector< double > &  v_in_b 
)

addDeltaPose: Calculate the pose after unit time given a velocity

Parameters
pose_a_in_bcurrent pose of a relative to b
v_in_bvelocity of frame a described in frame b at current time
Returns
pose_in_b, pose after unit time described in frame b

◆ deltaPoseTrans()

std::vector< double > arcs::common_interface::Math::deltaPoseTrans ( const std::vector< double > &  pose_a_in_b,
const std::vector< double > &  ft_in_a 
)

changeFTFrame: Transform the reference frame of force and torque

Parameters
pose_a_in_bpose of frame a in frame b
ft_in_aforce and torque applied at point a, described in frame a
Returns
ft_in_b, force and torque applied at point b, described in frame b

◆ forceTrans()

std::vector< double > arcs::common_interface::Math::forceTrans ( const std::vector< double > &  pose_a_in_b,
const std::vector< double > &  force_in_a 
)

forceTrans: Transform the reference frame of force and torque: force_in_b = pose_a_in_b * force_in_a

Parameters
pose_a_in_bpose of frame a in frame b
force_in_aforce and torque described in frame a
Returns
Force_in_b, force and torque described in frame b

◆ getDeltaPoseBySensorDistance()

std::vector< double > arcs::common_interface::Math::getDeltaPoseBySensorDistance ( const std::vector< double > &  distances,
double  position,
double  radius,
double  track_scale 
)

Calculate pose increment in tool coordinate system based on sensor data

Parameters
distancesN distances, N >= 3
positionreference height to maintain from the trajectory
radiuseffective radius from sensor center to tool TCP
track_scaletracking ratio, range (0, 1], 1 means faster tracking
Returns
Pose increment in tool coordinate system

◆ homMatrixToPose()

std::vector< double > arcs::common_interface::Math::homMatrixToPose ( const std::vector< double > &  homMatrix)

homMatrixToPose: Get pose from homogeneous transformation matrix

Parameters
homMatrix4x4 homogeneous transformation matrix, input elements are arranged row-wise
Returns
corresponding pose

◆ interpolatePose()

std::vector< double > arcs::common_interface::Math::interpolatePose ( const std::vector< double > &  p1,
const std::vector< double > &  p2,
double  alpha 
)

Calculate linear interpolation

Parameters
p1starting TCP pose
p2ending TCP pose
alphacoefficient; When 0<alpha<1,return a point between p1 & p2 that is closer to p1, at alpha percentage of the path; For example when alpha=0.3,point returned is closer to p1,at 30% of the total distance; When alpha>1, return p2; When alpha<0,return p1;
Returns
interpolation result
Python interface prototype
interpolatePose(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float], arg2: float) -> List[float]
Lua interface prototype
interpolatePose(p1: table, p2: table, alpha: number) -> table
Lua example
pose_interpolate = interpolatePose({0.2, 0.2, 0.4, 0, 0, 0},{0.2, 0.2, 0.6, 0, 0, 0},0.5)
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.interpolatePose","params":[[0.2, 0.2, 0.4, 0, 0, 0],[0.2, 0.2, 0.6, 0, 0, 0],0.5],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.2,0.2,0.5,0.0,-0.0,0.0]}

◆ poseAdd()

std::vector< double > arcs::common_interface::Math::poseAdd ( const std::vector< double > &  p1,
const std::vector< double > &  p2 
)

Pose addition

Both arguments contain three position parameters (x, y, z) jointly called P, and three rotation parameters (R_x, R_y, R_z) jointly called R. This function calculates the result x_3 as the addition of the given poses as follows:

p_3.P = p_1.P + p_2.P

p_3.R = p_1.R * p_2.R

Parameters
p1Tool pose 1
p2Tool pose 2
Returns
sum of position parts and product of rotation parts (pose)
Python interface prototype
poseAdd(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float]) -> List[float]
Lua interface prototype
poseAdd(p1: table, p2: table) -> table
Lua example
pose_add = poseAdd({0.2, 0.5, 0.1, 1.57, 0, 0},{0.2, 0.5, 0.6, 1.57, 0, 0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseAdd","params":[[0.2, 0.5, 0.1, 1.57, 0, 0],[0.2, 0.5, 0.6, 1.57, 0, 0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.4,1.0,0.7,3.14,-0.0,0.0]} \endengish

◆ poseAngleDistance()

double arcs::common_interface::Math::poseAngleDistance ( const std::vector< double > &  p1,
const std::vector< double > &  p2 
)

Calculate axis-angle difference between two poses

Parameters
p1pose 1
p2pose 2
Returns
axis angle difference
Lua函数原型
poseAngleDistance(p1: table, p2: table) -> number
Lua示例
pose_angle_distance = poseAngleDistance({0.1, 0.3, 0.1, 0.3142, 0.0, 1.571},{0.2, 0.5, 0.6, 0, -0.172, 0.0})

◆ poseDistance()

double arcs::common_interface::Math::poseDistance ( const std::vector< double > &  p1,
const std::vector< double > &  p2 
)

Calculate distance between two poses

Parameters
p1pose 1
p2pose 2
Returns
distance between the poses
Lua function prototype
poseDistance(p1: table, p2: table) -> number
Lua example
pose_distance = poseDistance({0.1, 0.3, 0.1, 0.3142, 0.0, 1.571},{0.2, 0.5, 0.6, 0, -0.172, 0.0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseDistance","params":[[0.1, 0.3, 0.1, 0.3142, 0.0, 1.571],[0.2, 0.5, 0.6, 0, -0.172, 0.0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0.5477225575051661}

◆ poseEqual()

bool arcs::common_interface::Math::poseEqual ( const std::vector< double > &  p1,
const std::vector< double > &  p2,
double  eps = 5e-5 
)

Determine if two poses are equivalent

Parameters
p1pose 1
p2pose 2
epserror margin
Returns
true or false
Lua函数原型
poseEqual(p1: table, p2: table, eps: number) -> boolean
Lua示例
pose_equal = poseEqual({0.1, 0.3, 0.1, 0.3142, 0.0, 1.571},{0.1, 0.3, 0.1, 0.3142, 0.0, 1.5711},0.01)
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseEqual","params":[[0.1, 0.3, 0.1, 0.3142, 0.0, 1.571],[0.1, 0.3, 0.1, 0.3142, 0.0, 1.5711],0.01],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":0.0}

◆ poseInverse()

std::vector< double > arcs::common_interface::Math::poseInverse ( const std::vector< double > &  pose)

Get the inverse of a pose

Parameters
posetool pose (spatial vector)
Returns
inverse tool pose transformation (spatial vector)
Python interface prototype
poseInverse(self: pyaubo_sdk.Math, arg0: List[float]) -> List[float]
Lua interface prototype
poseInverse(pose: table) -> table
Lua example
pose_inverse = poseInverse({0.2, 0.5, 0.1, 1.57, 0, 3.14})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseInverse","params":[[0.2, 0.5, 0.1, 1.57, 0, 3.14]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.19920341988726448,-0.09960155178838484,-0.5003973704832628, 1.5699999989900404,-0.0015926530848129354,-3.1415913853161266]}

◆ poseRotation()

std::vector< double > arcs::common_interface::Math::poseRotation ( const std::vector< double > &  pose,
const std::vector< double > &  rotv 
)

Pose rotation

Parameters
pose
rotv
Returns
Python interface prototype
poseRotation(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float]) -> List[float]
Lua interface prototype
poseRotation(pose: table, rotv: table) -> table

◆ poseSub()

std::vector< double > arcs::common_interface::Math::poseSub ( const std::vector< double > &  p1,
const std::vector< double > &  p2 
)

Pose subtraction

Both arguments contain three position parameters (x, y, z) jointly called P, and three rotation parameters (R_x, R_y, R_z) jointly called R. This function calculates the result x_3 as the addition of the given poses as follows:

p_3.P = p_1.P - p_2.P,

p_3.R = p_1.R * p_2.R.inverse

Parameters
p1tool pose 1
p2tool pose 2
Returns
difference between two poses
Python interface prototype
poseSub(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float]) -> List[float]
Lua interface prototype
poseSub(p1: table, p2: table) -> table
Lua example
pose_sub = poseSub({0.2, 0.5, 0.1, 1.57, 0, 0},{0.2, 0.5, 0.6, 1.57, 0, 0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseSub","params":[[0.2, 0.5, 0.1, 1.57, 0, 0],[0.2, 0.5, 0.6, 1.57, 0, 0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.0,0.0,-0.5,0.0,-0.0,0.0]}

◆ poseToHomMatrix()

std::vector< double > arcs::common_interface::Math::poseToHomMatrix ( const std::vector< double > &  pose)

poseToHomMatrix: Get homogeneous transformation matrix from pose

Parameters
poseinput pose
Returns
output homogeneous transformation matrix, elements arranged row-wise

◆ poseTrans()

std::vector< double > arcs::common_interface::Math::poseTrans ( const std::vector< double > &  pose_from,
const std::vector< double > &  pose_from_to 
)

Pose transformation

The first argument, p_from, is used to transform the second argument, p_from_to, and the result is then returned. This means that the result is the resulting pose, when starting at the coordinate system of p_from, and then in that coordinate system moving p_from_to.

This function can be seen in two different views. Either the function transforms, that is translates and rotates, p_from_to by the parameters of p_from. Or the function is used to get the resulting pose, when first making a move of p_from and then from there, a move of p_from_to. If the poses were regarded as transformation matrices, it would look like:

T_world->to = T_world->from * T_from->to, T_x->to = T_x->from * T_from->to

These two equations describes the foundations for pose transformation. Based on a starting pose and the pose transformation relative to the starting pose, we can get the target pose.

For example, we know pose of B relative to A, pose of C relative to B, find pose of C relative to A. param 1 is pose of B relative to A,param 2 is pose of C relative to B, the return value is the pose of C relative to A

Parameters
pose_fromstarting pose(vector in 3D space)
pose_from_topose transformation relative to starting pose(vector in 3D space)
Returns
final pose (vector in 3D space)
Python interface prototype
poseTrans(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float]) -> List[float]
Lua interface prototype
poseTrans(pose_from: table, pose_from_to: table) -> table
Lua example
pose_trans = poseTrans({0.2, 0.5, 0.1, 1.57, 0, 0},{0.2, 0.5, 0.6, 1.57, 0, 0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseTrans","params":[[0.2, 0.5, 0.1, 1.57, 0, 0],[0.2, 0.5, 0.6, 1.57, 0, 0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.4,-0.09960164640373415,0.6004776374923573,3.14,-0.0,0.0]}

◆ poseTransInv()

std::vector< double > arcs::common_interface::Math::poseTransInv ( const std::vector< double > &  pose_from,
const std::vector< double > &  pose_to_from 
)

Pose inverse transformation

Given pose of C relative to A, pose of C relative to B, find pose of B relative to A. param 1 is pose of C relative to A,param 2 is pose of C relative to B, the return value is the pose of B relative to A

Parameters
pose_fromstarting pose
pose_to_frompose transformation relative to final pose
Returns
resulting pose
Python interface prototype
poseTransInv(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float]) -> List[float]
Lua interface prototype
poseTransInv(pose_from: table, pose_to_from: table) -> table
Lua example
pose_trans_inv = poseTransInv({0.4, -0.0996016, 0.600478, 3.14, 0, 0},{0.2, 0.5, 0.6, 1.57, 0, 0})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.poseTransInv","params":[[0.4, -0.0996016, 0.600478, 3.14, 0, 0],[0.2, 0.5, 0.6, 1.57, 0, 0]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.2,0.5000000464037341,0.10000036250764266,1.57,-0.0,0.0]}

◆ quaternionToRpy()

std::vector< double > arcs::common_interface::Math::quaternionToRpy ( const std::vector< double > &  quat)

Quaternions to euler angles

Parameters
quatquaternions
Returns
euler angles
Python interface prototype
quaternionToRpy(self: pyaubo_sdk.Math, arg0: List[float]) -> List[float]
Lua interface prototype
quaternionToRpy(quat: table) -> table
Lua example
rpy = quaternionToRpy({0.834722,0.0780426, 0.451893, 0.304864})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.quaternionToRpy","params":[[0.834722, 0.0780426, 0.451893, 0.304864]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.6110000520523781,0.7849996877683915,0.960000543982093]}

◆ rpyToQuaternion()

std::vector< double > arcs::common_interface::Math::rpyToQuaternion ( const std::vector< double > &  rpy)

Euler angles to quaternions

Parameters
rpyeuler angles
Returns
quaternions
Python interface prototype
rpyToQuaternion(self: pyaubo_sdk.Math, arg0: List[float]) -> List[float]
Lua interface prototype
rpyToQuaternion(rpy: table) -> table
Lua example
quaternion = rpyToQuaternion({0.611, 0.785, 0.960})
JSON-RPC request example
{"jsonrpc":"2.0","method":"Math.rpyToQuaternion","params":[[0.611, 0.785, 0.960]],"id":1}
JSON-RPC response example
{"id":1,"jsonrpc":"2.0","result":[0.834721517970497,0.07804256900772265,0.4518931575790371,0.3048637712043723]}

◆ tcpOffsetIdentify()

ResultWithErrno arcs::common_interface::Math::tcpOffsetIdentify ( const std::vector< std::vector< double > > &  poses)

Four point method calibration for TCP offset

About a sharp point, move the robot's tcp in four different poses. Difference between each pose should be drastic. Result can be obtained based on these four poses

Parameters
posescombination of four different poses
Returns
TCP calibration result and whether successfull
Python interface prototype
tcpOffsetIdentify(self: pyaubo_sdk.Math, arg0: List[List[float]]) -> Tuple[List[float], int]
Lua interface prototype
tcpOffsetIdentify(poses: table) -> table
Lua example
p1 = {0.48659,0.10456,0.24824,-3.135,0.004,1.569}
p2 = {0.38610,0.09096,0.22432,2.552,-0.437,1.008}
p3 = {0.38610,0.05349,0.16791,-3.021,-0.981,0.517}
p4 = {0.49675,0.06417,0.21408,-2.438,0.458,0.651}
p = {p1,p2,p3,p4}
tcp_result = tcpOffsetIdentify(p)

◆ transferRefFrame()

std::vector< double > arcs::common_interface::Math::transferRefFrame ( const std::vector< double > &  F_b_a_old,
const Vector3d V_in_a,
int  type 
)

Parameters
F_b_a_old
V_in_a
type
Returns
Python interface prototype
transferRefFrame(self: pyaubo_sdk.Math, arg0: List[float], arg1: List[float[3]], arg2: int) -> List[float]
Lua interface prototype
transferRefFrame(F_b_a_old: table, V_in_a: table, type: number) -> table

Member Data Documentation

◆ d_

void* arcs::common_interface::Math::d_
protected

Definition at line 1044 of file math.h.


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