|
hpp-constraints 6.0.0
Definition of basic geometric constraints for motion planning
|
#include <hpp/constraints/affine-function.hh>


Static Public Member Functions | |
| static ConstantFunctionPtr_t | create (const vector_t &constant, const size_type &sizeIn, const size_type &sizeInDer, const std::string name="ConstantFunction") |
| static ConstantFunctionPtr_t | create (const LiegroupElement &element, const size_type &sizeIn, const size_type &sizeInDer, const std::string name="ConstantFunction") |
Protected Member Functions | |
| ConstantFunction (const vector_t &constant, const size_type &sizeIn, const size_type &sizeInDer, const std::string name="ConstantFunction") | |
| ConstantFunction (const LiegroupElement &element, const size_type &sizeIn, const size_type &sizeInDer, const std::string name="ConstantFunction") | |
| void | impl_compute (LiegroupElementRef r, vectorIn_t) const |
| User implementation of function evaluation. | |
| void | impl_jacobian (matrixOut_t J, vectorIn_t) const |
| bool | isEqual (const DifferentiableFunction &other) 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. | |
| DifferentiableFunction (size_type sizeInput, size_type sizeInputDerivative, const LiegroupSpacePtr_t &outputSpace, std::string name=std::string()) | |
| Concrete class constructor should call this constructor. | |
| DifferentiableFunction () | |
Protected Attributes | |
| const LiegroupElement | c_ |
Protected Attributes inherited from hpp::constraints::DifferentiableFunction | |
| size_type | inputSize_ |
| Dimension of input vector. | |
| size_type | inputDerivativeSize_ |
| Dimension of input derivative. | |
| LiegroupSpacePtr_t | outputSpace_ |
| Dimension of output vector. | |
| ArrayXb | activeParameters_ |
| ArrayXb | activeDerivativeParameters_ |
Additional Inherited Members | |
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. | |
| size_type | inputDerivativeSize () const |
| LiegroupSpacePtr_t | outputSpace () const |
| Get output space. | |
| size_type | outputSize () const |
| Get dimension of output vector. | |
| size_type | outputDerivativeSize () const |
| Get dimension of output derivative vector. | |
| const std::string & | name () const |
| Get function name. | |
| virtual std::ostream & | print (std::ostream &o) const |
| Display object in a stream. | |
| 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 |
| bool | operator== (DifferentiableFunction const &other) const |
| bool | operator!= (DifferentiableFunction const &b) const |
| virtual std::pair< JointConstPtr_t, JointConstPtr_t > | dependsOnRelPoseBetween (DeviceConstPtr_t) const |
Constant function \( f(q) = C \)
|
inlineprotected |
|
inlineprotected |
|
inlinestatic |
|
inlinestatic |
|
inlineprotectedvirtual |
User implementation of function evaluation.
Implements hpp::constraints::DifferentiableFunction.
|
inlineprotectedvirtual |
Implements hpp::constraints::DifferentiableFunction.
|
inlineprotectedvirtual |
Reimplemented from hpp::constraints::DifferentiableFunction.
|
protected |