libalmath
2.5.7.1
|
Functions | |
std::vector< Pose2D > | AL::Math::getDubinsSolutions (const Pose2D &pTargetPose, const float pCircleRadius) |
Get the dubins solutions. More... | |
void | AL::Math::modulo2PIInPlace (float &pAngle) |
Set an angle between ]-PI, PI]. More... | |
float | AL::Math::modulo2PI (float pAngle) |
Return an angle between ]-PI, PI]. More... | |
float | AL::Math::meanAngle (const std::vector< float > &pAngles) |
Returns the mean of given angles (between ]-PI, PI]). It is defined by the direction of the mean of all unitary vectors corresponding to the given angles. If that mean vector is a null vector, then the angular mean is not defined and the method will throw. For example, meanAngle([0, PI]) throws. More... | |
float | AL::Math::weightedMeanAngle (const std::vector< float > &pAngles, const std::vector< float > &pWeights) |
Returns the weighted mean of given angles (between ]-PI, PI]). It is defined by the direction of the mean of all unitary vectors corresponding to the given angles, multiplied by the given weights. If that mean vector is a null vector, then the angular mean is not defined and the method will throw. For example, meanAngle([0, PI], [1.0, 1.0]) throws. More... | |
bool | AL::Math::clipData (const float &pMin, const float &pMax, float &pData) |
Clip an input data inside min and max limit. More... | |
void | AL::Math::changeReferencePose2D (const float &pTheta, const Pose2D &pPosIn, Pose2D &pPosOut) |
void | AL::Math::changeReferencePose2DInPlace (const float &pTheta, Pose2D &pPosOut) |
Change orientation of a Pose2D in place. More... | |
Position6D | AL::Math::position6DFromVelocity6D (const Velocity6D &pVel) |
Create a Position6D from a Velocity6D More... | |
void | AL::Math::position2DFromPose2DInPlace (const Pose2D &pPose2D, Position2D &pPosition2D) |
Compute a Position2D from a Pose2D. The theta member of the Pose2D is not taken into account. More... | |
Position2D | AL::Math::position2DFromPose2D (const Pose2D &pPose2D) |
Create a Position2D from a Pose2D More... | |
Position3D | AL::Math::position3DFromPosition6D (const Position6D &pPosition6D) |
Create a Position3D from a Position6D More... | |
Position3D | AL::Math::operator* (const Rotation &pRot, const Position3D &pPos) |
Overloading of operator * between Rotation and Position3D: More... | |
Position3D | AL::Math::operator* (const Quaternion &pQuat, const Position3D &pPos) |
Overloading of operator * between Quaternion and Position3D More... | |
Velocity6D | AL::Math::operator* (const float pVal, const Position6D &pPos) |
Overloading of operator * for float to Position6D, give a Velocity6D: More... | |
Velocity3D | AL::Math::operator* (const float pVal, const Position3D &pPos) |
Overloading of operator * for float to Position3D, give a Velocity3D: More... | |
Velocity3D | AL::Math::operator* (const Rotation &pRot, const Velocity3D &pVel) |
Overloading of operator * between Rotation and Velocity3D: More... | |
Rotation | AL::Math::rotationFromAngleDirection (const float &pTheta, const Position3D &pPos) |
Creates a 3*3 Rotation Matrix from a an angle and a normalized Position3D. More... | |
void | AL::Math::position6DFromPose2DInPlace (const Pose2D &pPose2D, Position6D &pPosition6D) |
Compute a Position6D from a Pose2D. More... | |
Position6D | AL::Math::position6DFromPose2D (const Pose2D &pPose2D) |
Create a Position6D from a Pose2D. More... | |
void | AL::Math::position6DFromPosition3DInPlace (const Position3D &pPosition3D, Position6D &pPosition6D) |
Compute a Position6D from a Position3D. More... | |
Position6D | AL::Math::position6DFromPosition3D (const Position3D &pPosition3D) |
Create a Position6D from a Position3D. More... | |
void | AL::Math::pose2DFromPosition6DInPlace (const Position6D &pPosition6D, Pose2D &pPose2D) |
Compute a Pose2D from a Position6D. More... | |
Pose2D | AL::Math::pose2DFromPosition6D (const Position6D &pPosition6D) |
Create a Pose2D from a Position6D. More... | |
void | AL::Math::pose2DFromPosition2DInPlace (const Position2D &pPosition2D, const float pAngle, Pose2D &pPose2D) |
Compute a Pose2D from a Position2D. pPose2D.x = pPosition2D.x pPose2D.y = pPosition2D.y pPose2D.theta = pAngle More... | |
Pose2D | AL::Math::pose2DFromPosition2D (const Position2D &pPosition2D, const float pAngle=0.0f) |
Create a Pose2D from a Position2D. More... | |
Position2D | AL::Math::operator* (const Pose2D &pVal, const Position2D &pPos) |
Overloading of operator * for Pose2D to Position2D, give a Position2D: More... | |
void | AL::Math::quaternionFromRotation3D (const Rotation3D &pRot3D, Quaternion &pQuaternion) |
Create a Quaternion from a Rotation3D when composed in the following order: Rz(wz) * Ry(wy) * Rx(wx) More... | |
void | AL::Math::rotationFromQuaternion (const Quaternion &pQua, Rotation &pRot) |
Create a Rotation Matrix from a Quaternion More... | |
void | AL::Math::rotation3DFromQuaternion (const Quaternion &pQuaterion, Rotation3D &pRot3D) |
Create a Rotation3D from a Quaternion when composed in the following order: Rz(wz) * Ry(wy) * Rx(wx) More... | |
void | AL::Math::quaternionPosition3DFromPosition6D (const Position6D &pPos6D, Quaternion &pQua, Position3D &pPos3D) |
Convert a Position6D to Quaternion and Position3D More... | |
void | AL::Math::pointMassRotationalInertia (float pMass, const Position3D &pPos, std::vector< float > &pInertia) |
Return the rotational inertia, expressed at the origin, of a point mass located at pPos. The inertia value is More... | |
void | AL::Math::transformLogarithmInPlace (const Transform &pT, Velocity6D &pVel) |
Compute the logarithme of a transform. Angle must be between More... | |
Velocity6D | AL::Math::transformLogarithm (const Transform &pT) |
Compute the logarithme of a transform. Angle must be between More... | |
Transform | AL::Math::velocityExponential (const Velocity6D &pVel) |
void | AL::Math::changeReferenceVelocity6D (const Transform &pT, const Velocity6D &pVelIn, Velocity6D &pVelOut) |
void | AL::Math::changeReferencePosition6D (const Transform &pT, const Position6D &pPosIn, Position6D &pPosOut) |
void | AL::Math::changeReferencePosition3D (const Transform &pT, const Position3D &pPosIn, Position3D &pPosOut) |
void | AL::Math::changeReferenceTransposePosition3D (const Transform &pT, const Position3D &pPosIn, Position3D &pPosOut) |
void | AL::Math::changeReferenceTransform (const Transform &pT, const Transform &pTIn, Transform &pTOut) |
void | AL::Math::changeReferenceTransposeTransform (const Transform &pT, const Transform &pTIn, Transform &pTOut) |
void | AL::Math::changeReferenceTransposeVelocity6D (const Transform &pT, const Velocity6D &pVelIn, Velocity6D &pVelOut) |
void | AL::Math::changeReferenceTransposePosition6D (const Transform &pT, const Position6D &pPosIn, Position6D &pPosOut) |
void | AL::Math::transformMeanInPlace (const Transform &pTIn1, const Transform &pTIn2, const float &pVal, Transform &pTOut) |
Preform a logarithmic mean of pTIn1 and pTIn2 and put it in pTout. More... | |
Transform | AL::Math::transformMean (const Transform &pTIn1, const Transform &pTIn2, const float &pVal=0.5f) |
Preform a logarithmic mean of pTIn1 and pTIn2. More... | |
Transform | AL::Math::transformFromRotationPosition3D (const Rotation &pRot, const float &pX, const float &pY, const float &pZ) |
Create a Transform from 3D cartesian coordiantes and a Rotation. More... | |
Transform | AL::Math::transformFromRotationPosition3D (const Rotation &pRot, const Position3D &pPos) |
Create a Transform from a Position3D and a Rotation. More... | |
void | AL::Math::transformFromPosition3DInPlace (const Position3D &pPosition, Transform &pTransform) |
Modify pTransform to set the translation part to pPosition. More... | |
Transform | AL::Math::transformFromPosition3D (const Position3D &pPosition) |
Create a 4*4 transform matrix from cartesian coordinates given in pPosition. More... | |
void | AL::Math::transformFromRotationInPlace (const Rotation &pRotation, Transform &pTransform) |
Modify the rotation part of the transform. The translation part of the transform is not modified. More... | |
Transform | AL::Math::transformFromRotation (const Rotation &pRotation) |
void | AL::Math::rotationFromTransformInPlace (const Transform &pTransform, Rotation &pRotation) |
Extract the position coordinates from a Transform. More... | |
Rotation | AL::Math::rotationFromTransform (const Transform &pTransform) |
Rotation3D | AL::Math::rotation3DFromRotation (const Rotation &pRotation) |
return 3 angles which result in the equivalent rotation when composed in the following order: Rz(wz) * Ry(wy) * Rx(wx) = R More... | |
Rotation | AL::Math::rotationFromAxesXY (const Position3D &pX, const Position3D &pY) |
return a Rotation Matrix initialized with its direction vectors X and Y in world coordinates. These vectors represent, respectively, the first and second columns of the Rotation matrix. The vectors must be unitary and orthogonal. More... | |
Rotation | AL::Math::rotationFromAxesXZ (const Position3D &pX, const Position3D &pZ) |
return a Rotation Matrix initialized with its direction vectors X and Z in world coordinates. These vectors represent, respectively, the first and third columns of the Rotation matrix. The vectors must be unitary and orthogonal. More... | |
Rotation | AL::Math::rotationFromAxesYZ (const Position3D &pY, const Position3D &pZ) |
return a Rotation Matrix initialized with its direction vectors X and Y in world coordinates. These vectors represent, respectively, the second and third columns of the Rotation matrix. The vectors must be unitary and orthogonal. More... | |
Rotation | AL::Math::rotationFromAxesXYZ (const Position3D &pX, const Position3D &pY, const Position3D &pZ) |
return a Rotation Matrix initialized with its direction vectors in world coordinates. The vectors represent the columns of the Rotation matrix. The vectors must be unitary and orthogonal. More... | |
void | AL::Math::position6DFromTransformInPlace (const Transform &pT, Position6D &pPos) |
Compute Position6D corresponding to the Transform. More... | |
Position6D | AL::Math::position6DFromTransform (const Transform &pT) |
Compute Position6D corresponding to 4*4 Homogenous Transform. More... | |
void | AL::Math::transformFromPose2DInPlace (const Pose2D &pPose, Transform &pT) |
Compute a Transform from a Pose2D. More... | |
Transform | AL::Math::transformFromPose2D (const Pose2D &pPose) |
Create a Transform from a Pose2D. More... | |
void | AL::Math::pose2DFromTransformInPlace (const Transform &pT, Pose2D &pPos) |
Compute a Pose2D from a Transform. More... | |
Pose2D | AL::Math::pose2DFromTransform (const Transform &pT) |
Create a Pose2D from a Transform. More... | |
void | AL::Math::position2DFromTransformInPlace (const Transform &pT, Position2D &pPos) |
Compute a Position2D from a Transform. More... | |
Position2D | AL::Math::position2DFromTransform (const Transform &pT) |
Create a Position2D from a Transform. More... | |
Transform | AL::Math::transformFromRotation3D (const Rotation3D &pRotation) |
Create a Transform from the 3 angles stored in a Rotation3D. The angles are composed in the following order: Rz(wz) * Ry(wy) * Rx(wx) = R More... | |
Transform | AL::Math::transformFromPosition6D (const Position6D &pPosition6D) |
Create a Transform from a Position6D. More... | |
void | AL::Math::position6DFromTransformDiffInPlace (const Transform &pCurrent, const Transform &pTarget, Position6D &result) |
Computes a 6 differential motion required to move from a 4*4 Homogenous transform matrix Current to a 4*4 Homogenous transform matrix target. More... | |
Position6D | AL::Math::position6DFromTransformDiff (const Transform &pCurrent, const Transform &pTarget) |
Computes a 6 differential motion require to move from a 4*4 Homogenous transform matrix Current to a 4*4 Homogenous transform matrix target. More... | |
void | AL::Math::position3DFromTransformInPlace (const Transform &pT, Position3D &pPos) |
Compute a Position3D from a Transform. More... | |
Position3D | AL::Math::position3DFromTransform (const Transform &pT) |
Create a Position3D from a Transform. More... | |
Rotation3D | AL::Math::rotation3DFromTransform (const Transform &pT) |
Create a Rotation3D (Roll, Pitch, Yaw) corresponding to the rotational part of the Transform. R = Rz(wz) * Ry(wy) * Rx(wx) More... | |
void | AL::Math::transformFromRotVecInPlace (const int pAxis, const float pTheta, const Position3D &pPos, Transform &pT) |
Compute a Transform from More... | |
Transform | AL::Math::transformFromRotVec (const int pAxis, const float pTheta, const Position3D &pPos) |
void | AL::Math::transformFromRotVecInPlace (const Position3D &pPos, Transform &pT) |
Transform | AL::Math::transformFromRotVec (const Position3D &pPos) |
Transform | AL::Math::transformFromRotVec (const int &pAxis, const float &pTheta) |
const bool | AL::Math::avoidFootCollision (const std::vector< Position2D > &pLFootBoundingBox, const std::vector< Position2D > &pRFootBoundingBox, const bool &pIsLeftSupport, Pose2D &pMove) |
Compute the best position(orientation) of the foot to avoid collision. More... | |
const bool | AL::Math::clipFootWithEllipse (const float &pMaxFootX, const float &pMaxFootY, Pose2D &pMove) |
Clip foot move with ellipsoid function More... | |
static Pose2D | AL::Math::Pose2D::fromPolarCoordinates (const float pRadius, const float pAngle) |
Create a Pose2D from polar coordinates. More... | |
const bool AL::Math::avoidFootCollision | ( | const std::vector< Position2D > & | pLFootBoundingBox, |
const std::vector< Position2D > & | pRFootBoundingBox, | ||
const bool & | pIsLeftSupport, | ||
Pose2D & | pMove | ||
) |
Compute the best position(orientation) of the foot to avoid collision.
pLFootBoundingBox | vector<Position2D> of the left footBoundingBox. |
pRFootBoundingBox | vector<Position2D> of the right footBoundingBox. |
pIsLeftSupport | Bool true if left is the support leg. |
pMove | the desired and return Pose2D. |
void AL::Math::changeReferencePose2D | ( | const float & | pTheta, |
const Pose2D & | pPosIn, | ||
Pose2D & | pPosOut | ||
) |
void AL::Math::changeReferencePose2DInPlace | ( | const float & | pTheta, |
Pose2D & | pPosOut | ||
) |
void AL::Math::changeReferencePosition3D | ( | const Transform & | pT, |
const Position3D & | pPosIn, | ||
Position3D & | pPosOut | ||
) |
pT | the given Transform |
pPosIn | a Position3D containing the position to change |
pPosOut | a Position3D containing the changed position |
void AL::Math::changeReferencePosition6D | ( | const Transform & | pT, |
const Position6D & | pPosIn, | ||
Position6D & | pPosOut | ||
) |
pT | the given Transform |
pPosIn | a Position6D containing the position to change |
pPosOut | a Position6D containing the changed position |
void AL::Math::changeReferenceTransform | ( | const Transform & | pT, |
const Transform & | pTIn, | ||
Transform & | pTOut | ||
) |
void AL::Math::changeReferenceTransposePosition3D | ( | const Transform & | pT, |
const Position3D & | pPosIn, | ||
Position3D & | pPosOut | ||
) |
pT | the given Transform |
pPosIn | a Position3D containing the position to change |
pPosOut | a Position3D containing the changed position |
void AL::Math::changeReferenceTransposePosition6D | ( | const Transform & | pT, |
const Position6D & | pPosIn, | ||
Position6D & | pPosOut | ||
) |
pT | the given Transform |
pPosIn | a Position6D containing the position to change |
pPosOut | a Position6D containing the changed position |
void AL::Math::changeReferenceTransposeTransform | ( | const Transform & | pT, |
const Transform & | pTIn, | ||
Transform & | pTOut | ||
) |
void AL::Math::changeReferenceTransposeVelocity6D | ( | const Transform & | pT, |
const Velocity6D & | pVelIn, | ||
Velocity6D & | pVelOut | ||
) |
pT | the given Transform |
pVelIn | a Velocity6D containing the velocity to change |
pVelOut | a Velocity6D containing the changed velocity |
void AL::Math::changeReferenceVelocity6D | ( | const Transform & | pT, |
const Velocity6D & | pVelIn, | ||
Velocity6D & | pVelOut | ||
) |
pT | the given Transform |
pVelIn | a Velocity6D containing the velocity to change |
pVelOut | a Velocity6D containing the changed velocity |
bool AL::Math::clipData | ( | const float & | pMin, |
const float & | pMax, | ||
float & | pData | ||
) |
Clip an input data inside min and max limit.
pMin | the min limit |
pMax | the max limit |
pData | the clipped data |
const bool AL::Math::clipFootWithEllipse | ( | const float & | pMaxFootX, |
const float & | pMaxFootY, | ||
Pose2D & | pMove | ||
) |
Clip foot move with ellipsoid function
pMaxFootX | float of the max step along x axis. |
pMaxFootY | float of the max step along y axis. |
pMove | the desired and return Pose2D. |
|
static |
std::vector<Pose2D> AL::Math::getDubinsSolutions | ( | const Pose2D & | pTargetPose, |
const float | pCircleRadius | ||
) |
Get the dubins solutions.
pTargetPose | the target pose |
pCircleRadius | the circle radius |
float AL::Math::meanAngle | ( | const std::vector< float > & | pAngles | ) |
Returns the mean of given angles (between ]-PI, PI]). It is defined by the direction of the mean of all unitary vectors corresponding to the given angles. If that mean vector is a null vector, then the angular mean is not defined and the method will throw. For example, meanAngle([0, PI]) throws.
pAngles | the input/output angles |
float AL::Math::modulo2PI | ( | float | pAngle | ) |
Return an angle between ]-PI, PI].
pAngle | the input angle |
void AL::Math::modulo2PIInPlace | ( | float & | pAngle | ) |
Set an angle between ]-PI, PI].
pAngle | the input/output angle |
Position3D AL::Math::operator* | ( | const Rotation & | pRot, |
const Position3D & | pPos | ||
) |
Overloading of operator * between Rotation and Position3D:
pRot | the given Rotation |
pPos | the given Position3D |
Position3D AL::Math::operator* | ( | const Quaternion & | pQuat, |
const Position3D & | pPos | ||
) |
Overloading of operator * between Quaternion and Position3D
pQuat | the given Quaternion |
pPos | the given Position3D |
Velocity6D AL::Math::operator* | ( | const float | pVal, |
const Position6D & | pPos | ||
) |
Overloading of operator * for float to Position6D, give a Velocity6D:
pVal | the given float |
pPos | the given Position6D |
Velocity3D AL::Math::operator* | ( | const float | pVal, |
const Position3D & | pPos | ||
) |
Overloading of operator * for float to Position3D, give a Velocity3D:
pVal | the given float |
pPos | the given Position3D |
Velocity3D AL::Math::operator* | ( | const Rotation & | pRot, |
const Velocity3D & | pVel | ||
) |
Overloading of operator * between Rotation and Velocity3D:
pRot | the given Rotation |
pVel | the given Velocity3D |
Position2D AL::Math::operator* | ( | const Pose2D & | pVal, |
const Position2D & | pPos | ||
) |
Overloading of operator * for Pose2D to Position2D, give a Position2D:
pVal | the given Pose2D |
pPos | the given Position2D |
void AL::Math::pointMassRotationalInertia | ( | float | pMass, |
const Position3D & | pPos, | ||
std::vector< float > & | pInertia | ||
) |
Return the rotational inertia, expressed at the origin, of a point mass located at pPos. The inertia value is
pMass | mass of the point |
pPos | position of the point |
pInertia | a vector of size 9, rotational inertia matrix of the point mass, expressed at the origin |
Thanks to the Huygens–Steiner theorem, this function can be used to change the reference of a rigid-body (non-necessarily punctual) rotational inertia matrix:
typedef std::vector<float> Inertia; float mass = ...; Inertia inertiaAtCom = ...; AL::Math::Position3d comPosition = ...; Inertia inertiaAtOrigin; // first compute the contribution of the translation pointMassRotationalInertia(mass, comPosition, inertiaAtOrigin); // then add the "proper" body inertia std::transform(inertiaAtCom.begin(), inertiaAtCom.end(), inertiaAtOrigin.begin(), inertiaAtOrigin.begin(), std::plus<float>());
Pose2D AL::Math::pose2DFromPosition2D | ( | const Position2D & | pPosition2D, |
const float | pAngle = 0.0f |
||
) |
Create a Pose2D from a Position2D.
pPosition2D | the Position2D you want to extract |
pAngle | the angle in radians to set the new Pose2D to |
void AL::Math::pose2DFromPosition2DInPlace | ( | const Position2D & | pPosition2D, |
const float | pAngle, | ||
Pose2D & | pPose2D | ||
) |
Compute a Pose2D from a Position2D. pPose2D.x = pPosition2D.x pPose2D.y = pPosition2D.y pPose2D.theta = pAngle
pPosition2D | the Position2D you want to extract |
pAngle | the angle in radians to set pPose2d to |
pPose2D | the result Pose2D |
Pose2D AL::Math::pose2DFromPosition6D | ( | const Position6D & | pPosition6D | ) |
Create a Pose2D from a Position6D.
pPosition6D | the position6d you want to extract |
void AL::Math::pose2DFromPosition6DInPlace | ( | const Position6D & | pPosition6D, |
Pose2D & | pPose2D | ||
) |
Compute a Pose2D from a Position6D.
pPosition6D | the Position6D you want to extract |
pPose2D | the result Pose2D |
Pose2D AL::Math::pose2DFromTransform | ( | const Transform & | pT | ) |
void AL::Math::pose2DFromTransformInPlace | ( | const Transform & | pT, |
Pose2D & | pPos | ||
) |
Position2D AL::Math::position2DFromPose2D | ( | const Pose2D & | pPose2D | ) |
void AL::Math::position2DFromPose2DInPlace | ( | const Pose2D & | pPose2D, |
Position2D & | pPosition2D | ||
) |
Compute a Position2D from a Pose2D. The theta member of the Pose2D is not taken into account.
pPose2D | the Pose2D to extract |
pPosition2D | the result Position2D |
Position2D AL::Math::position2DFromTransform | ( | const Transform & | pT | ) |
Create a Position2D from a Transform.
pT | the transform you want to extract |
void AL::Math::position2DFromTransformInPlace | ( | const Transform & | pT, |
Position2D & | pPos | ||
) |
Compute a Position2D from a Transform.
pT | the Transform you want to extract |
pPos | the result Position2D |
Position3D AL::Math::position3DFromPosition6D | ( | const Position6D & | pPosition6D | ) |
Create a Position3D from a Position6D
pPosition6D | the given Position6D |
Position3D AL::Math::position3DFromTransform | ( | const Transform & | pT | ) |
Create a Position3D from a Transform.
pT | the Transform you want to extract |
void AL::Math::position3DFromTransformInPlace | ( | const Transform & | pT, |
Position3D & | pPos | ||
) |
Compute a Position3D from a Transform.
pT | the Transform you want to extract |
pPos | the result Position3D |
Position6D AL::Math::position6DFromPose2D | ( | const Pose2D & | pPose2D | ) |
Create a Position6D from a Pose2D.
pPose2D | the pose2D you want to extract |
void AL::Math::position6DFromPose2DInPlace | ( | const Pose2D & | pPose2D, |
Position6D & | pPosition6D | ||
) |
Compute a Position6D from a Pose2D.
pPose2D | the Pose2D to extract |
pPosition6D | the result Position6D |
Position6D AL::Math::position6DFromPosition3D | ( | const Position3D & | pPosition3D | ) |
Create a Position6D from a Position3D.
pPosition3D | the position3D you want to extract |
void AL::Math::position6DFromPosition3DInPlace | ( | const Position3D & | pPosition3D, |
Position6D & | pPosition6D | ||
) |
Compute a Position6D from a Position3D.
pPosition3D | the Position3D to extract |
pPosition6D | the result Position6D |
Position6D AL::Math::position6DFromTransform | ( | const Transform & | pT | ) |
Compute Position6D corresponding to 4*4 Homogenous Transform.
pT | the transform you want to extract |
Position6D AL::Math::position6DFromTransformDiff | ( | const Transform & | pCurrent, |
const Transform & | pTarget | ||
) |
Computes a 6 differential motion require to move from a 4*4 Homogenous transform matrix Current to a 4*4 Homogenous transform matrix target.
pCurrent | the Position6D you want to extract |
pTarget | the Position6D you want to extract |
void AL::Math::position6DFromTransformDiffInPlace | ( | const Transform & | pCurrent, |
const Transform & | pTarget, | ||
Position6D & | result | ||
) |
Computes a 6 differential motion required to move from a 4*4 Homogenous transform matrix Current to a 4*4 Homogenous transform matrix target.
For instance, one would do
Position6D P; position6DFromTransformDiffInPlace(H_ab, H_ac, P)
Now P contains (an approximation of) the dispacement from the frame b to the frame c, expressed at the origin of frame b, and in the basis of frame a
pCurrent | the Position6D you want to extract |
pTarget | the Position6D you want to extract |
result | the result Position6D |
void AL::Math::position6DFromTransformInPlace | ( | const Transform & | pT, |
Position6D & | pPos | ||
) |
Compute Position6D corresponding to the Transform.
pT | the transform you want to extract |
pPos | the transform you want to extract |
Position6D AL::Math::position6DFromVelocity6D | ( | const Velocity6D & | pVel | ) |
Create a Position6D from a Velocity6D
pVel | the given Velocity6D |
void AL::Math::quaternionFromRotation3D | ( | const Rotation3D & | pRot3D, |
Quaternion & | pQuaternion | ||
) |
Create a Quaternion from a Rotation3D when composed in the following order: Rz(wz) * Ry(wy) * Rx(wx)
pRot3D | the rotation3d you want to extract |
void AL::Math::quaternionPosition3DFromPosition6D | ( | const Position6D & | pPos6D, |
Quaternion & | pQua, | ||
Position3D & | pPos3D | ||
) |
Convert a Position6D to Quaternion and Position3D
pPos6D | the input Position6D you want to extract |
pQua | the Quaternion extracted from Position6D |
pPos3D | the Position3D extracted from Position6D |
void AL::Math::rotation3DFromQuaternion | ( | const Quaternion & | pQuaterion, |
Rotation3D & | pRot3D | ||
) |
Create a Rotation3D from a Quaternion when composed in the following order: Rz(wz) * Ry(wy) * Rx(wx)
pQuaternion | the quaternion you want to extract |
Rotation3D AL::Math::rotation3DFromRotation | ( | const Rotation & | pRotation | ) |
return 3 angles which result in the equivalent rotation when composed in the following order: Rz(wz) * Ry(wy) * Rx(wx) = R
pRotation | the Rotation to extract |
Rotation3D AL::Math::rotation3DFromTransform | ( | const Transform & | pT | ) |
Create a Rotation3D (Roll, Pitch, Yaw) corresponding to the rotational part of the Transform. R = Rz(wz) * Ry(wy) * Rx(wx)
pT | the Transform you want to extract |
Rotation AL::Math::rotationFromAngleDirection | ( | const float & | pTheta, |
const Position3D & | pPos | ||
) |
Creates a 3*3 Rotation Matrix from a an angle and a normalized Position3D.
pTheta | the float value of angle in radian |
pPos | the Position3D direction of the vector of the rotation, normalized |
Rotation AL::Math::rotationFromAxesXY | ( | const Position3D & | pX, |
const Position3D & | pY | ||
) |
return a Rotation Matrix initialized with its direction vectors X and Y in world coordinates. These vectors represent, respectively, the first and second columns of the Rotation matrix. The vectors must be unitary and orthogonal.
pX | direction vector for X axis. |
pY | direction vector for Y axis. |
Rotation AL::Math::rotationFromAxesXYZ | ( | const Position3D & | pX, |
const Position3D & | pY, | ||
const Position3D & | pZ | ||
) |
return a Rotation Matrix initialized with its direction vectors in world coordinates. The vectors represent the columns of the Rotation matrix. The vectors must be unitary and orthogonal.
pX | direction vector for X axis. |
pY | direction vector for Y axis. |
pZ | direction vector for Z axis. |
Rotation AL::Math::rotationFromAxesXZ | ( | const Position3D & | pX, |
const Position3D & | pZ | ||
) |
return a Rotation Matrix initialized with its direction vectors X and Z in world coordinates. These vectors represent, respectively, the first and third columns of the Rotation matrix. The vectors must be unitary and orthogonal.
pX | direction vector for X axis. |
pZ | direction vector for Z axis. |
Rotation AL::Math::rotationFromAxesYZ | ( | const Position3D & | pY, |
const Position3D & | pZ | ||
) |
return a Rotation Matrix initialized with its direction vectors X and Y in world coordinates. These vectors represent, respectively, the second and third columns of the Rotation matrix. The vectors must be unitary and orthogonal.
pY | direction vector for Y axis. |
pZ | direction vector for Z axis. |
void AL::Math::rotationFromQuaternion | ( | const Quaternion & | pQua, |
Rotation & | pRot | ||
) |
Create a Rotation Matrix from a Quaternion
pQua | the quaternion you want to extract |
Rotation AL::Math::rotationFromTransform | ( | const Transform & | pTransform | ) |
void AL::Math::rotationFromTransformInPlace | ( | const Transform & | pTransform, |
Rotation & | pRotation | ||
) |
Transform AL::Math::transformFromPose2D | ( | const Pose2D & | pPose | ) |
void AL::Math::transformFromPose2DInPlace | ( | const Pose2D & | pPose, |
Transform & | pT | ||
) |
Transform AL::Math::transformFromPosition3D | ( | const Position3D & | pPosition | ) |
Create a 4*4 transform matrix from cartesian coordinates given in pPosition.
pPosition | position in cartesian coordinates |
void AL::Math::transformFromPosition3DInPlace | ( | const Position3D & | pPosition, |
Transform & | pTransform | ||
) |
Modify pTransform to set the translation part to pPosition.
pPosition | a Position3D cartesian coordinates |
pTransform | the given Transform |
Transform AL::Math::transformFromPosition6D | ( | const Position6D & | pPosition6D | ) |
Create a Transform from a Position6D.
pPosition6D | the Position6D you want to extract |
Transform AL::Math::transformFromRotation | ( | const Rotation & | pRotation | ) |
Transform AL::Math::transformFromRotation3D | ( | const Rotation3D & | pRotation | ) |
Create a Transform from the 3 angles stored in a Rotation3D. The angles are composed in the following order: Rz(wz) * Ry(wy) * Rx(wx) = R
pRotation | the Rotation you want to extract |
void AL::Math::transformFromRotationInPlace | ( | const Rotation & | pRotation, |
Transform & | pTransform | ||
) |
Transform AL::Math::transformFromRotationPosition3D | ( | const Rotation & | pRot, |
const float & | pX, | ||
const float & | pY, | ||
const float & | pZ | ||
) |
Transform AL::Math::transformFromRotationPosition3D | ( | const Rotation & | pRot, |
const Position3D & | pPos | ||
) |
Create a Transform from a Position3D and a Rotation.
pPos | the given Position3D |
pRot | the given Rotation |
Transform AL::Math::transformFromRotVec | ( | const int | pAxis, |
const float | pTheta, | ||
const Position3D & | pPos | ||
) |
Transform AL::Math::transformFromRotVec | ( | const Position3D & | pPos | ) |
Transform AL::Math::transformFromRotVec | ( | const int & | pAxis, |
const float & | pTheta | ||
) |
void AL::Math::transformFromRotVecInPlace | ( | const int | pAxis, |
const float | pTheta, | ||
const Position3D & | pPos, | ||
Transform & | pT | ||
) |
Compute a Transform from
pAxis | the Rotation you want to extract |
pTheta | the rotation you want to extract |
pPos | the Position3D you want to extract |
pT | the Rotation you want to extract |
void AL::Math::transformFromRotVecInPlace | ( | const Position3D & | pPos, |
Transform & | pT | ||
) |
Velocity6D AL::Math::transformLogarithm | ( | const Transform & | pT | ) |
Compute the logarithme of a transform. Angle must be between
Cette fonction calcule le logarithme associe a une matrice de type Deplacement - matrice homogene 4x4 (SE3) La sortie est un torseur cinematique de se3. Le resultat n'est garanti que pour des angles dans [-pi+0.001,pi-0.001]. cette fonction calcule la differentielle du logarithme associe a une matrice de type Deplacement - matrice homogene 4x4 (SE3).
pT | the given Transform |
void AL::Math::transformLogarithmInPlace | ( | const Transform & | pT, |
Velocity6D & | pVel | ||
) |
Compute the logarithme of a transform. Angle must be between
Cette fonction calcule le logarithme associe a une matrice de type Deplacement - matrice homogene 4x4 (SE3) La sortie est un torseur cinematique de se3. Le resultat n'est garanti que pour des angles dans [-pi+0.001,pi-0.001]. cette fonction calcule la differentielle du logarithme associe a une matrice de type Deplacement - matrice homogene 4x4 (SE3).
Transform AL::Math::transformMean | ( | const Transform & | pTIn1, |
const Transform & | pTIn2, | ||
const float & | pVal = 0.5f |
||
) |
void AL::Math::transformMeanInPlace | ( | const Transform & | pTIn1, |
const Transform & | pTIn2, | ||
const float & | pVal, | ||
Transform & | pTOut | ||
) |
Transform AL::Math::velocityExponential | ( | const Velocity6D & | pVel | ) |
Function Velocity Exponential: compute homogenous matrix displacement from a dt * 6D velocity vector.
pVel | the given Velocity6D |
float AL::Math::weightedMeanAngle | ( | const std::vector< float > & | pAngles, |
const std::vector< float > & | pWeights | ||
) |
Returns the weighted mean of given angles (between ]-PI, PI]). It is defined by the direction of the mean of all unitary vectors corresponding to the given angles, multiplied by the given weights. If that mean vector is a null vector, then the angular mean is not defined and the method will throw. For example, meanAngle([0, PI], [1.0, 1.0]) throws.
All weights must be strictly positive, else the method throws.
pAngles | the input/output angles |
pWeights | the input/output weights |