| 
    Aikido
    
   | 
 
A differentiable constraint which constrains relative transform of jacobianNodeTarget w.r.t. More...
#include <aikido/constraint/dart/FramePairDifferentiable.hpp>
  
Public Member Functions | |
| FramePairDifferentiable (statespace::dart::MetaSkeletonStateSpacePtr _metaSkeletonStateSpace, ::dart::dynamics::MetaSkeletonPtr _metaskeleton, ::dart::dynamics::ConstJacobianNodePtr _jacobianNodeTarget, ::dart::dynamics::ConstJacobianNodePtr _jacobianNodeBase, DifferentiablePtr _relPoseConstraint) | |
| 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 the jacobian of constraints evaluated at _s, expressed in the frame each state space is expressed in).  More... | |
| void | getValueAndJacobian (const statespace::StateSpace::State *_s, Eigen::VectorXd &_val, Eigen::MatrixXd &_jac) const override | 
| Get both Value and Jacobian.  More... | |
| std::vector< ConstraintType > | getConstraintTypes () 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 | mJacobianNode1 | 
| ::dart::dynamics::ConstJacobianNodePtr | mJacobianNode2 | 
| DifferentiablePtr | mRelPoseConstraint | 
A differentiable constraint which constrains relative transform of jacobianNodeTarget w.r.t.
jacobianNodeBase. _relPoseConstraint is 1) Differentiable 2) in SE3. 2) constrains _jacobianNodeTarget's pose in jacobianNodeBase's frame.
| aikido::constraint::dart::FramePairDifferentiable::FramePairDifferentiable | ( | statespace::dart::MetaSkeletonStateSpacePtr | _metaSkeletonStateSpace, | 
| ::dart::dynamics::MetaSkeletonPtr | _metaskeleton, | ||
| ::dart::dynamics::ConstJacobianNodePtr | _jacobianNodeTarget, | ||
| ::dart::dynamics::ConstJacobianNodePtr | _jacobianNodeBase, | ||
| DifferentiablePtr | _relPoseConstraint | ||
| ) | 
Constructor.
| _metaSkeletonStateSpace | StateSpace whose states define _jacobianNodeTarget and _jacobianNodeBase's relative transform. | 
| _metaskeleton | MetaSkeleton to test with | 
| _jacobianNodeTarget | The frame whose relative transform w.r.t. _jacobianNodeBase is being constrained. | 
| _jacobianNodeBase | The base frame for this constraint. | 
| _relPoseConstraint | Relative pose constraint on _jacobianNodeTarget w.r.t. _jacobianNodeBase. | 
      
  | 
  overridevirtual | 
Size of constraints.
Implements aikido::constraint::Differentiable.
      
  | 
  overridevirtual | 
Returns a vector of constraints' types, i-th element correspoinding to the type of i-th constraint.
Implements aikido::constraint::Differentiable.
      
  | 
  overridevirtual | 
Get the jacobian of constraints evaluated at _s, expressed in the frame each state space is expressed in).
| _s | State to be evaluated at. | |
| [out] | _out | Jacobian matrix. The dimension should be the following: SO3 StateSpace : m x 3 SO2 : m x 1 SE2 : m x 3 SE3 : m x 6 Rn : m x n CartesianProduct: m x k (k = sum of all state jacobian cols) If Matrix of incorrect dimension is given, false will be returned. | 
Implements aikido::constraint::Differentiable.
      
  | 
  overridevirtual | 
Gets the StateSpace that this constraint operates on.
Implements aikido::constraint::Differentiable.
      
  | 
  overridevirtual | 
Get the value of constraints at _s.
Should be 0 to satisfy equality constraints. Should be <=0 to satisfy inequality constraints.
| _s | State to be evaluated at. | |
| [out] | _out | Vector to store the value. Length should match the number of constraints. | 
Implements aikido::constraint::Differentiable.
      
  | 
  overridevirtual | 
Get both Value and Jacobian.
| _s | State to be evaluated. | |
| [out] | _val | Value of constraints. | 
| [out] | _jac | Jacoiban of constraints. | 
Reimplemented from aikido::constraint::Differentiable.
      
  | 
  private | 
      
  | 
  private | 
      
  | 
  private | 
      
  | 
  private | 
      
  | 
  private |