hpp-constraints  6.0.0
Definition of basic geometric constraints for motion planning
implicit-function.hh
Go to the documentation of this file.
1 // Copyright (c) 2015 - 2018 LAAS-CNRS
2 // Authors: Florent Lamiraux, Joseph Mirabel
3 //
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // 1. Redistributions of source code must retain the above copyright
10 // notice, this list of conditions and the following disclaimer.
11 //
12 // 2. Redistributions in binary form must reproduce the above copyright
13 // notice, this list of conditions and the following disclaimer in the
14 // documentation and/or other materials provided with the distribution.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
19 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
20 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
21 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
22 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
24 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
27 // DAMAGE.
28 
29 #ifndef HPP_CONSTRAINTS_EXPLICIT_IMPLICIT_FUNCTION_HH
30 #define HPP_CONSTRAINTS_EXPLICIT_IMPLICIT_FUNCTION_HH
31 
34 
35 namespace hpp {
36 namespace constraints {
37 namespace explicit_ {
50  public:
51  typedef shared_ptr<ImplicitFunction> Ptr_t;
62 
63  static Ptr_t create(const LiegroupSpacePtr_t& configSpace,
64  const DifferentiableFunctionPtr_t& function,
65  const segments_t& inputConf, const segments_t& outputConf,
66  const segments_t& inputVelocity,
67  const segments_t& outputVelocity);
68 
71 
72  protected:
82  const DifferentiableFunctionPtr_t& function,
83  const segments_t& inputConf, const segments_t& outputConf,
84  const segments_t& inputVelocity,
85  const segments_t& outputVelocity);
87  void impl_compute(LiegroupElementRef result, vectorIn_t argument) const;
88 
91 
92  bool isEqual(const DifferentiableFunction& other) const {
93  const ImplicitFunction& castother =
94  dynamic_cast<const ImplicitFunction&>(other);
95  if (!DifferentiableFunction::isEqual(other)) return false;
96 
97  if (robot_ != castother.robot_) return false;
98  if (inputToOutput_ != castother.inputToOutput_) return false;
99  if (inputConfIntervals_.rows() != castother.inputConfIntervals_.rows())
100  return false;
101  if (outputConfIntervals_.rows() != castother.outputConfIntervals_.rows())
102  return false;
103  if (inputDerivIntervals_.rows() != castother.inputDerivIntervals_.rows())
104  return false;
105  if (outputDerivIntervals_.rows() != castother.outputDerivIntervals_.rows())
106  return false;
107 
108  return true;
109  }
110 
125  std::pair<JointConstPtr_t, JointConstPtr_t> dependsOnRelPoseBetween(
126  DeviceConstPtr_t robot) const;
127 
128  private:
129  void computeJacobianBlocks();
130 
131  DevicePtr_t robot_;
132  DifferentiableFunctionPtr_t inputToOutput_;
133  Eigen::RowBlockIndices inputConfIntervals_;
134  Eigen::RowBlockIndices outputConfIntervals_;
135  Eigen::RowBlockIndices inputDerivIntervals_;
136  Eigen::RowBlockIndices outputDerivIntervals_;
137  std::vector<Eigen::MatrixBlocks<false, false> > outJacobian_;
138  std::vector<Eigen::MatrixBlocks<false, false> > inJacobian_;
139  mutable vector_t qIn_;
140  mutable LiegroupElement f_qIn_, qOut_;
141  mutable LiegroupElement result_;
142  // Jacobian of explicit function
143  mutable matrix_t Jf_;
144 
145  ImplicitFunction() {}
146  HPP_SERIALIZABLE();
147 }; // class ImplicitFunction
148 
149 } // namespace explicit_
150 } // namespace constraints
151 } // namespace hpp
152 
153 BOOST_CLASS_EXPORT_KEY(hpp::constraints::explicit_::ImplicitFunction)
154 
155 #endif // HPP_CONSTRAINTS_EXPLICIT_IMPLICIT_FUNCTION_HH
const RowIndices_t & rows() const
Definition: matrix-view.hh:675
Definition: differentiable-function.hh:63
virtual bool isEqual(const DifferentiableFunction &other) const
Definition: differentiable-function.hh:206
void jacobian(matrixOut_t jacobian, vectorIn_t argument) const
Definition: differentiable-function.hh:88
Definition: implicit-function.hh:49
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)
std::pair< JointConstPtr_t, JointConstPtr_t > dependsOnRelPoseBetween(DeviceConstPtr_t robot) const
const DifferentiableFunctionPtr_t & inputToOutput() const
Get function f that maps input variables to output variables.
shared_ptr< ImplicitFunction > Ptr_t
Definition: implicit-function.hh:51
bool isEqual(const DifferentiableFunction &other) const
Definition: implicit-function.hh:92
void impl_compute(LiegroupElementRef result, vectorIn_t argument) const
Compute g (q_out) - f (q_in)
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_jacobian(matrixOut_t jacobian, vectorIn_t arg) const
Compute Jacobian of g (q_out) - f (q_in) with respect to q.
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
shared_ptr< DifferentiableFunction > DifferentiableFunctionPtr_t
Definition: fwd.hh:113
pinocchio::vectorIn_t vectorIn_t
Definition: fwd.hh:60
pinocchio::matrix_t matrix_t
Definition: fwd.hh:56
Eigen::Ref< matrix_t > matrixOut_t
Definition: fwd.hh:58
std::vector< segment_t > segments_t
Definition: fwd.hh:84
pinocchio::vector_t vector_t
Definition: fwd.hh:59
pinocchio::LiegroupElementRef LiegroupElementRef
Definition: fwd.hh:66
Definition: active-set-differentiable-function.hh:36