Aikido
aikido::constraint::dart::FrameDifferentiable Class Reference

A pose constraint on _jacobianNode's transform w.r.t. More...

#include <aikido/constraint/dart/FrameDifferentiable.hpp>

Inheritance diagram for aikido::constraint::dart::FrameDifferentiable:
aikido::constraint::Differentiable

Public Member Functions

 FrameDifferentiable (statespace::dart::MetaSkeletonStateSpacePtr _metaSkeletonStateSpace, ::dart::dynamics::MetaSkeletonPtr _metaskeleton, ::dart::dynamics::ConstJacobianNodePtr _jacobianNode, DifferentiablePtr _poseConstraint)
 Constructor. More...
 
std::size_t getConstraintDimension () const override
 Size of constraints. More...
 
void getValue (const statespace::StateSpace::State *_s, Eigen::VectorXd &_out) const override
 Get the value of constraints at _s. More...
 
void getJacobian (const statespace::StateSpace::State *_s, Eigen::MatrixXd &_out) const override
 Get jacobian of poseConstraint w.r.t. More...
 
void getValueAndJacobian (const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const override
 Get both Value and Jacobian evaluated at _s. More...
 
std::vector< ConstraintTypegetConstraintTypes () const override
 Returns a vector of constraints' types, i-th element correspoinding to the type of i-th constraint. More...
 
statespace::ConstStateSpacePtr getStateSpace () const override
 Gets the StateSpace that this constraint operates on. More...
 
- Public Member Functions inherited from aikido::constraint::Differentiable
virtual ~Differentiable ()=default
 Destructor. More...
 

Private Attributes

statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
 
::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
 
::dart::dynamics::ConstJacobianNodePtr mJacobianNode
 
DifferentiablePtr mPoseConstraint
 

Detailed Description

A pose constraint on _jacobianNode's transform w.r.t.

MetaSkeletonState of _jacobianNode. _poseConstraint is 1) Differentiable 2) in SE3. 2) constrains _jacobianNode's pose in World Frame.

Constructor & Destructor Documentation

◆ FrameDifferentiable()

aikido::constraint::dart::FrameDifferentiable::FrameDifferentiable ( statespace::dart::MetaSkeletonStateSpacePtr  _metaSkeletonStateSpace,
::dart::dynamics::MetaSkeletonPtr  _metaskeleton,
::dart::dynamics::ConstJacobianNodePtr  _jacobianNode,
DifferentiablePtr  _poseConstraint 
)

Constructor.

Parameters
_metaSkeletonStateSpaceStateSpace whose state defines _jacobianNode's transform.
_metaskeletonMetaSkeleton to test with
_jacobianNodeThe frame being constrained.
_poseConstraintConstraint on _jacobian. This should be in SE3.

Member Function Documentation

◆ getConstraintDimension()

std::size_t aikido::constraint::dart::FrameDifferentiable::getConstraintDimension ( ) const
overridevirtual

Size of constraints.

Implements aikido::constraint::Differentiable.

◆ getConstraintTypes()

std::vector<ConstraintType> aikido::constraint::dart::FrameDifferentiable::getConstraintTypes ( ) const
overridevirtual

Returns a vector of constraints' types, i-th element correspoinding to the type of i-th constraint.

Implements aikido::constraint::Differentiable.

◆ getJacobian()

void aikido::constraint::dart::FrameDifferentiable::getJacobian ( const statespace::StateSpace::State _s,
Eigen::MatrixXd &  _out 
) const
overridevirtual

Get jacobian of poseConstraint w.r.t.

generalized coordinates.

Parameters
_sState to be evaluated at.
[out]_out_m x numDofs, where m is the number of constraints.

Implements aikido::constraint::Differentiable.

◆ getStateSpace()

statespace::ConstStateSpacePtr aikido::constraint::dart::FrameDifferentiable::getStateSpace ( ) const
overridevirtual

Gets the StateSpace that this constraint operates on.

Implements aikido::constraint::Differentiable.

◆ getValue()

void aikido::constraint::dart::FrameDifferentiable::getValue ( const statespace::StateSpace::State _s,
Eigen::VectorXd &  _out 
) const
overridevirtual

Get the value of constraints at _s.

Should be 0 to satisfy equality constraints. Should be <=0 to satisfy inequality constraints.

Parameters
_sState to be evaluated at.
[out]_outVector to store the value. Length should match the number of constraints.

Implements aikido::constraint::Differentiable.

◆ getValueAndJacobian()

void aikido::constraint::dart::FrameDifferentiable::getValueAndJacobian ( const statespace::StateSpace::State _s,
Eigen::VectorXd &  _val,
Eigen::MatrixXd &  _jac 
) const
overridevirtual

Get both Value and Jacobian evaluated at _s.

This is more efficient than calling getValue and getJacobian separately because this sets MetaSkeleton's position only once.

Parameters
_sState to be evaluated at.
[out]_valValue of constraints.
[out]_jacJacobian of constraints.

Reimplemented from aikido::constraint::Differentiable.

Member Data Documentation

◆ mJacobianNode

::dart::dynamics::ConstJacobianNodePtr aikido::constraint::dart::FrameDifferentiable::mJacobianNode
private

◆ mMetaSkeleton

::dart::dynamics::MetaSkeletonPtr aikido::constraint::dart::FrameDifferentiable::mMetaSkeleton
private

◆ mMetaSkeletonStateSpace

statespace::dart::ConstMetaSkeletonStateSpacePtr aikido::constraint::dart::FrameDifferentiable::mMetaSkeletonStateSpace
private

◆ mPoseConstraint

DifferentiablePtr aikido::constraint::dart::FrameDifferentiable::mPoseConstraint
private