30 #ifndef HPP_CONSTRAINTS_DIFFERENTIABLE_FUNCTION_HH
31 #define HPP_CONSTRAINTS_DIFFERENTIABLE_FUNCTION_HH
35 #include <hpp/pinocchio/liegroup-element.hh>
36 #include <hpp/util/debug.hh>
37 #include <hpp/util/serialization-fwd.hh>
40 namespace constraints {
71 assert(argument.size() == inputSize());
73 impl_compute(result, argument);
80 assert(result.space()->nq() == outputSize());
81 assert(argument.size() == inputSize());
82 impl_compute(result, argument);
89 assert(argument.size() == inputSize());
90 assert(jacobian.rows() == outputDerivativeSize());
91 assert(jacobian.cols() == inputDerivativeSize());
92 impl_jacobian(jacobian, argument);
102 return activeDerivativeParameters_;
122 const std::string&
name()
const {
return name_; }
125 virtual std::ostream&
print(std::ostream& o)
const;
127 std::string
context()
const {
return context_; }
129 void context(
const std::string& c) { context_ = c; }
143 std::sqrt(Eigen::NumTraits<value_type>::epsilon()))
const;
157 std::sqrt(Eigen::NumTraits<value_type>::epsilon()))
const;
176 return std::pair<JointConstPtr_t, JointConstPtr_t>(
nullptr,
nullptr);
188 std::string name = std::string());
198 std::string name = std::string());
207 if (name_ != other.name_)
return false;
208 if (inputSize_ != other.
inputSize_)
return false;
210 if (*outputSpace_ != *(other.
outputSpace_))
return false;
234 std::string context_;
Definition: differentiable-function-set.hh:45
Definition: differentiable-function.hh:63
LiegroupSpacePtr_t outputSpace_
Dimension of output vector.
Definition: differentiable-function.hh:220
DifferentiableFunction(size_type sizeInput, size_type sizeInputDerivative, const LiegroupSpacePtr_t &outputSpace, std::string name=std::string())
Concrete class constructor should call this constructor.
size_type inputDerivativeSize_
Dimension of input derivative.
Definition: differentiable-function.hh:218
virtual bool isEqual(const DifferentiableFunction &other) const
Definition: differentiable-function.hh:206
bool operator==(DifferentiableFunction const &other) const
std::string context() const
Definition: differentiable-function.hh:127
bool operator!=(DifferentiableFunction const &b) const
size_type inputSize_
Dimension of input vector.
Definition: differentiable-function.hh:216
void finiteDifferenceCentral(matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot=DevicePtr_t(), value_type eps=std::sqrt(Eigen::NumTraits< value_type >::epsilon())) const
void context(const std::string &c)
Definition: differentiable-function.hh:129
virtual ~DifferentiableFunction()
Definition: differentiable-function.hh:65
size_type outputSize() const
Get dimension of output vector.
Definition: differentiable-function.hh:116
virtual void impl_jacobian(matrixOut_t jacobian, vectorIn_t arg) const =0
DifferentiableFunction(size_type sizeInput, size_type sizeInputDerivative, size_type sizeOutput, std::string name=std::string())
Concrete class constructor should call this constructor.
size_type inputDerivativeSize() const
Definition: differentiable-function.hh:112
size_type outputDerivativeSize() const
Get dimension of output derivative vector.
Definition: differentiable-function.hh:118
const std::string & name() const
Get function name.
Definition: differentiable-function.hh:122
virtual std::ostream & print(std::ostream &o) const
Display object in a stream.
virtual void impl_compute(LiegroupElementRef result, vectorIn_t argument) const =0
User implementation of function evaluation.
size_type inputSize() const
Get dimension of input vector.
Definition: differentiable-function.hh:106
ArrayXb activeParameters_
Definition: differentiable-function.hh:225
const ArrayXb & activeDerivativeParameters() const
Definition: differentiable-function.hh:101
LiegroupElement operator()(vectorIn_t argument) const
Definition: differentiable-function.hh:70
const ArrayXb & activeParameters() const
Definition: differentiable-function.hh:97
virtual std::pair< JointConstPtr_t, JointConstPtr_t > dependsOnRelPoseBetween(DeviceConstPtr_t) const
Definition: differentiable-function.hh:174
void jacobian(matrixOut_t jacobian, vectorIn_t argument) const
Definition: differentiable-function.hh:88
LiegroupSpacePtr_t outputSpace() const
Get output space.
Definition: differentiable-function.hh:114
DifferentiableFunction()
Definition: differentiable-function.hh:239
ArrayXb activeDerivativeParameters_
Definition: differentiable-function.hh:229
void value(LiegroupElementRef result, vectorIn_t argument) const
Definition: differentiable-function.hh:79
void finiteDifferenceForward(matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot=DevicePtr_t(), value_type eps=std::sqrt(Eigen::NumTraits< value_type >::epsilon())) const
#define HPP_CONSTRAINTS_DLLAPI
Definition: config.hh:88
assert(d.lhs()._blocks()==d.rhs()._blocks())
pinocchio::LiegroupElement LiegroupElement
Definition: fwd.hh:65
pinocchio::DevicePtr_t DevicePtr_t
Definition: fwd.hh:109
pinocchio::DeviceConstPtr_t DeviceConstPtr_t
Definition: fwd.hh:110
pinocchio::LiegroupSpacePtr_t LiegroupSpacePtr_t
Definition: fwd.hh:69
ComparisonTypes_t operator<<(const ComparisonType &a, const ComparisonType &b)
Definition: comparison-types.hh:61
pinocchio::size_type size_type
Definition: fwd.hh:47
pinocchio::ArrayXb ArrayXb
Definition: fwd.hh:80
pinocchio::value_type value_type
Definition: fwd.hh:48
pinocchio::vectorIn_t vectorIn_t
Definition: fwd.hh:60
Eigen::Ref< matrix_t > matrixOut_t
Definition: fwd.hh:58
pinocchio::LiegroupElementRef LiegroupElementRef
Definition: fwd.hh:66
Definition: active-set-differentiable-function.hh:36