hpp-constraints
4.9.1
Definition of basic geometric constraints for motion planning
|
#include <hpp/constraints/explicit/implicit-function.hh>
Public Types | |
typedef boost::shared_ptr< ImplicitFunction > | Ptr_t |
Public Member Functions | |
const DifferentiableFunctionPtr_t & | inputToOutput () const |
Get function f that maps input variables to output variables. 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 |
Static Public Member Functions | |
static Ptr_t | create (const DevicePtr_t &robot, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity) HPP_CONSTRAINTS_DEPRECATED |
static Ptr_t | create (const DevicePtr_t &robot, const DifferentiableFunctionPtr_t &function, const DifferentiableFunctionPtr_t &g, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity) HPP_CONSTRAINTS_DEPRECATED |
static Ptr_t | create (const LiegroupSpacePtr_t &configSpace, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity) |
Protected Member Functions | |
ImplicitFunction (const DevicePtr_t &robot, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity) HPP_CONSTRAINTS_DEPRECATED | |
ImplicitFunction (const LiegroupSpacePtr_t &configSpace, const DifferentiableFunctionPtr_t &function, const segments_t &inputConf, const segments_t &outputConf, const segments_t &inputVelocity, const segments_t &outputVelocity) | |
void | impl_compute (LiegroupElementRef result, vectorIn_t argument) const |
Compute g (q_out) - f (q_in) More... | |
void | impl_jacobian (matrixOut_t jacobian, vectorIn_t arg) const |
Compute Jacobian of g (q_out) - f (q_in) with respect to q. More... | |
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_ |
ArrayXb | activeDerivativeParameters_ |
Function of the form q -> g (q_out) - f (q_in)
where
This class is mainly used to create hpp::constraints::Explicit instances.
typedef boost::shared_ptr<ImplicitFunction> hpp::constraints::explicit_::ImplicitFunction::Ptr_t |
create instance and return shared pointer
|
protected |
Constructor
|
protected |
Constructor
configSpace | input space of this function - usually a robot configuration space, |
function | function f, |
inputConf | set of indices defining q_in, |
inputVelocity | set of indices defining q_in derivative, |
outputConf | set of indices defining q_out |
outputVelocity | set of indices defining q_out derivative |
|
static |
|
static |
create instance and return shared pointer
|
static |
create instance and return shared pointer
configSpace | input space of this function - usually a robot configuration space, |
function | function f, |
inputConf | set of indices defining q_in, |
inputVelocity | set of indices defining q_in derivative, |
outputConf | set of indices defining q_out |
outputVelocity | set of indices defining q_out derivative |
|
protectedvirtual |
Compute g (q_out) - f (q_in)
Implements hpp::constraints::DifferentiableFunction.
|
protectedvirtual |
Compute Jacobian of g (q_out) - f (q_in) with respect to q.
Implements hpp::constraints::DifferentiableFunction.
const DifferentiableFunctionPtr_t& hpp::constraints::explicit_::ImplicitFunction::inputToOutput | ( | ) | const |
Get function f that maps input variables to output variables.