hpp-constraints  6.0.0
Definition of basic geometric constraints for motion planning
differentiable-function.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2014 CNRS
3 // Authors: Florent Lamiraux
4 //
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are
8 // met:
9 //
10 // 1. Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 //
13 // 2. Redistributions in binary form must reproduce the above copyright
14 // notice, this list of conditions and the following disclaimer in the
15 // documentation and/or other materials provided with the distribution.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
18 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
19 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
20 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
21 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
22 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
23 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
24 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
25 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
26 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
28 // DAMAGE.
29 
30 #ifndef HPP_CONSTRAINTS_DIFFERENTIABLE_FUNCTION_HH
31 #define HPP_CONSTRAINTS_DIFFERENTIABLE_FUNCTION_HH
32 
34 #include <hpp/constraints/fwd.hh>
35 #include <hpp/pinocchio/liegroup-element.hh>
36 #include <hpp/util/debug.hh>
37 #include <hpp/util/serialization-fwd.hh>
38 
39 namespace hpp {
40 namespace constraints {
41 
44 
64  public:
66 
71  assert(argument.size() == inputSize());
72  LiegroupElement result(outputSpace_);
73  impl_compute(result, argument);
74  return result;
75  }
79  void value(LiegroupElementRef result, vectorIn_t argument) const {
80  assert(result.space()->nq() == outputSize());
81  assert(argument.size() == inputSize());
82  impl_compute(result, argument);
83  }
88  void jacobian(matrixOut_t jacobian, vectorIn_t argument) const {
89  assert(argument.size() == inputSize());
90  assert(jacobian.rows() == outputDerivativeSize());
91  assert(jacobian.cols() == inputDerivativeSize());
92  impl_jacobian(jacobian, argument);
93  }
94 
97  const ArrayXb& activeParameters() const { return activeParameters_; }
98 
102  return activeDerivativeParameters_;
103  }
104 
106  size_type inputSize() const { return inputSize_; }
112  size_type inputDerivativeSize() const { return inputDerivativeSize_; }
114  LiegroupSpacePtr_t outputSpace() const { return outputSpace_; }
116  size_type outputSize() const { return outputSpace_->nq(); }
118  size_type outputDerivativeSize() const { return outputSpace_->nv(); }
122  const std::string& name() const { return name_; }
123 
125  virtual std::ostream& print(std::ostream& o) const;
126 
127  std::string context() const { return context_; }
128 
129  void context(const std::string& c) { context_ = c; }
130 
141  matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot = DevicePtr_t(),
142  value_type eps =
143  std::sqrt(Eigen::NumTraits<value_type>::epsilon())) const;
144 
155  matrixOut_t jacobian, vectorIn_t arg, DevicePtr_t robot = DevicePtr_t(),
156  value_type eps =
157  std::sqrt(Eigen::NumTraits<value_type>::epsilon())) const;
158 
159  bool operator==(DifferentiableFunction const& other) const;
160  bool operator!=(DifferentiableFunction const& b) const;
161 
174  virtual std::pair<JointConstPtr_t, JointConstPtr_t> dependsOnRelPoseBetween(
175  DeviceConstPtr_t /*robot*/) const {
176  return std::pair<JointConstPtr_t, JointConstPtr_t>(nullptr, nullptr);
177  };
178 
179  protected:
186  DifferentiableFunction(size_type sizeInput, size_type sizeInputDerivative,
187  size_type sizeOutput,
188  std::string name = std::string());
189 
196  DifferentiableFunction(size_type sizeInput, size_type sizeInputDerivative,
197  const LiegroupSpacePtr_t& outputSpace,
198  std::string name = std::string());
199 
201  virtual void impl_compute(LiegroupElementRef result,
202  vectorIn_t argument) const = 0;
203 
204  virtual void impl_jacobian(matrixOut_t jacobian, vectorIn_t arg) const = 0;
205 
206  virtual bool isEqual(const DifferentiableFunction& other) const {
207  if (name_ != other.name_) return false;
208  if (inputSize_ != other.inputSize_) return false;
209  if (inputDerivativeSize_ != other.inputDerivativeSize_) return false;
210  if (*outputSpace_ != *(other.outputSpace_)) return false;
211 
212  return true;
213  }
214 
221 
230 
231  private:
232  std::string name_;
234  std::string context_;
235 
237 
238  protected:
240 
241  private:
242  HPP_SERIALIZABLE();
243 }; // class DifferentiableFunction
244 inline std::ostream& operator<<(std::ostream& os,
245  const DifferentiableFunction& f) {
246  return f.print(os);
247 }
249 } // namespace constraints
250 } // namespace hpp
251 
252 /*
253 // This will override boost::shared_ptr 's equality operator
254 // between 2 DifferentiableFunctionPtr_t
255 namespace boost {
256  using namespace hpp::constraints;
257  typedef DifferentiableFunction T;
258  typedef shared_ptr<T> TPtr;
259 
260  template<> inline bool operator==<T, T> (TPtr const & a, TPtr const & b)
261 BOOST_SP_NOEXCEPT
262  {
263  return *a == *b;
264  }
265 
266  template<> inline bool operator!=<T, T> (TPtr const & a, TPtr const & b)
267 BOOST_SP_NOEXCEPT
268  {
269  return !(a == b);
270  }
271 }
272 */
273 
274 #endif // HPP_CONSTRAINTS_DIFFERENTIABLE_FUNCTION_HH
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