hpp-constraints
4.12.0
Definition of basic geometric constraints for motion planning
|
#include <hpp/constraints/convex-shape-contact.hh>
Public Member Functions | |
ConvexShapeContactPtr_t | contactConstraint () const |
ConvexShapeContactComplementPtr_t | complement () const |
![]() | |
virtual | ~DifferentiableFunction () |
LiegroupElement | operator() (vectorIn_t argument) const |
void | value (LiegroupElementRef result, vectorIn_t argument) const |
void | jacobian (matrixOut_t jacobian, vectorIn_t argument) const |
const ArrayXb & | activeParameters () const |
const ArrayXb & | activeDerivativeParameters () const |
size_type | inputSize () const |
Get dimension of input vector. More... | |
size_type | inputDerivativeSize () const |
LiegroupSpacePtr_t | outputSpace () const |
Get output space. More... | |
size_type | outputSize () const |
Get dimension of output vector. More... | |
size_type | outputDerivativeSize () const |
Get dimension of output derivative vector. More... | |
const std::string & | name () const |
Get function name. More... | |
virtual std::ostream & | print (std::ostream &o) const |
Display object in a stream. More... | |
std::string | context () const |
void | context (const std::string &c) |
void | finiteDifferenceForward (matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot=DevicePtr_t(), value_type eps=std::sqrt(Eigen::NumTraits< value_type >::epsilon())) const |
void | finiteDifferenceCentral (matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot=DevicePtr_t(), value_type eps=std::sqrt(Eigen::NumTraits< value_type >::epsilon())) const |
Static Public Member Functions | |
static ConvexShapeContactHoldPtr_t | create (const std::string &name, DevicePtr_t robot, const JointAndShapes_t &floorSurfaces, const JointAndShapes_t &objectSurfaces) |
Protected Member Functions | |
ConvexShapeContactHold (const std::string &name, DevicePtr_t robot, const JointAndShapes_t &floorSurfaces, const JointAndShapes_t &objectSurfaces) | |
virtual void | impl_compute (LiegroupElementRef result, vectorIn_t argument) const |
User implementation of function evaluation. More... | |
virtual void | impl_jacobian (matrixOut_t jacobian, vectorIn_t arg) const |
![]() | |
DifferentiableFunction (size_type sizeInput, size_type sizeInputDerivative, size_type sizeOutput, std::string name=std::string()) | |
Concrete class constructor should call this constructor. More... | |
DifferentiableFunction (size_type sizeInput, size_type sizeInputDerivative, const LiegroupSpacePtr_t &outputSpace, std::string name=std::string()) | |
Concrete class constructor should call this constructor. More... | |
DifferentiableFunction () | |
Additional Inherited Members | |
![]() | |
size_type | inputSize_ |
Dimension of input vector. More... | |
size_type | inputDerivativeSize_ |
Dimension of input derivative. More... | |
LiegroupSpacePtr_t | outputSpace_ |
Dimension of output vector. More... | |
ArrayXb | activeParameters_ |
ArrayXb | activeDerivativeParameters_ |
Combination of ConvexShapeContact and complement constaints
Create one instance of
and concatenate their values.
|
protected |
Constructor
constraintName | name of the ConvexShapeContact instance, |
complementName | name of the ConvexShapeContactComplement instance, |
holdName | name of this DifferentiableFunction instance |
robot | the input space of the function is the robot configuration space. |
|
inline |
|
inline |
|
static |
Create instance and return shared pointer
constraintName | name of the ConvexShapeContact instance, |
complementName | name of the ConvexShapeContactComplement instance, |
holdName | name of this DifferentiableFunction instance |
robot | the input space of the function is the robot configuration space. |
|
protectedvirtual |
User implementation of function evaluation.
Implements hpp::constraints::DifferentiableFunction.
|
protectedvirtual |
Implements hpp::constraints::DifferentiableFunction.