Aikido
FrameDifferentiable.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONSTRAINT_DART_FRAMEDIFFERENTIABLE_HPP_
2 #define AIKIDO_CONSTRAINT_DART_FRAMEDIFFERENTIABLE_HPP_
3 
4 #include <Eigen/Dense>
5 #include <dart/dynamics/dynamics.hpp>
6 
9 
10 namespace aikido {
11 namespace constraint {
12 namespace dart {
13 
21 {
22 public:
31  statespace::dart::MetaSkeletonStateSpacePtr _metaSkeletonStateSpace,
32  ::dart::dynamics::MetaSkeletonPtr _metaskeleton,
33  ::dart::dynamics::ConstJacobianNodePtr _jacobianNode,
34  DifferentiablePtr _poseConstraint);
35 
36  // Documentation inherited.
37  std::size_t getConstraintDimension() const override;
38 
39  // Documentation inherited.
40  void getValue(const statespace::StateSpace::State* _s, Eigen::VectorXd& _out)
41  const override;
42 
46  void getJacobian(
48  Eigen::MatrixXd& _out) const override;
49 
58  Eigen::VectorXd& _val,
59  Eigen::MatrixXd& _jac) const override;
60 
61  // Documentation inherited.
62  std::vector<ConstraintType> getConstraintTypes() const override;
63 
64  // Documentation inherited.
66 
67 private:
69  ::dart::dynamics::MetaSkeletonPtr mMetaSkeleton;
70  ::dart::dynamics::ConstJacobianNodePtr mJacobianNode;
72 };
73 
74 } // namespace dart
75 } // namespace constraint
76 } // namespace aikido
77 
78 #endif // AIKIDO_CONSTRAINT_DART_FRAMEDIFFERENTIABLE_HPP_
aikido::statespace::dart::ConstMetaSkeletonStateSpacePtr
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::statespace::dart::MetaSkeletonStateSpacePtr
std::shared_ptr< MetaSkeletonStateSpace > MetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
aikido::constraint::Differentiable
A differentiable constraint.
Definition: Differentiable.hpp:27
aikido::constraint::dart::FrameDifferentiable::getValueAndJacobian
void getValueAndJacobian(const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const override
Get both Value and Jacobian evaluated at _s.
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
Differentiable.hpp
aikido::constraint::dart::FrameDifferentiable::mJacobianNode
::dart::dynamics::ConstJacobianNodePtr mJacobianNode
Definition: FrameDifferentiable.hpp:70
aikido::statespace::ConstStateSpacePtr
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
aikido::constraint::dart::FrameDifferentiable::getJacobian
void getJacobian(const statespace::StateSpace::State *_s, Eigen::MatrixXd &_out) const override
Get jacobian of poseConstraint w.r.t.
aikido::constraint::DifferentiablePtr
std::shared_ptr< Differentiable > DifferentiablePtr
Definition: Differentiable.hpp:14
aikido::constraint::dart::FrameDifferentiable
A pose constraint on _jacobianNode's transform w.r.t.
Definition: FrameDifferentiable.hpp:20
aikido::constraint::dart::FrameDifferentiable::mPoseConstraint
DifferentiablePtr mPoseConstraint
Definition: FrameDifferentiable.hpp:71
aikido::constraint::dart::FrameDifferentiable::getConstraintDimension
std::size_t getConstraintDimension() const override
Size of constraints.
aikido::constraint::dart::FrameDifferentiable::getConstraintTypes
std::vector< ConstraintType > getConstraintTypes() const override
Returns a vector of constraints' types, i-th element correspoinding to the type of i-th constraint.
MetaSkeletonStateSpace.hpp
aikido::constraint::dart::FrameDifferentiable::mMetaSkeletonStateSpace
statespace::dart::ConstMetaSkeletonStateSpacePtr mMetaSkeletonStateSpace
Definition: FrameDifferentiable.hpp:68
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::constraint::dart::FrameDifferentiable::FrameDifferentiable
FrameDifferentiable(statespace::dart::MetaSkeletonStateSpacePtr _metaSkeletonStateSpace, ::dart::dynamics::MetaSkeletonPtr _metaskeleton, ::dart::dynamics::ConstJacobianNodePtr _jacobianNode, DifferentiablePtr _poseConstraint)
Constructor.
dart
Definition: FrameMarker.hpp:11
aikido::constraint::dart::FrameDifferentiable::getStateSpace
statespace::ConstStateSpacePtr getStateSpace() const override
Gets the StateSpace that this constraint operates on.
aikido::constraint::dart::FrameDifferentiable::getValue
void getValue(const statespace::StateSpace::State *_s, Eigen::VectorXd &_out) const override
Get the value of constraints at _s.
aikido::constraint::dart::FrameDifferentiable::mMetaSkeleton
::dart::dynamics::MetaSkeletonPtr mMetaSkeleton
Definition: FrameDifferentiable.hpp:69