hpp-constraints  4.9.1
Definition of basic geometric constraints for motion planning
hpp::constraints::DifferentiableFunction Class Referenceabstract

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

Inheritance diagram for hpp::constraints::DifferentiableFunction:

Public Member Functions

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 ArrayXbactiveParameters () const
 
const ArrayXbactiveDerivativeParameters () 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
 

Protected Member Functions

 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
 

Protected Attributes

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_
 

Friends

class DifferentiableFunctionSet
 

Detailed Description

Differentiable function from a Lie group, for instance the configuration space of a robot (hpp::pinocchio::Device) to a another Lie group.

Note that the input Lie group is only represented by the sizes of the elements and of the velocities: methods inputSize and inputDerivativeSize

The output space can be accessed by method outputSpace.

The value of the function for a given input can be accessed by method value . The Jacobian of the function for a given input can be accessed by method jacobian .

Constructor & Destructor Documentation

◆ ~DifferentiableFunction()

virtual hpp::constraints::DifferentiableFunction::~DifferentiableFunction ( )
inlinevirtual

◆ DifferentiableFunction() [1/2]

hpp::constraints::DifferentiableFunction::DifferentiableFunction ( size_type  sizeInput,
size_type  sizeInputDerivative,
size_type  sizeOutput,
std::string  name = std::string() 
)
protected

Concrete class constructor should call this constructor.

Parameters
sizeInputdimension of the function input
sizeInputDerivativedimension of the function input derivative,
sizeOutputdimension of the output,
namefunction's name

◆ DifferentiableFunction() [2/2]

hpp::constraints::DifferentiableFunction::DifferentiableFunction ( size_type  sizeInput,
size_type  sizeInputDerivative,
const LiegroupSpacePtr_t outputSpace,
std::string  name = std::string() 
)
protected

Concrete class constructor should call this constructor.

Parameters
sizeInputdimension of the function input
sizeInputDerivativedimension of the function input derivative,
outputSpaceoutput space of the function.
namefunction name

Member Function Documentation

◆ activeDerivativeParameters()

const ArrayXb& hpp::constraints::DifferentiableFunction::activeDerivativeParameters ( ) const
inline

Returns a vector of booleans that indicates whether the corresponding velocity parameter influences this constraints.

◆ activeParameters()

const ArrayXb& hpp::constraints::DifferentiableFunction::activeParameters ( ) const
inline

Returns a vector of booleans that indicates whether the corresponding configuration parameter influences this constraints.

◆ context() [1/2]

std::string hpp::constraints::DifferentiableFunction::context ( ) const
inline

◆ context() [2/2]

void hpp::constraints::DifferentiableFunction::context ( const std::string &  c)
inline

◆ finiteDifferenceCentral()

void hpp::constraints::DifferentiableFunction::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.

Return values
jacobianjacobian will be stored in this argument
Parameters
argpoint at which the jacobian will be computed
robotuse to add configuration and velocities. If set to NULL, the configuration space is considered a vector space.
epsrefers to \(\epsilon\) in http://en.wikipedia.org/wiki/Numerical_differentiation Evaluate the function 2*x.size() times but more precise the finiteDifferenceForward

◆ finiteDifferenceForward()

void hpp::constraints::DifferentiableFunction::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.

Return values
jacobianjacobian will be stored in this argument
Parameters
argpoint at which the jacobian will be computed
robotuse to add configuration and velocities. If set to NULL, the configuration space is considered a vector space.
epsrefers to \(\epsilon\) in http://en.wikipedia.org/wiki/Numerical_differentiation Evaluate the function (x.size() + 1) times but less precise the finiteDifferenceCentral

◆ impl_compute()

◆ impl_jacobian()

◆ inputDerivativeSize()

size_type hpp::constraints::DifferentiableFunction::inputDerivativeSize ( ) const
inline

Get dimension of input derivative vector

The dimension of configuration vectors might differ from the dimension of velocity vectors since some joints are represented by non minimal size vectors: e.g. quaternion for SO(3)

◆ inputSize()

size_type hpp::constraints::DifferentiableFunction::inputSize ( ) const
inline

Get dimension of input vector.

◆ jacobian()

void hpp::constraints::DifferentiableFunction::jacobian ( matrixOut_t  jacobian,
vectorIn_t  argument 
) const
inline

Computes the jacobian.

Return values
jacobianjacobian will be stored in this argument
Parameters
argumentpoint at which the jacobian will be computed

◆ name()

const std::string& hpp::constraints::DifferentiableFunction::name ( ) const
inline

Get function name.

Returns
Function name.

◆ operator()()

LiegroupElement hpp::constraints::DifferentiableFunction::operator() ( vectorIn_t  argument) const
inline

Evaluate the function at a given parameter.

Note
parameters should be of the correct size.

◆ outputDerivativeSize()

size_type hpp::constraints::DifferentiableFunction::outputDerivativeSize ( ) const
inline

Get dimension of output derivative vector.

◆ outputSize()

size_type hpp::constraints::DifferentiableFunction::outputSize ( ) const
inline

Get dimension of output vector.

◆ outputSpace()

LiegroupSpacePtr_t hpp::constraints::DifferentiableFunction::outputSpace ( ) const
inline

Get output space.

◆ print()

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

◆ value()

void hpp::constraints::DifferentiableFunction::value ( LiegroupElementRef  result,
vectorIn_t  argument 
) const
inline

Evaluate the function at a given parameter.

Note
parameters should be of the correct size.

Friends And Related Function Documentation

◆ DifferentiableFunctionSet

friend class DifferentiableFunctionSet
friend

Member Data Documentation

◆ activeDerivativeParameters_

ArrayXb hpp::constraints::DifferentiableFunction::activeDerivativeParameters_
protected

Initialized to true by this class. Child class are responsible for updating it.

See also
activeDerivativeParameters

◆ activeParameters_

ArrayXb hpp::constraints::DifferentiableFunction::activeParameters_
protected

Initialized to true by this class. Child class are responsible for updating it.

See also
activeParameters

◆ inputDerivativeSize_

size_type hpp::constraints::DifferentiableFunction::inputDerivativeSize_
protected

Dimension of input derivative.

◆ inputSize_

size_type hpp::constraints::DifferentiableFunction::inputSize_
protected

Dimension of input vector.

◆ outputSpace_

LiegroupSpacePtr_t hpp::constraints::DifferentiableFunction::outputSpace_
protected

Dimension of output vector.


The documentation for this class was generated from the following file: