hpp-pinocchio  4.9.1
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 // This file is part of hpp-pinocchio
7 // hpp-pinocchio is free software: you can redistribute it
8 // and/or modify it under the terms of the GNU Lesser General Public
9 // License as published by the Free Software Foundation, either version
10 // 3 of the License, or (at your option) any later version.
11 //
12 // hpp-pinocchio is distributed in the hope that it will be
13 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
14 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
15 // General Lesser Public License for more details. You should have
16 // received a copy of the GNU Lesser General Public License along with
17 // hpp-pinocchio If not, see
18 // <http://www.gnu.org/licenses/>.
19 
20 #ifndef HPP_PINOCCHIO_JOINT_HH
21 # define HPP_PINOCCHIO_JOINT_HH
22 
23 # include <cstddef>
24 # include <hpp/pinocchio/fwd.hh>
25 # include <hpp/pinocchio/config.hh>
26 
27 namespace hpp {
28  namespace pinocchio {
45  class HPP_PINOCCHIO_DLLAPI Joint {
46  public:
49 
56  static JointPtr_t create (DeviceWkPtr_t device, JointIndex indexInJointList );
57 
62  Joint (DeviceWkPtr_t device, JointIndex indexInJointList );
63 
64  ~Joint() {}
66  // -----------------------------------------------------------------------
69 
71  const std::string& name() const;
72 
74  // -----------------------------------------------------------------------
77 
79  const Transform3f& currentTransformation () const { return currentTransformation(data()); }
80 
82  const Transform3f& currentTransformation (const DeviceData& data) const;
83 
85  // -----------------------------------------------------------------------
88 
90  size_type numberDof () const;
91 
93  size_type configSize () const;
94 
96  size_type rankInConfiguration () const;
97 
99  size_type rankInVelocity () const;
100 
102  // -----------------------------------------------------------------------
105 
107  JointPtr_t parentJoint () const;
108 
110  std::size_t numberChildJoints () const;
111 
113  JointPtr_t childJoint (std::size_t rank) const;
114 
116  const Transform3f& positionInParentFrame () const;
117 
119  // -----------------------------------------------------------------------
122 
126  void isBounded (size_type rank, bool bounded);
128  bool isBounded (size_type rank) const;
130  value_type lowerBound (size_type rank) const;
132  value_type upperBound (size_type rank) const;
134  void lowerBound (size_type rank, value_type lowerBound);
136  void upperBound (size_type rank, value_type upperBound);
138  void lowerBounds (vectorIn_t lowerBounds);
140  void upperBounds (vectorIn_t upperBounds);
141 
151  value_type upperBoundLinearVelocity () const;
152 
162  value_type upperBoundAngularVelocity () const;
163 
165  const value_type& maximalDistanceToParent () const { return maximalDistanceToParent_; }
166 
168  protected:
170  void computeMaximalDistanceToParent ();
171  public:
172  // -----------------------------------------------------------------------
175 
181  JointJacobian_t& jacobian (const bool localFrame=true) const { return jacobian (data(), localFrame); }
182 
189  JointJacobian_t& jacobian (DeviceData& data, const bool localFrame=true) const;
190 
192  // -----------------------------------------------------------------------
193 
195  DeviceConstPtr_t robot () const { return devicePtr.lock();}
197  DevicePtr_t robot () { return devicePtr.lock();}
198 
201 
203  BodyPtr_t linkedBody () const;
204 
206 
208  std::ostream& display (std::ostream& os) const;
209 
211  LiegroupSpacePtr_t configurationSpace () const;
212 
215  LiegroupSpacePtr_t RnxSOnConfigurationSpace () const;
216 
219 
220  const JointIndex& index () const
221  {
222  return jointIndex;
223  }
224 
225  const JointModel& jointModel() const;
226 
228 
229  protected:
231  DeviceWkPtr_t devicePtr;
233  std::vector<JointIndex> children;
234 
236  void setChildList();
237  Model& model() ;
238  const Model& model() const ;
239  DeviceData& data() const;
240 
242  void selfAssert() const;
243 
244  friend class Device;
245  }; // class Joint
246 
247  inline std::ostream& operator<< (std::ostream& os, const Joint& joint) { return joint.display(os); }
248 
249  } // namespace pinocchio
250 } // namespace hpp
251 
252 #endif // HPP_PINOCCHIO_JOINT_HH
boost::shared_ptr< Device > DevicePtr_t
Definition: fwd.hh:104
boost::shared_ptr< Body > BodyPtr_t
Definition: fwd.hh:96
Utility functions.
Eigen::Matrix< value_type, 6, Eigen::Dynamic > JointJacobian_t
Definition: fwd.hh:88
Definition: device-data.hh:41
const Transform3f & currentTransformation() const
Joint transformation.
Definition: joint.hh:79
ObjectFactory * create(ObjectFactory *parent=NULL, const XMLElement *element=NULL)
matrix_t::Index size_type
Definition: fwd.hh:84
JointIndex jointIndex
Definition: joint.hh:232
std::vector< JointIndex > children
Definition: joint.hh:233
std::ostream & operator<<(std::ostream &os, const hpp::pinocchio::Device &device)
Definition: device.hh:344
const JointIndex & index() const
Definition: joint.hh:220
JointJacobian_t & jacobian(const bool localFrame=true) const
Definition: joint.hh:181
std::ostream & display(std::ostream &os) const
Display joint.
Robot with geometric and dynamic pinocchio.
Definition: device.hh:51
double value_type
Definition: fwd.hh:40
DeviceWkPtr_t devicePtr
Definition: joint.hh:231
::pinocchio::SE3 Transform3f
Definition: fwd.hh:69
boost::shared_ptr< const Device > DeviceConstPtr_t
Definition: fwd.hh:105
Eigen::Ref< const vector_t > vectorIn_t
Definition: fwd.hh:80
DevicePtr_t robot()
Access robot owning the object.
Definition: joint.hh:197
const value_type & maximalDistanceToParent() const
Maximal distance of joint origin to parent origin.
Definition: joint.hh:165
~Joint()
Definition: joint.hh:64
::pinocchio::JointIndex JointIndex
Definition: fwd.hh:62
boost::shared_ptr< LiegroupSpace > LiegroupSpacePtr_t
Definition: fwd.hh:134
DeviceConstPtr_t robot() const
Access robot owning the object.
Definition: joint.hh:195
Definition: joint.hh:45
std::ostream & display(std::ostream &os, const SE3 &m)
Write a SE3 taking into account the indentation.
value_type maximalDistanceToParent_
Definition: joint.hh:230
boost::shared_ptr< Joint > JointPtr_t
Definition: fwd.hh:109