hpp-pinocchio  6.0.0
Wrapping of the kinematic/dynamic chain Pinocchio for HPP.
joint.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016 CNRS
3 // Author: NMansard from Florent Lamiraux
4 //
5 //
6 
7 // Redistribution and use in source and binary forms, with or without
8 // modification, are permitted provided that the following conditions are
9 // met:
10 //
11 // 1. Redistributions of source code must retain the above copyright
12 // notice, this list of conditions and the following disclaimer.
13 //
14 // 2. Redistributions in binary form must reproduce the above copyright
15 // notice, this list of conditions and the following disclaimer in the
16 // documentation and/or other materials provided with the distribution.
17 //
18 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
21 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
22 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
24 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
26 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
29 // DAMAGE.
30 
31 #ifndef HPP_PINOCCHIO_JOINT_HH
32 #define HPP_PINOCCHIO_JOINT_HH
33 
34 #include <cstddef>
35 #include <hpp/pinocchio/config.hh>
36 #include <hpp/pinocchio/fwd.hh>
37 #include <hpp/util/serialization-fwd.hh>
38 
39 namespace hpp {
40 namespace pinocchio {
58  public:
61 
68  static JointPtr_t create(DeviceWkPtr_t device, JointIndex indexInJointList);
69 
74  Joint(DeviceWkPtr_t device, JointIndex indexInJointList);
75 
76  ~Joint() {}
78  // -----------------------------------------------------------------------
81 
83  const std::string& name() const;
84 
86  // -----------------------------------------------------------------------
89 
92  return currentTransformation(data());
93  }
94 
96  const Transform3s& currentTransformation(const DeviceData& data) const;
97 
99  // -----------------------------------------------------------------------
102 
105 
108 
111 
114 
116  // -----------------------------------------------------------------------
119 
122 
124  std::size_t numberChildJoints() const;
125 
127  JointPtr_t childJoint(std::size_t rank) const;
128 
132 
134  // -----------------------------------------------------------------------
137 
141  void isBounded(size_type rank, bool bounded);
143  bool isBounded(size_type rank) const;
149  void lowerBound(size_type rank, value_type lowerBound);
151  void upperBound(size_type rank, value_type upperBound);
153  void lowerBounds(vectorIn_t lowerBounds);
155  void upperBounds(vectorIn_t upperBounds);
156 
166 
176 
179  if (maximalDistanceToParent_ < 0) computeMaximalDistanceToParent();
180  return maximalDistanceToParent_;
181  }
182 
184  protected:
187 
188  public:
189  // -----------------------------------------------------------------------
192 
199  JointJacobian_t& jacobian(const bool localFrame = true) const {
200  return jacobian(data(), localFrame);
201  }
202 
211  const bool localFrame = true) const;
212 
214  // -----------------------------------------------------------------------
215 
217  DeviceConstPtr_t robot() const { return devicePtr.lock(); }
219  DevicePtr_t robot() { return devicePtr.lock(); }
220 
223 
226 
228 
230  std::ostream& display(std::ostream& os) const;
231 
234 
238 
241 
242  const JointIndex& index() const { return jointIndex; }
243 
247  static inline size_type index(const JointConstPtr_t& joint) {
248  return (joint ? joint->index() : 0);
249  }
250 
251  const JointModel& jointModel() const;
252 
254 
255  bool operator==(const Joint& other) const {
256  return index() == other.index() && robot() == other.robot();
257  }
258 
259  bool operator!=(const Joint& other) const { return !operator==(other); }
260 
261  protected:
263  DeviceWkPtr_t devicePtr;
265  std::vector<JointIndex> children;
266 
268  void setChildList();
270  const Model& model() const;
271  DeviceData& data() const;
272 
274  void selfAssert() const;
275 
276  friend class Device;
277 
278  Joint() {}
280 }; // class Joint
281 
282 inline std::ostream& operator<<(std::ostream& os, const Joint& joint) {
283  return joint.display(os);
284 }
285 
286 } // namespace pinocchio
287 } // namespace hpp
288 
289 #endif // HPP_PINOCCHIO_JOINT_HH
Robot with geometric and dynamic pinocchio.
Definition: device.hh:60
Definition: joint.hh:57
JointJacobian_t & jacobian(DeviceData &data, const bool localFrame=true) const
void isBounded(size_type rank, bool bounded)
value_type maximalDistanceToParent_
Definition: joint.hh:262
static JointPtr_t create(DeviceWkPtr_t device, JointIndex indexInJointList)
JointPtr_t childJoint(std::size_t rank) const
Get child joint.
const Transform3s & positionInParentFrame() const
std::ostream & display(std::ostream &os) const
Display joint.
void upperBound(size_type rank, value_type upperBound)
Set upper bound of given degree of freedom.
const value_type & maximalDistanceToParent()
Maximal distance of joint origin to parent origin.
Definition: joint.hh:178
value_type upperBound(size_type rank) const
Get upper bound of given degree of freedom.
DeviceData & data() const
DevicePtr_t robot()
Access robot owning the object.
Definition: joint.hh:219
const Model & model() const
value_type lowerBound(size_type rank) const
Get lower bound of given degree of freedom.
size_type numberDof() const
Return number of degrees of freedom.
BodyPtr_t linkedBody() const
Get linked body.
void computeMaximalDistanceToParent()
Compute the maximal distance.
std::vector< JointIndex > children
Definition: joint.hh:265
static size_type index(const JointConstPtr_t &joint)
Definition: joint.hh:247
Joint()
Definition: joint.hh:278
JointPtr_t parentJoint() const
Get a pointer to the parent joint (if any).
void lowerBound(size_type rank, value_type lowerBound)
Set lower bound of given degree of freedom.
~Joint()
Definition: joint.hh:76
std::size_t numberChildJoints() const
Number of child joints.
size_type rankInVelocity() const
Return rank of the joint in the velocity vector.
void lowerBounds(vectorIn_t lowerBounds)
Set lower bounds.
const std::string & name() const
Get name.
DeviceConstPtr_t robot() const
Access robot owning the object.
Definition: joint.hh:217
size_type rankInConfiguration() const
Return rank of the joint in the configuration vector.
value_type upperBoundLinearVelocity() const
const Transform3s & currentTransformation(const DeviceData &data) const
Joint transformation.
void selfAssert() const
Assert that the members of the struct are valid (no null pointer, etc).
LiegroupSpacePtr_t RnxSOnConfigurationSpace() const
Joint(DeviceWkPtr_t device, JointIndex indexInJointList)
bool operator==(const Joint &other) const
Definition: joint.hh:255
bool operator!=(const Joint &other) const
Definition: joint.hh:259
void setChildList()
Store list of childrens.
value_type upperBoundAngularVelocity() const
const JointIndex & index() const
Definition: joint.hh:242
void upperBounds(vectorIn_t upperBounds)
Set upper bounds.
const Transform3s & currentTransformation() const
Joint transformation.
Definition: joint.hh:91
DeviceWkPtr_t devicePtr
Definition: joint.hh:263
size_type configSize() const
Return number of degrees of freedom.
JointIndex jointIndex
Definition: joint.hh:264
const JointModel & jointModel() const
JointJacobian_t & jacobian(const bool localFrame=true) const
Definition: joint.hh:199
bool isBounded(size_type rank) const
Get whether given degree of freedom is bounded.
LiegroupSpacePtr_t configurationSpace() const
Get configuration space of joint.
#define HPP_PINOCCHIO_DLLAPI
Definition: config.hh:88
shared_ptr< Device > DevicePtr_t
Definition: fwd.hh:118
shared_ptr< Joint > JointPtr_t
Definition: fwd.hh:123
::pinocchio::ModelTpl< value_type, 0, JointCollectionTpl > Model
Definition: fwd.hh:77
std::ostream & operator<<(std::ostream &os, const hpp::pinocchio::Device &device)
Definition: device.hh:366
shared_ptr< LiegroupSpace > LiegroupSpacePtr_t
Definition: fwd.hh:150
matrix_t::Index size_type
Definition: fwd.hh:97
Eigen::Matrix< value_type, 6, Eigen::Dynamic > JointJacobian_t
Definition: fwd.hh:101
::pinocchio::JointModelTpl< value_type, 0, JointCollectionTpl > JointModel
Definition: fwd.hh:84
shared_ptr< Body > BodyPtr_t
Definition: fwd.hh:109
::pinocchio::SE3 Transform3s
Definition: fwd.hh:81
double value_type
Definition: fwd.hh:51
::pinocchio::JointIndex JointIndex
Definition: fwd.hh:74
shared_ptr< const Joint > JointConstPtr_t
Definition: fwd.hh:124
shared_ptr< const Device > DeviceConstPtr_t
Definition: fwd.hh:119
Eigen::Ref< const vector_t > vectorIn_t
Definition: fwd.hh:93
Utility functions.
Definition: body.hh:39
Definition: collision-object.hh:40
Definition: device-data.hh:51