Aikido
aikido::constraint::Satisfied Class Reference

A constraint which is always satisfied. More...

#include <aikido/constraint/Satisfied.hpp>

Inheritance diagram for aikido::constraint::Satisfied:
aikido::constraint::Differentiable aikido::constraint::Projectable aikido::constraint::Testable

Public Member Functions

 Satisfied (statespace::ConstStateSpacePtr _space)
 Constructor. More...
 
statespace::ConstStateSpacePtr getStateSpace () const override
 Gets the StateSpace that this constraint operates on. More...
 
std::size_t getConstraintDimension () const override
 Returns 0. More...
 
std::vector< constraint::ConstraintTypegetConstraintTypes () const override
 Returns an empty vector. More...
 
bool isSatisfied (const statespace::StateSpace::State *state, TestableOutcome *outcome=nullptr) const override
 Returns true. More...
 
std::unique_ptr< TestableOutcomecreateOutcome () const override
 Return an instance of DefaultTestableOutcome, since this class doesn't have a more specialized TestableOutcome derivative assigned to it. More...
 
bool project (const statespace::StateSpace::State *_s, statespace::StateSpace::State *_out) const override
 Sets _out to _s. More...
 
void getValue (const statespace::StateSpace::State *_s, Eigen::VectorXd &_out) const override
 Returns an empty vector. More...
 
void getJacobian (const statespace::StateSpace::State *_s, Eigen::MatrixXd &_out) const override
 Returns an empty matrix. More...
 
virtual void getValueAndJacobian (const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const
 Get both Value and Jacobian. More...
 
- Public Member Functions inherited from aikido::constraint::Differentiable
virtual ~Differentiable ()=default
 Destructor. More...
 
virtual void getValueAndJacobian (const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const
 Get both Value and Jacobian. More...
 
- Public Member Functions inherited from aikido::constraint::Projectable
virtual ~Projectable ()=default
 
virtual bool project (statespace::StateSpace::State *_s) const
 Performs an in-place projection. More...
 
- Public Member Functions inherited from aikido::constraint::Testable
virtual ~Testable ()=default
 

Private Attributes

statespace::ConstStateSpacePtr mStateSpace
 

Detailed Description

A constraint which is always satisfied.

This class is often used in CartesianProduct constraints to represent that some subspace doesn't have any constraint.

Constructor & Destructor Documentation

◆ Satisfied()

aikido::constraint::Satisfied::Satisfied ( statespace::ConstStateSpacePtr  _space)
explicit

Constructor.

Parameters
_spaceStateSpace in which this constraint operates.

Member Function Documentation

◆ createOutcome()

std::unique_ptr<TestableOutcome> aikido::constraint::Satisfied::createOutcome ( ) const
overridevirtual

Return an instance of DefaultTestableOutcome, since this class doesn't have a more specialized TestableOutcome derivative assigned to it.

Implements aikido::constraint::Testable.

◆ getConstraintDimension()

std::size_t aikido::constraint::Satisfied::getConstraintDimension ( ) const
overridevirtual

Returns 0.

Implements aikido::constraint::Differentiable.

◆ getConstraintTypes()

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

Returns an empty vector.

Implements aikido::constraint::Differentiable.

◆ getJacobian()

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

Returns an empty matrix.

Parameters
_sinput state
[out]_outempty Jacobian matrix

Implements aikido::constraint::Differentiable.

◆ getStateSpace()

statespace::ConstStateSpacePtr aikido::constraint::Satisfied::getStateSpace ( ) const
overridevirtual

Gets the StateSpace that this constraint operates on.

Implements aikido::constraint::Differentiable.

◆ getValue()

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

Returns an empty vector.

Parameters
_sinput state
[out]_outreturns an empty vector

Implements aikido::constraint::Differentiable.

◆ getValueAndJacobian()

virtual void aikido::constraint::Differentiable::getValueAndJacobian

Get both Value and Jacobian.

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

◆ isSatisfied()

bool aikido::constraint::Satisfied::isSatisfied ( const statespace::StateSpace::State state,
TestableOutcome outcome = nullptr 
) const
overridevirtual

Returns true.

Parameters
statea state in getStateSpace()
outcomeobject to populate with information about satisfiability result.

Implements aikido::constraint::Testable.

◆ project()

bool aikido::constraint::Satisfied::project ( const statespace::StateSpace::State _s,
statespace::StateSpace::State _out 
) const
overridevirtual

Sets _out to _s.

Parameters
_sinput state
[out]_outoutput state

Implements aikido::constraint::Projectable.

Member Data Documentation

◆ mStateSpace

statespace::ConstStateSpacePtr aikido::constraint::Satisfied::mStateSpace
private