Differentiable function.
More...
#include <hpp/constraints/differentiable-function.hh>
◆ ~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
-
sizeInput | dimension of the function input |
sizeInputDerivative | dimension of the function input derivative, |
sizeOutput | dimension of the output, |
name | function'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
-
sizeInput | dimension of the function input |
sizeInputDerivative | dimension of the function input derivative, |
outputSpace | output space of the function. |
name | function name |
◆ 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()
Approximate the jacobian using forward finite difference.
- Return values
-
jacobian | jacobian will be stored in this argument |
- Parameters
-
arg | point at which the jacobian will be computed |
robot | use to add configuration and velocities. If set to NULL, the configuration space is considered a vector space. |
eps | refers to \(\epsilon\) in http://en.wikipedia.org/wiki/Numerical_differentiation Evaluate the function 2*x.size() times but more precise the finiteDifferenceForward |
◆ finiteDifferenceForward()
Approximate the jacobian using forward finite difference.
- Return values
-
jacobian | jacobian will be stored in this argument |
- Parameters
-
arg | point at which the jacobian will be computed |
robot | use to add configuration and velocities. If set to NULL, the configuration space is considered a vector space. |
eps | refers 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()
virtual void hpp::constraints::DifferentiableFunction::impl_jacobian |
( |
matrixOut_t |
jacobian, |
|
|
vectorIn_t |
arg |
|
) |
| const |
|
protectedpure virtual |
◆ 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
-
jacobian | jacobian will be stored in this argument |
- Parameters
-
argument | point at which the jacobian will be computed |
References Eigen::assert().
◆ name()
const std::string& hpp::constraints::DifferentiableFunction::name |
( |
| ) |
const |
|
inline |
Get function name.
- Returns
- Function name.
◆ operator()()
Evaluate the function at a given parameter.
- Note
- parameters should be of the correct size.
References Eigen::assert().
◆ outputDerivativeSize()
size_type hpp::constraints::DifferentiableFunction::outputDerivativeSize |
( |
| ) |
const |
|
inline |
◆ outputSize()
size_type hpp::constraints::DifferentiableFunction::outputSize |
( |
| ) |
const |
|
inline |
◆ outputSpace()
Get output element.
Getting an output element enables users to know the type of Liegroup the function output values lie in.
◆ print()
virtual std::ostream& hpp::constraints::DifferentiableFunction::print |
( |
std::ostream & |
o | ) |
const |
|
virtual |
◆ value()
Evaluate the function at a given parameter.
- Note
- parameters should be of the correct size.
References Eigen::assert().
◆ DifferentiableFunctionSet
◆ activeDerivativeParameters_
ArrayXb hpp::constraints::DifferentiableFunction::activeDerivativeParameters_ |
|
protected |
◆ 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_
Dimension of output vector.