Go to the documentation of this file. 1 #ifndef AIKIDO_CONSTRAINT_SATISFIED_HPP_
2 #define AIKIDO_CONSTRAINT_SATISFIED_HPP_
46 std::unique_ptr<TestableOutcome>
createOutcome()
const override;
69 Eigen::MatrixXd& _out)
const override;
78 #endif // ifndef AIKIDO_CONSTRAINT_SATISFIED_HPP_
std::vector< constraint::ConstraintType > getConstraintTypes() const override
Returns an empty vector.
A differentiable constraint.
Definition: Differentiable.hpp:27
bool isSatisfied(const statespace::StateSpace::State *state, TestableOutcome *outcome=nullptr) const override
Returns true.
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
void getJacobian(const statespace::StateSpace::State *_s, Eigen::MatrixXd &_out) const override
Returns an empty matrix.
statespace::ConstStateSpacePtr mStateSpace
Definition: Satisfied.hpp:72
Constraint which can be tested.
Definition: Testable.hpp:17
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
A projectable constraint.
Definition: Projectable.hpp:12
A constraint which is always satisfied.
Definition: Satisfied.hpp:14
Base class for constraint outcomes.
Definition: TestableOutcome.hpp:13
void getValue(const statespace::StateSpace::State *_s, Eigen::VectorXd &_out) const override
Returns an empty vector.
std::size_t getConstraintDimension() const override
Returns 0.
statespace::ConstStateSpacePtr getStateSpace() const override
Gets the StateSpace that this constraint operates on.
virtual void getValueAndJacobian(const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const
Get both Value and Jacobian.
Definition: StateSpace.hpp:167
std::unique_ptr< TestableOutcome > createOutcome() const override
Return an instance of DefaultTestableOutcome, since this class doesn't have a more specialized Testab...
bool project(const statespace::StateSpace::State *_s, statespace::StateSpace::State *_out) const override
Sets _out to _s.
Satisfied(statespace::ConstStateSpacePtr _space)
Constructor.