hpp::constraints::DifferentiableFunctionSet Class Reference

Set of differentiable functions. More...

#include <hpp/constraints/differentiable-function-set.hh>

Inheritance diagram for hpp::constraints::DifferentiableFunctionSet:
[legend]
Collaboration diagram for hpp::constraints::DifferentiableFunctionSet:
[legend]

Public Types

typedef std::vector< DifferentiableFunctionPtr_tFunctions_t
 

Public Member Functions

virtual ~DifferentiableFunctionSet () throw ()
 
std::ostream & print (std::ostream &os) const
 Display object in a stream. More...
 
 DifferentiableFunctionSet (const std::string &name)
 Constructor. More...
 
 DifferentiableFunctionSet ()
 
Function stack management
const Functions_tfunctions () const
 Get the stack of functions. More...
 
void add (const DifferentiableFunctionPtr_t &func)
 
void merge (const DifferentiableFunctionSetPtr_t &other)
 The output columns selection of other is not taken into account. More...
 
- Public Member Functions inherited from hpp::constraints::DifferentiableFunction
virtual ~DifferentiableFunction ()
 
LiegroupElement operator() (vectorIn_t argument) const
 Evaluate the function at a given parameter. More...
 
void value (LiegroupElementRef result, vectorIn_t argument) const
 Evaluate the function at a given parameter. More...
 
void jacobian (matrixOut_t jacobian, vectorIn_t argument) const
 Computes the jacobian. More...
 
const ArrayXbactiveParameters () const
 Returns a vector of booleans that indicates whether the corresponding configuration parameter influences this constraints. More...
 
const ArrayXbactiveDerivativeParameters () const
 Returns a vector of booleans that indicates whether the corresponding velocity parameter influences this constraints. More...
 
size_type inputSize () const
 Get dimension of input vector. More...
 
size_type inputDerivativeSize () const
 Get dimension of input derivative vector. More...
 
LiegroupSpacePtr_t outputSpace () const
 Get output element. 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...
 
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
 Approximate the jacobian using forward finite difference. More...
 
void finiteDifferenceCentral (matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot=DevicePtr_t(), value_type eps=std::sqrt(Eigen::NumTraits< value_type >::epsilon())) const
 Approximate the jacobian using forward finite difference. More...
 

Static Public Member Functions

static DifferentiableFunctionSetPtr_t create (const std::string &name)
 Return a shared pointer to a new instance. More...
 

Protected Member Functions

void impl_compute (LiegroupElementRef result, ConfigurationIn_t arg) const throw ()
 
void impl_jacobian (matrixOut_t jacobian, ConfigurationIn_t arg) const throw ()
 
- Protected Member Functions inherited from hpp::constraints::DifferentiableFunction
 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...
 
virtual void impl_compute (LiegroupElementRef result, vectorIn_t argument) const =0
 User implementation of function evaluation. More...
 
virtual void impl_jacobian (matrixOut_t jacobian, vectorIn_t arg) const =0
 

Additional Inherited Members

- Protected Attributes inherited from hpp::constraints::DifferentiableFunction
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_
 Initialized to true by this class. More...
 
ArrayXb activeDerivativeParameters_
 Initialized to true by this class. More...
 

Detailed Description

Set of differentiable functions.

This class also handles selection of cols of the output matrix.

Member Typedef Documentation

Constructor & Destructor Documentation

virtual hpp::constraints::DifferentiableFunctionSet::~DifferentiableFunctionSet ( )
throw (
)
inlinevirtual
hpp::constraints::DifferentiableFunctionSet::DifferentiableFunctionSet ( const std::string &  name)
inline

Constructor.

Parameters
namethe name of the constraints,
hpp::constraints::DifferentiableFunctionSet::DifferentiableFunctionSet ( )
inline

Member Function Documentation

void hpp::constraints::DifferentiableFunctionSet::add ( const DifferentiableFunctionPtr_t func)
inline

References Eigen::assert().

static DifferentiableFunctionSetPtr_t hpp::constraints::DifferentiableFunctionSet::create ( const std::string &  name)
inlinestatic

Return a shared pointer to a new instance.

Parameters
namethe name of the constraints,
const Functions_t& hpp::constraints::DifferentiableFunctionSet::functions ( ) const
inline

Get the stack of functions.

void hpp::constraints::DifferentiableFunctionSet::impl_compute ( LiegroupElementRef  result,
ConfigurationIn_t  arg 
) const
throw (
)
inlineprotected
void hpp::constraints::DifferentiableFunctionSet::impl_jacobian ( matrixOut_t  jacobian,
ConfigurationIn_t  arg 
) const
throw (
)
inlineprotected
void hpp::constraints::DifferentiableFunctionSet::merge ( const DifferentiableFunctionSetPtr_t other)
inline

The output columns selection of other is not taken into account.

std::ostream& hpp::constraints::DifferentiableFunctionSet::print ( std::ostream &  o) const
virtual

Display object in a stream.

Reimplemented from hpp::constraints::DifferentiableFunction.