KrisLibrary
1.0.0
|
A structure defining a link's desired configuration for IK. More...
#include <IK.h>
Public Types | |
enum | PosConstraint { PosNone =0, PosPlanar =1, PosLinear =2, PosFixed =3 } |
enum | RotConstraint { RotNone =0, RotTwoAxis =1, RotAxis =2, RotFixed =3 } |
Public Member Functions | |
void | SetFixedPosition (const Vector3 &pos) |
void | SetPlanarPosition (const Vector3 &point, const Vector3 &normal) |
void | SetLinearPosition (const Vector3 &point, const Vector3 &direction) |
void | SetFreePosition () |
Removes the position constraint. | |
void | SetFixedRotation (const Matrix3 &R) |
Contrains the link to have a fixed rotation matrix. | |
void | SetFixedRotation (const Vector3 &mR) |
Contrains the link to have a fixed rotation moment. | |
void | SetAxisRotation (const Vector3 &localAxis, const Vector3 &worldAxis) |
void | SetFreeRotation () |
Removes the rotation constraint. | |
void | SetFixedTransform (const RigidTransform &T) |
Sets a fixed goal transformation. | |
void | SetFromPoints (const std::vector< Vector3 > &localpos, const std::vector< Vector3 > &worldpos, Real degeneracyTol=Epsilon) |
void | RemovePositionAxis (const Vector3 &axis) |
Removes the position constraint through this axis. | |
void | RemoveRotationAxis (const Vector3 &axis) |
Removes the rotation constraint about the axis. | |
void | RemoveRotationAxis (const Vector3 &p, const Vector3 &axis) |
Removes the rotation constraint about the axis through the point p. | |
void | Transform (const RigidTransform &T) |
Inplace transformation of the goal position/orientation. | |
void | TransformLocal (const RigidTransform &T) |
Inplace transformation of the local position/orientation. | |
void | GetError (const RigidTransform &Trel, Real posErr[3], Real rotErr[3]) const |
void | GetFixedGoalRotation (Matrix3 &R) const |
void | GetFixedGoalTransform (RigidTransform &T) const |
void | GetBaseEdgeRotation (Matrix3 &R0) const |
void | GetEdgeGoalTransform (Real theta, RigidTransform &T) const |
void | GetClosestGoalTransform (const RigidTransform &T0, RigidTransform &T) const |
void | MatchGoalTransform (const RigidTransform &Trel) |
Static Public Member Functions | |
static int | NumDims (PosConstraint c) |
Returns the number of operational space dof's of the given constraint. | |
static int | NumDims (RotConstraint c) |
Public Attributes | |
int | link |
Robot link index. | |
int | destLink |
Desintation link index (-1 means world frame) | |
PosConstraint | posConstraint |
Position terms: | |
Vector3 | localPosition |
End effector position in the local frame. | |
Vector3 | endPosition |
The desired end effector position. | |
Vector3 | direction |
RotConstraint | rotConstraint |
Rotation terms: | |
Vector3 | localAxis |
If in axis-constrained rotation, the local rot axis. | |
Vector3 | endRotation |
A structure defining a link's desired configuration for IK.
Position and/or rotation can be constrained, as well as individual components of each.
void IKGoal::GetClosestGoalTransform | ( | const RigidTransform & | T0, |
RigidTransform & | T | ||
) | const |
Gets a transformation T that satisfies the IK goal's constraints, and is closest to the transform T0. Useful for non-fixed IKGoals.
References Math3D::Line3D::closestPoint(), Math3D::GetCanonicalBasis(), GetMinimalRotation(), and Math3D::Plane3D::project().
void IKGoal::GetError | ( | const RigidTransform & | Trel, |
Real | posErr[3], | ||
Real | rotErr[3] | ||
) | const |
Returns the error in the current configuration given the current relative transform between link -> destlink
References destLink, direction, endPosition, endRotation, Math3D::Vector3::getOrthogonalBasis(), Math::IsFinite(), link, localAxis, localPosition, posConstraint, and rotConstraint.
Referenced by EvalIKError(), IntersectGoals(), and IsReachableGoal().
void IKGoal::MatchGoalTransform | ( | const RigidTransform & | Trel | ) |
sets the endPosition / endRotation values so that if the current relative transform between the link and its target is Trel, the objective's error is 0
References Math3D::RigidTransform::mul().
Contrains the link's orientation so that localAxis is mapped onto worldAxis
|
inline |
Contrains localPosition to be fixed at pos. NOTE: localPosition is not set here!
void IKGoal::SetFromPoints | ( | const std::vector< Vector3 > & | localpos, |
const std::vector< Vector3 > & | worldpos, | ||
Real | degeneracyTol = Epsilon |
||
) |
Fits a constraint that maps the local positions onto the world positions. If 0 points are specified, the constraint is free. If the points are all equal, then the constraint is a point constraint. If the points lie on a line, then the constraint is a hinge constraint.
References Math3D::FitFrames(), GetMinimalRotation(), GetRotationAboutLocalPoint(), and Math::IsInf().
Referenced by IntersectGoals().
Contrains localPosition to lie along a line passing through point with direction normal. NOTE: localPosition is not set here!
Contrains localPosition to lie along a plane passing through point with normal normal. NOTE: localPosition is not set here!
Vector3 IKGoal::direction |
For plane position constraints, the normal of the plane.
For line position constraints, the direction of the line.
Referenced by EvalIKGoalDeriv(), GetError(), and IntersectGoals().
Vector3 IKGoal::endRotation |
The desired end effector rotation, that is, for: Axis-constrained rotation: the desired axis. Fixed rotation: the moment of the desired rotation R=e^[endRotation]
Referenced by EvalIKGoalDeriv(), GetError(), IntersectGoals(), IsReachableGoal(), and JointStructure::SolveWorkspaceBounds().