Identity function \( q_{out} = q_{in} \). More...
#include <hpp/constraints/affine-function.hh>
Public Member Functions | |
| Identity (const LiegroupSpacePtr_t space, const std::string &name) | |
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 ArrayXb & | activeParameters () const |
| Returns a vector of booleans that indicates whether the corresponding configuration parameter influences this constraints. More... | |
| const ArrayXb & | activeDerivativeParameters () 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... | |
Static Public Member Functions | |
| static IdentityPtr_t | create (const LiegroupSpacePtr_t space, const std::string &name) |
Protected Member Functions | |
| void | impl_compute (LiegroupElementRef y, vectorIn_t arg) const |
| User implementation of function evaluation. More... | |
| void | impl_jacobian (matrixOut_t J, vectorIn_t) 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... | |
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... | |
Identity function \( q_{out} = q_{in} \).
|
inline |
|
inlinestatic |
|
inlineprotectedvirtual |
User implementation of function evaluation.
Implements hpp::constraints::DifferentiableFunction.
|
inlineprotectedvirtual |
Implements hpp::constraints::DifferentiableFunction.