Go to the documentation of this file. 1 #ifndef AIKIDO_CONSTRAINT_DART_FRAMEDIFFERENTIABLE_HPP_
2 #define AIKIDO_CONSTRAINT_DART_FRAMEDIFFERENTIABLE_HPP_
5 #include <dart/dynamics/dynamics.hpp>
11 namespace constraint {
32 ::dart::dynamics::MetaSkeletonPtr _metaskeleton,
33 ::dart::dynamics::ConstJacobianNodePtr _jacobianNode,
48 Eigen::MatrixXd& _out)
const override;
58 Eigen::VectorXd& _val,
59 Eigen::MatrixXd& _jac)
const override;
78 #endif // AIKIDO_CONSTRAINT_DART_FRAMEDIFFERENTIABLE_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
std::shared_ptr< MetaSkeletonStateSpace > MetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
A differentiable constraint.
Definition: Differentiable.hpp:27
void getValueAndJacobian(const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const override
Get both Value and Jacobian evaluated at _s.
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
::dart::dynamics::ConstJacobianNodePtr mJacobianNode
Definition: FrameDifferentiable.hpp:70
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
void getJacobian(const statespace::StateSpace::State *_s, Eigen::MatrixXd &_out) const override
Get jacobian of poseConstraint w.r.t.
std::shared_ptr< Differentiable > DifferentiablePtr
Definition: Differentiable.hpp:14
A pose constraint on _jacobianNode's transform w.r.t.
Definition: FrameDifferentiable.hpp:20
DifferentiablePtr mPoseConstraint
Definition: FrameDifferentiable.hpp:71
std::size_t getConstraintDimension() const override
Size of constraints.
std::vector< ConstraintType > getConstraintTypes() const override
Returns a vector of constraints' types, i-th element correspoinding to the type of i-th constraint.
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
Definition: FrameDifferentiable.hpp:68
Definition: StateSpace.hpp:167
FrameDifferentiable(statespace::dart::MetaSkeletonStateSpacePtr _metaSkeletonStateSpace, ::dart::dynamics::MetaSkeletonPtr _metaskeleton, ::dart::dynamics::ConstJacobianNodePtr _jacobianNode, DifferentiablePtr _poseConstraint)
Constructor.
Definition: FrameMarker.hpp:11
statespace::ConstStateSpacePtr getStateSpace() const override
Gets the StateSpace that this constraint operates on.
void getValue(const statespace::StateSpace::State *_s, Eigen::VectorXd &_out) const override
Get the value of constraints at _s.
::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
Definition: FrameDifferentiable.hpp:69