hpp-constraints
4.9.1
Definition of basic geometric constraints for motion planning
|
#include <hpp/constraints/active-set-differentiable-function.hh>
Public Member Functions | |
ActiveSetDifferentiableFunction (const DifferentiableFunctionPtr_t &f, segments_t intervals) | |
const DifferentiableFunction & | function () const |
Get the original function. More... | |
const DifferentiableFunctionPtr_t & | functionPtr () const |
Get the original function. More... | |
Public Member Functions inherited from hpp::constraints::DifferentiableFunction | |
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 |
Protected Types | |
typedef std::vector< segments_t > | intervalss_t |
Protected Member Functions | |
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 |
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_ |
ArrayXb | activeDerivativeParameters_ |
Handle bounds on input variables of a differentiable function.
This class is a decorator of class DifferentiableFunction that sets to 0 some columns of the Jacobian of the function.
The class is used to handle saturation of input variables of the function during numerical resolution of implicit constraints built with the function.
|
protected |
|
inline |
Constructor
f | initial differentiable function, |
intervals | set of intervals of indices corresponding to saturated input variables. |
|
inline |
Get the original function.
|
inline |
Get the original function.
|
inlineprotectedvirtual |
User implementation of function evaluation.
Implements hpp::constraints::DifferentiableFunction.
|
inlineprotectedvirtual |
Implements hpp::constraints::DifferentiableFunction.
|
protected |
|
protected |