Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
hpp::constraints::ActiveSetDifferentiableFunction Class Reference

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

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

Public Member Functions

 ActiveSetDifferentiableFunction (const DifferentiableFunctionPtr_t &f, segments_t intervals)
 
const DifferentiableFunctionfunction () const
 
const DifferentiableFunctionPtr_tfunctionPtr () const
 
- 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 (LiegroupElement &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...
 
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
 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...
 

Protected Types

typedef std::vector< segments_tintervalss_t
 

Protected Member Functions

virtual void impl_compute (LiegroupElement &result, vectorIn_t argument) const
 User implementation of function evaluation. More...
 
virtual void impl_jacobian (matrixOut_t jacobian, vectorIn_t arg) const
 
- 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...
 

Protected Attributes

DifferentiableFunctionPtr_t function_
 
segments_t intervals_
 
- 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...
 

Member Typedef Documentation

◆ intervalss_t

Constructor & Destructor Documentation

◆ ActiveSetDifferentiableFunction()

hpp::constraints::ActiveSetDifferentiableFunction::ActiveSetDifferentiableFunction ( const DifferentiableFunctionPtr_t f,
segments_t  intervals 
)
inline

Member Function Documentation

◆ function()

const DifferentiableFunction& hpp::constraints::ActiveSetDifferentiableFunction::function ( ) const
inline

◆ functionPtr()

const DifferentiableFunctionPtr_t& hpp::constraints::ActiveSetDifferentiableFunction::functionPtr ( ) const
inline

◆ impl_compute()

virtual void hpp::constraints::ActiveSetDifferentiableFunction::impl_compute ( LiegroupElement result,
vectorIn_t  argument 
) const
inlineprotectedvirtual

User implementation of function evaluation.

Implements hpp::constraints::DifferentiableFunction.

◆ impl_jacobian()

virtual void hpp::constraints::ActiveSetDifferentiableFunction::impl_jacobian ( matrixOut_t  jacobian,
vectorIn_t  arg 
) const
inlineprotectedvirtual

Member Data Documentation

◆ function_

DifferentiableFunctionPtr_t hpp::constraints::ActiveSetDifferentiableFunction::function_
protected

◆ intervals_

segments_t hpp::constraints::ActiveSetDifferentiableFunction::intervals_
protected