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


Public Types | |
| typedef shared_ptr< Difference > | Ptr_t |
Public Member Functions | |
| Difference (const DifferentiableFunctionPtr_t &inner, const size_type &nArgs, const size_type &nDers, const segment_t &lInArgs, const segment_t &lInDers, const segment_t &rInArgs, const segment_t &rInDers) | |
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. | |
| 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 |
Protected Member Functions | |
| void | impl_compute (LiegroupElementRef y, vectorIn_t arg) const |
| User implementation of function evaluation. | |
| void | impl_jacobian (matrixOut_t J, vectorIn_t arg) const |
| bool | isEqual (const DifferentiableFunction &other) const |
| std::ostream & | print (std::ostream &os) const |
| Display object in a stream. | |
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 | |
| DifferentiableFunctionPtr_t | inner_ |
| const segment_t | lsa_ |
| const segment_t | lsd_ |
| const segment_t | rsa_ |
| const segment_t | rsd_ |
| LiegroupElement | l_ |
| LiegroupElement | r_ |
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_ |
Compute the difference between the value of the function in two points. i.e.: \( f (q_0, ... , q_n) = f_{inner} (q_{left}) - f_{inner} (q_{right}) \)
| typedef shared_ptr<Difference> hpp::constraints::function::Difference::Ptr_t |
| hpp::constraints::function::Difference::Difference | ( | const DifferentiableFunctionPtr_t & | inner, |
| const size_type & | nArgs, | ||
| const size_type & | nDers, | ||
| const segment_t & | lInArgs, | ||
| const segment_t & | lInDers, | ||
| const segment_t & | rInArgs, | ||
| const segment_t & | rInDers | ||
| ) |
Constructor
| inner | function f, |
| nArgs,nDers | size of the input space of this function, |
| lInArgs,lInders | configuration and velocity intervals defining \(q_{left}\), |
| rInArgs,rInders | configuration and velocity intervals defining \(q_{right}\), |
|
inlineprotectedvirtual |
User implementation of function evaluation.
Implements hpp::constraints::DifferentiableFunction.
|
inlineprotectedvirtual |
Implements hpp::constraints::DifferentiableFunction.
|
inlineprotectedvirtual |
Reimplemented from hpp::constraints::DifferentiableFunction.
|
protectedvirtual |
Display object in a stream.
Reimplemented from hpp::constraints::DifferentiableFunction.
|
protected |
|
mutableprotected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |