Namespaces | |
eigen | |
explicit_ | |
function | |
implicit | |
lineSearch | |
solver | |
Classes | |
class | ActiveSetDifferentiableFunction |
Handle bounds on input variables of a differentiable function. More... | |
class | AffineFunction |
Affine function \( f(q) = J * q + b \). More... | |
class | CalculusBase |
Main abstract class. More... | |
class | CalculusBaseAbstract |
Abstract class defining a basic common interface. More... | |
class | ComBetweenFeet |
Constraint on the relative position of the center of mass. More... | |
class | ConfigurationConstraint |
Square distance between input configuration and reference configuration. More... | |
struct | ConstantFunction |
Constant function \( f(q) = C \). More... | |
class | ConvexShape |
class | ConvexShapeContact |
The function returns a relative transformation between the two "closest" convex shapes it contains. More... | |
class | ConvexShapeContactComplement |
Complement to full transformation constraint of ConvexShapeContact. More... | |
struct | ConvexShapeData |
class | CrossProduct |
Cross product of two expressions. More... | |
class | Difference |
Difference of two expressions. More... | |
class | DifferentiableFunction |
Differentiable function. More... | |
class | DifferentiableFunctionSet |
Set of differentiable functions. More... | |
class | DistanceBetweenBodies |
Distance between two sets of objects. More... | |
class | DistanceBetweenPointsInBodies |
Distance between two sets of objects. More... | |
class | Explicit |
Explicit numerical constraint. More... | |
class | ExplicitConstraintSet |
Set of explicit constraints. More... | |
class | Expression |
Base class for classes representing an operation. More... | |
class | FunctionExp |
Basic expression mapping a function as an expression. More... | |
class | GenericTransformation |
GenericTransformation class encapsulates 6 possible differentiable functions: Position, Orientation, Transformation and their relative versions RelativePosition, RelativeOrientation, RelativeTransformation. More... | |
class | Identity |
Identity function \( q_{out} = q_{in} \). More... | |
class | Implicit |
This class represents a parameterizable numerical constraint that compares the output of a function \(h\) to a right hand side vector. More... | |
class | ImplicitConstraintSet |
Set of implicit constraints. More... | |
class | JointFrame |
struct | JointTranspose |
class | LockedJoint |
Implementation of constraint specific to locked joint. More... | |
class | Manipulability |
Differentiable function. More... | |
class | MatrixOfExpressions |
Matrix having Expression elements. More... | |
class | Point |
Basic expression representing a static point. More... | |
class | PointCom |
Basic expression representing a COM. More... | |
class | PointInJoint |
Basic expression representing a point in a joint frame. More... | |
class | QPStaticStability |
class | RelativeCom |
Constraint on the relative position of the center of mass. More... | |
class | RotationMultiply |
Multiplication of an expression by a rotation matrix. More... | |
class | ScalarMultiply |
Multiplication of an expression by a scalar. More... | |
class | ScalarProduct |
Scalar product of two expressions. More... | |
class | StaticStability |
class | Sum |
Sum of two expressions. More... | |
class | SymbolicFunction |
struct | Traits |
struct | Traits< JointTranspose > |
struct | Traits< pinocchio::Joint > |
struct | Traits< value_type > |
class | VectorInJoint |
Basic expression representing a vector in a joint frame. More... | |
Typedefs | |
typedef pinocchio::size_type | size_type |
typedef pinocchio::value_type | value_type |
typedef pinocchio::JointPtr_t | JointPtr_t |
typedef pinocchio::JointConstPtr_t | JointConstPtr_t |
typedef pinocchio::vector3_t | vector3_t |
typedef pinocchio::matrix3_t | matrix3_t |
typedef Eigen::Matrix< value_type, 6, 6 > | matrix6_t |
typedef pinocchio::matrix_t | matrix_t |
typedef Eigen::Ref< const matrix_t > | matrixIn_t |
typedef Eigen::Ref< matrix_t > | matrixOut_t |
typedef pinocchio::vector_t | vector_t |
typedef pinocchio::vectorIn_t | vectorIn_t |
typedef pinocchio::vectorOut_t | vectorOut_t |
typedef pinocchio::ComJacobian_t | ComJacobian_t |
typedef pinocchio::JointJacobian_t | JointJacobian_t |
typedef pinocchio::Transform3f | Transform3f |
typedef pinocchio::LiegroupElement | LiegroupElement |
typedef pinocchio::LiegroupElementRef | LiegroupElementRef |
typedef pinocchio::LiegroupSpace | LiegroupSpace |
typedef pinocchio::LiegroupSpacePtr_t | LiegroupSpacePtr_t |
typedef pinocchio::LiegroupSpaceConstPtr_t | LiegroupSpaceConstPtr_t |
typedef Eigen::Matrix< value_type, 5, 1 > | vector5_t |
typedef Eigen::Matrix< value_type, 6, 1 > | vector6_t |
typedef Eigen::Matrix< value_type, 7, 1 > | vector7_t |
typedef Eigen::Quaternion< value_type > | Quaternion_t |
typedef pinocchio::ArrayXb | ArrayXb |
typedef ArrayXb | bool_array_t |
typedef std::pair< size_type, size_type > | segment_t |
typedef std::vector< segment_t > | segments_t |
typedef pinocchio::ObjectVector_t | ObjectVector_t |
typedef pinocchio::CollisionObjectPtr_t | CollisionObjectPtr_t |
typedef pinocchio::CollisionObjectConstPtr_t | CollisionObjectConstPtr_t |
typedef pinocchio::Configuration_t | Configuration_t |
typedef pinocchio::ConfigurationIn_t | ConfigurationIn_t |
typedef pinocchio::ConfigurationOut_t | ConfigurationOut_t |
typedef pinocchio::Device | Device |
typedef pinocchio::DevicePtr_t | DevicePtr_t |
typedef pinocchio::CenterOfMassComputation | CenterOfMassComputation |
typedef pinocchio::CenterOfMassComputationPtr_t | CenterOfMassComputationPtr_t |
typedef boost::shared_ptr< DifferentiableFunction > | DifferentiableFunctionPtr_t |
typedef boost::shared_ptr< DifferentiableFunctionSet > | DifferentiableFunctionSetPtr_t |
typedef DifferentiableFunctionSet DifferentiableFunctionStack | HPP_CONSTRAINTS_DEPRECATED |
typedef boost::shared_ptr< ActiveSetDifferentiableFunction > | ActiveSetDifferentiableFunctionPtr_t |
typedef boost::shared_ptr< DistanceBetweenBodies > | DistanceBetweenBodiesPtr_t |
typedef boost::shared_ptr< DistanceBetweenPointsInBodies > | DistanceBetweenPointsInBodiesPtr_t |
typedef boost::shared_ptr< RelativeCom > | RelativeComPtr_t |
typedef boost::shared_ptr< ComBetweenFeet > | ComBetweenFeetPtr_t |
typedef boost::shared_ptr< ConvexShapeContact > | ConvexShapeContactPtr_t |
typedef boost::shared_ptr< ConvexShapeContactComplement > | ConvexShapeContactComplementPtr_t |
typedef boost::shared_ptr< StaticStability > | StaticStabilityPtr_t |
typedef boost::shared_ptr< QPStaticStability > | QPStaticStabilityPtr_t |
typedef boost::shared_ptr< ConfigurationConstraint > | ConfigurationConstraintPtr_t |
typedef boost::shared_ptr< Identity > | IdentityPtr_t |
typedef boost::shared_ptr< AffineFunction > | AffineFunctionPtr_t |
typedef boost::shared_ptr< ConstantFunction > | ConstantFunctionPtr_t |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContact | StaticStabilityGravity |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContactComplement | StaticStabilityGravityComplement |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContactPtr_t | StaticStabilityGravityPtr_t |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContactComplementPtr_t | StaticStabilityGravityComplementPtr_t |
typedef GenericTransformation< PositionBit > | Position |
typedef GenericTransformation< OrientationBit > | Orientation |
typedef GenericTransformation< RelativeBit|PositionBit|OrientationBit > | RelativeTransformation |
typedef GenericTransformation< RelativeBit|PositionBit > | RelativePosition |
typedef GenericTransformation< RelativeBit|OrientationBit > | RelativeOrientation |
typedef GenericTransformation< PositionBit|OrientationBit|OutputSE3Bit > | TransformationSE3 |
typedef GenericTransformation< RelativeBit|PositionBit|OrientationBit|OutputSE3Bit > | RelativeTransformationSE3 |
typedef GenericTransformation< OrientationBit|OutputSE3Bit > | OrientationSO3 |
typedef GenericTransformation< RelativeBit|OrientationBit|OutputSE3Bit > | RelativeOrientationSO3 |
typedef boost::shared_ptr< Position > | PositionPtr_t |
typedef boost::shared_ptr< Orientation > | OrientationPtr_t |
typedef boost::shared_ptr< Transformation > | TransformationPtr_t |
typedef boost::shared_ptr< RelativePosition > | RelativePositionPtr_t |
typedef boost::shared_ptr< RelativeOrientation > | RelativeOrientationPtr_t |
typedef boost::shared_ptr< RelativeTransformation > | RelativeTransformationPtr_t |
typedef Eigen::BlockIndex | BlockIndex |
typedef boost::shared_ptr< Implicit > | ImplicitPtr_t |
typedef boost::shared_ptr< const Implicit > | ImplicitConstPtr_t |
typedef std::vector< constraints::ImplicitPtr_t > | NumericalConstraints_t |
typedef boost::shared_ptr< ImplicitConstraintSet > | ImplicitConstraintSetPtr_t |
typedef std::vector< ComparisonType > | ComparisonTypes_t |
typedef boost::shared_ptr< Explicit > | ExplicitPtr_t |
typedef boost::shared_ptr< const Explicit > | ExplicitConstPtr_t |
typedef boost::shared_ptr< LockedJoint > | LockedJointPtr_t |
typedef boost::shared_ptr< const LockedJoint > | LockedJointConstPtr_t |
typedef std::vector< LockedJointPtr_t > | LockedJoints_t |
typedef boost::shared_ptr< Manipulability > | ManipulabilityPtr_t |
typedef eigen::matrix3_t | CrossMatrix |
typedef Eigen::Matrix< value_type, 1, Eigen::Dynamic, Eigen::RowMajor > | RowJacobianMatrix |
typedef Eigen::Matrix< value_type, 3, Eigen::Dynamic, Eigen::RowMajor > | JacobianMatrix |
Enumerations | |
enum | ComparisonType { Equality, EqualToZero, Superior, Inferior } |
Functions | |
void | closestPointToSegment (const vector3_t &P, const vector3_t &A, const vector3_t &v, vector3_t &B) |
Return the closest point to point P, on a segment line \( A + t*v, t \in [0,1] \). More... | |
vector3_t | linePlaneIntersection (const vector3_t &A, const vector3_t &u, const vector3_t &P, const vector3_t &n) |
std::ostream & | operator<< (std::ostream &os, const DifferentiableFunction &f) |
HPP_PREDEF_CLASS (DifferentiableFunction) | |
HPP_PREDEF_CLASS (DifferentiableFunctionSet) | |
HPP_PREDEF_CLASS (ActiveSetDifferentiableFunction) | |
HPP_PREDEF_CLASS (DistanceBetweenBodies) | |
HPP_PREDEF_CLASS (DistanceBetweenPointsInBodies) | |
HPP_PREDEF_CLASS (RelativeCom) | |
HPP_PREDEF_CLASS (ComBetweenFeet) | |
HPP_PREDEF_CLASS (StaticStability) | |
HPP_PREDEF_CLASS (QPStaticStability) | |
HPP_PREDEF_CLASS (ConvexShapeContact) | |
HPP_PREDEF_CLASS (ConvexShapeContactComplement) | |
HPP_PREDEF_CLASS (ConfigurationConstraint) | |
HPP_PREDEF_CLASS (Identity) | |
HPP_PREDEF_CLASS (AffineFunction) | |
HPP_PREDEF_CLASS (ConstantFunction) | |
HPP_PREDEF_CLASS (Implicit) | |
HPP_PREDEF_CLASS (ImplicitConstraintSet) | |
HPP_PREDEF_CLASS (Explicit) | |
HPP_PREDEF_CLASS (LockedJoint) | |
std::ostream & | operator<< (std::ostream &os, const LockedJoint &lj) |
HPP_PREDEF_CLASS (Manipulability) | |
template<typename SVD > | |
static Eigen::Ref< const typename SVD::MatrixUType > | getU1 (const SVD &svd, const size_type &rank) |
template<typename SVD > | |
static Eigen::Ref< const typename SVD::MatrixUType > | getU2 (const SVD &svd, const size_type &rank) |
template<typename SVD > | |
static Eigen::Ref< const typename SVD::MatrixUType > | getV1 (const SVD &svd, const size_type &rank) |
template<typename SVD > | |
static Eigen::Ref< const typename SVD::MatrixUType > | getV2 (const SVD &svd, const size_type &rank) |
template<typename SVD > | |
static void | pseudoInverse (const SVD &svd, Eigen::Ref< typename SVD::MatrixType > pinvmat) |
template<typename SVD > | |
void | projectorOnSpan (const SVD &svd, Eigen::Ref< typename SVD::MatrixType > projector) |
template<typename SVD > | |
void | projectorOnSpanOfInv (const SVD &svd, Eigen::Ref< typename SVD::MatrixType > projector) |
template<typename SVD > | |
void | projectorOnKernel (const SVD &svd, Eigen::Ref< typename SVD::MatrixType > projector, const bool &computeFullV=false) |
template<typename SVD > | |
void | projectorOnKernelOfInv (const SVD &svd, Eigen::Ref< typename SVD::MatrixType > projector, const bool &computeFullU=false) |
template<typename VectorType , typename MatrixType > | |
static void | computeCrossMatrix (const VectorType &v, MatrixType &m) |
template<typename Derived > | |
void | logSO3 (const matrix3_t &R, value_type &theta, Eigen::MatrixBase< Derived > const &result) |
Compute log of rotation matrix as a 3d vector. More... | |
template<typename Derived > | |
void | JlogSO3 (const value_type &theta, const Eigen::MatrixBase< Derived > &log, matrix3_t &Jlog) |
Compute jacobian of function log of rotation matrix in SO(3) More... | |
template<typename Derived > | |
void | logSE3 (const Transform3f &M, Eigen::MatrixBase< Derived > &result) |
Compute log of rigid-body transform. More... | |
template<typename Derived > | |
void | JlogSE3 (const Transform3f &M, Eigen::MatrixBase< Derived > const &Jlog) |
template<typename Derived1 , typename Derived2 > | |
void | matrixToQuat (const Eigen::MatrixBase< Derived1 > &M, Eigen::MatrixBase< Derived2 > const &q) |
template<typename Derived > | |
void | se3ToConfig (const Transform3f &M, Eigen::MatrixBase< Derived > const &q) |
Variables | |
DEVEL typedef GenericTransformation< PositionBit|OrientationBit > | Transformation |
typedef boost::shared_ptr<ActiveSetDifferentiableFunction> hpp::constraints::ActiveSetDifferentiableFunctionPtr_t |
typedef boost::shared_ptr<AffineFunction> hpp::constraints::AffineFunctionPtr_t |
typedef pinocchio::ArrayXb hpp::constraints::ArrayXb |
typedef pinocchio::CenterOfMassComputation hpp::constraints::CenterOfMassComputation |
typedef pinocchio::CenterOfMassComputationPtr_t hpp::constraints::CenterOfMassComputationPtr_t |
typedef pinocchio::CollisionObjectConstPtr_t hpp::constraints::CollisionObjectConstPtr_t |
typedef pinocchio::CollisionObjectPtr_t hpp::constraints::CollisionObjectPtr_t |
typedef boost::shared_ptr<ComBetweenFeet> hpp::constraints::ComBetweenFeetPtr_t |
typedef pinocchio::ComJacobian_t hpp::constraints::ComJacobian_t |
typedef std::vector<ComparisonType> hpp::constraints::ComparisonTypes_t |
typedef pinocchio::Configuration_t hpp::constraints::Configuration_t |
typedef boost::shared_ptr<ConfigurationConstraint> hpp::constraints::ConfigurationConstraintPtr_t |
typedef pinocchio::ConfigurationIn_t hpp::constraints::ConfigurationIn_t |
typedef pinocchio::ConfigurationOut_t hpp::constraints::ConfigurationOut_t |
typedef boost::shared_ptr<ConstantFunction> hpp::constraints::ConstantFunctionPtr_t |
typedef boost::shared_ptr<ConvexShapeContactComplement> hpp::constraints::ConvexShapeContactComplementPtr_t |
typedef boost::shared_ptr<ConvexShapeContact> hpp::constraints::ConvexShapeContactPtr_t |
typedef pinocchio::Device hpp::constraints::Device |
typedef pinocchio::DevicePtr_t hpp::constraints::DevicePtr_t |
typedef boost::shared_ptr<DifferentiableFunction> hpp::constraints::DifferentiableFunctionPtr_t |
typedef boost::shared_ptr<DifferentiableFunctionSet> hpp::constraints::DifferentiableFunctionSetPtr_t |
typedef boost::shared_ptr<DistanceBetweenBodies> hpp::constraints::DistanceBetweenBodiesPtr_t |
typedef boost::shared_ptr<DistanceBetweenPointsInBodies> hpp::constraints::DistanceBetweenPointsInBodiesPtr_t |
typedef boost::shared_ptr<const Explicit> hpp::constraints::ExplicitConstPtr_t |
typedef boost::shared_ptr<Explicit> hpp::constraints::ExplicitPtr_t |
typedef solver::BySubstitution HybridSolver hpp::constraints::HPP_CONSTRAINTS_DEPRECATED |
typedef boost::shared_ptr<Identity> hpp::constraints::IdentityPtr_t |
typedef boost::shared_ptr<const Implicit> hpp::constraints::ImplicitConstPtr_t |
typedef boost::shared_ptr<ImplicitConstraintSet> hpp::constraints::ImplicitConstraintSetPtr_t |
typedef boost::shared_ptr<Implicit> hpp::constraints::ImplicitPtr_t |
typedef pinocchio::JointConstPtr_t hpp::constraints::JointConstPtr_t |
typedef pinocchio::JointJacobian_t hpp::constraints::JointJacobian_t |
typedef pinocchio::JointPtr_t hpp::constraints::JointPtr_t |
typedef pinocchio::LiegroupElement hpp::constraints::LiegroupElement |
typedef pinocchio::LiegroupElementRef hpp::constraints::LiegroupElementRef |
typedef pinocchio::LiegroupSpace hpp::constraints::LiegroupSpace |
typedef pinocchio::LiegroupSpaceConstPtr_t hpp::constraints::LiegroupSpaceConstPtr_t |
typedef pinocchio::LiegroupSpacePtr_t hpp::constraints::LiegroupSpacePtr_t |
typedef boost::shared_ptr<const LockedJoint> hpp::constraints::LockedJointConstPtr_t |
typedef boost::shared_ptr<LockedJoint> hpp::constraints::LockedJointPtr_t |
typedef std::vector<LockedJointPtr_t> hpp::constraints::LockedJoints_t |
typedef boost::shared_ptr<Manipulability> hpp::constraints::ManipulabilityPtr_t |
typedef pinocchio::matrix3_t hpp::constraints::matrix3_t |
typedef Eigen::Matrix<value_type, 6, 6> hpp::constraints::matrix6_t |
typedef pinocchio::matrix_t hpp::constraints::matrix_t |
typedef Eigen::Ref<const matrix_t> hpp::constraints::matrixIn_t |
typedef Eigen::Ref<matrix_t> hpp::constraints::matrixOut_t |
typedef std::vector< constraints::ImplicitPtr_t > hpp::constraints::NumericalConstraints_t |
typedef pinocchio::ObjectVector_t hpp::constraints::ObjectVector_t |
typedef GenericTransformation< OrientationBit > hpp::constraints::Orientation |
typedef boost::shared_ptr<Orientation> hpp::constraints::OrientationPtr_t |
typedef GenericTransformation< OrientationBit | OutputSE3Bit > hpp::constraints::OrientationSO3 |
typedef GenericTransformation< PositionBit > hpp::constraints::Position |
typedef boost::shared_ptr<Position> hpp::constraints::PositionPtr_t |
typedef boost::shared_ptr<QPStaticStability> hpp::constraints::QPStaticStabilityPtr_t |
typedef Eigen::Quaternion<value_type> hpp::constraints::Quaternion_t |
typedef boost::shared_ptr<RelativeCom> hpp::constraints::RelativeComPtr_t |
typedef GenericTransformation< RelativeBit | OrientationBit > hpp::constraints::RelativeOrientation |
typedef boost::shared_ptr<RelativeOrientation> hpp::constraints::RelativeOrientationPtr_t |
typedef GenericTransformation< RelativeBit | OrientationBit | OutputSE3Bit > hpp::constraints::RelativeOrientationSO3 |
typedef GenericTransformation< RelativeBit | PositionBit > hpp::constraints::RelativePosition |
typedef boost::shared_ptr<RelativePosition> hpp::constraints::RelativePositionPtr_t |
typedef GenericTransformation< RelativeBit | PositionBit | OrientationBit > hpp::constraints::RelativeTransformation |
typedef boost::shared_ptr<RelativeTransformation> hpp::constraints::RelativeTransformationPtr_t |
typedef GenericTransformation< RelativeBit | PositionBit | OrientationBit | OutputSE3Bit > hpp::constraints::RelativeTransformationSE3 |
typedef std::pair<size_type, size_type> hpp::constraints::segment_t |
typedef std::vector< segment_t > hpp::constraints::segments_t |
typedef pinocchio::size_type hpp::constraints::size_type |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContactComplement hpp::constraints::StaticStabilityGravityComplement |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContactComplementPtr_t hpp::constraints::StaticStabilityGravityComplementPtr_t |
typedef HPP_CONSTRAINTS_DEPRECATED ConvexShapeContactPtr_t hpp::constraints::StaticStabilityGravityPtr_t |
typedef boost::shared_ptr<StaticStability> hpp::constraints::StaticStabilityPtr_t |
typedef pinocchio::Transform3f hpp::constraints::Transform3f |
typedef boost::shared_ptr<Transformation> hpp::constraints::TransformationPtr_t |
typedef GenericTransformation< PositionBit | OrientationBit | OutputSE3Bit > hpp::constraints::TransformationSE3 |
typedef pinocchio::value_type hpp::constraints::value_type |
typedef pinocchio::vector3_t hpp::constraints::vector3_t |
typedef Eigen::Matrix<value_type, 5, 1> hpp::constraints::vector5_t |
typedef Eigen::Matrix<value_type, 6, 1> hpp::constraints::vector6_t |
typedef Eigen::Matrix<value_type, 7, 1> hpp::constraints::vector7_t |
typedef pinocchio::vector_t hpp::constraints::vector_t |
typedef pinocchio::vectorIn_t hpp::constraints::vectorIn_t |
typedef pinocchio::vectorOut_t hpp::constraints::vectorOut_t |
|
inline |
Return the closest point to point P, on a segment line \( A + t*v, t \in [0,1] \).
P | PA where P is the point to | |
A | the origin the segment line | |
v | vector presenting the segment line | |
[out] | B | the closest point |
|
static |
References logSO3().
Referenced by hpp::constraints::PointInJoint::computeCrossRXl(), hpp::constraints::VectorInJoint::computeCrossRXl(), hpp::constraints::CalculusBase< ScalarProduct< LhsValue, RhsValue >, Eigen::Matrix< value_type, 1, 1 >, RowJacobianMatrix >::computeCrossValue(), JlogSE3(), and logSE3().
|
static |
|
static |
|
static |
|
static |
hpp::constraints::HPP_PREDEF_CLASS | ( | Manipulability | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | DifferentiableFunction | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | DifferentiableFunctionSet | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ActiveSetDifferentiableFunction | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | DistanceBetweenBodies | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | DistanceBetweenPointsInBodies | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | RelativeCom | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ComBetweenFeet | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | StaticStability | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | QPStaticStability | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ConvexShapeContact | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ConvexShapeContactComplement | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ConfigurationConstraint | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | Identity | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | AffineFunction | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ConstantFunction | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | Implicit | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | ImplicitConstraintSet | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | Explicit | ) |
hpp::constraints::HPP_PREDEF_CLASS | ( | LockedJoint | ) |
|
inline |
A,u | point and vector defining the line \( A + t*u \) |
P,n | point and normal vector defining the plane \( Q \in plane \Rightleftarrow (P - Q) . n = 0 \) |
u
and n
are expected not to be orthogonal. References Eigen::assert().
Referenced by hpp::constraints::ConvexShapeData::intersection(), and hpp::constraints::ConvexShape::intersectionLocal().
|
inline |
References hpp::constraints::LockedJoint::print().
void hpp::constraints::projectorOnKernel | ( | const SVD & | svd, |
Eigen::Ref< typename SVD::MatrixType > | projector, | ||
const bool & | computeFullV = false |
||
) |
void hpp::constraints::projectorOnKernelOfInv | ( | const SVD & | svd, |
Eigen::Ref< typename SVD::MatrixType > | projector, | ||
const bool & | computeFullU = false |
||
) |
void hpp::constraints::projectorOnSpan | ( | const SVD & | svd, |
Eigen::Ref< typename SVD::MatrixType > | projector | ||
) |
void hpp::constraints::projectorOnSpanOfInv | ( | const SVD & | svd, |
Eigen::Ref< typename SVD::MatrixType > | projector | ||
) |
|
static |
DEVEL typedef GenericTransformation< PositionBit | OrientationBit > hpp::constraints::Transformation |