|
| | 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) |
| |
Definition at line 17 of file math.h.
| 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
-
| p1 | tool pose 1 |
| p2 | tool 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]}
| 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_from | starting pose(vector in 3D space) |
| pose_from_to | pose 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]}