pinocchio  UNKNOWN
model.hxx
1 //
2 // Copyright (c) 2015-2018 CNRS
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 // This file is part of Pinocchio
6 // Pinocchio is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // Pinocchio is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // Pinocchio If not, see
17 // <http://www.gnu.org/licenses/>.
18 
19 #ifndef __se3_model_hxx__
20 #define __se3_model_hxx__
21 
22 #include "pinocchio/spatial/fwd.hpp"
23 #include "pinocchio/utils/string-generator.hpp"
24 #include "pinocchio/multibody/liegroup/liegroup-algo.hpp"
25 
26 #include <boost/bind.hpp>
27 #include <boost/utility.hpp>
28 
30 
31 namespace se3
32 {
33  namespace details
34  {
35  struct FilterFrame {
36  const std::string& name;
37  const FrameType & typeMask;
38  FilterFrame(const std::string& name, const FrameType& typeMask)
39  : name(name), typeMask(typeMask) {}
40  bool operator()(const Frame& frame) const
41  { return (typeMask & frame.type) && (name == frame.name); }
42  };
43  }
44 
45  inline std::ostream& operator<<(std::ostream & os, const Model & model)
46  {
47  os << "Nb joints = " << model.njoints << " (nq="<< model.nq<<",nv="<<model.nv<<")" << std::endl;
48  for(Model::Index i=0;i<(Model::Index)(model.njoints);++i)
49  {
50  os << " Joint "<< model.names[i] << ": parent=" << model.parents[i] << std::endl;
51  }
52 
53  return os;
54  }
55 
56  template<typename JointModelDerived>
57  Model::JointIndex Model::addJoint(const Model::JointIndex parent,
58  const JointModelBase<JointModelDerived> & joint_model,
59  const SE3 & joint_placement,
60  const std::string & joint_name,
61  const Eigen::VectorXd & max_effort,
62  const Eigen::VectorXd & max_velocity,
63  const Eigen::VectorXd & min_config,
64  const Eigen::VectorXd & max_config
65  )
66  {
67  assert( (njoints==(int)joints.size())&&(njoints==(int)inertias.size())
68  &&(njoints==(int)parents.size())&&(njoints==(int)jointPlacements.size()) );
69  assert((joint_model.nq()>=0) && (joint_model.nv()>=0));
70 
71  assert(max_effort.size() == joint_model.nv()
72  && max_velocity.size() == joint_model.nv()
73  && min_config.size() == joint_model.nq()
74  && max_config.size() == joint_model.nq());
75 
76  Model::JointIndex idx = (Model::JointIndex) (njoints++);
77 
78  joints .push_back(JointModel(joint_model.derived()));
79  JointModelDerived & jmodel = boost::get<JointModelDerived>(joints.back());
80  jmodel.setIndexes(idx,nq,nv);
81 
82  inertias .push_back(Inertia::Zero());
83  parents .push_back(parent);
84  jointPlacements.push_back(joint_placement);
85  names .push_back(joint_name);
86  nq += joint_model.nq();
87  nv += joint_model.nv();
88 
89  // Optimal efficiency here would be using the static-dim bottomRows, while specifying the dimension in argument in the case where D::NV is Eigen::Dynamic.
90  // However, this option is not compiling in Travis (why?).
91  // As efficiency of Model::addJoint is not critical, the dynamic bottomRows is used here.
92  effortLimit.conservativeResize(nv);
93  jmodel.jointVelocitySelector(effortLimit) = max_effort;
94  velocityLimit.conservativeResize(nv);
95  jmodel.jointVelocitySelector(velocityLimit) = max_velocity;
96  lowerPositionLimit.conservativeResize(nq);
97  jmodel.jointConfigSelector(lowerPositionLimit) = min_config;
98  upperPositionLimit.conservativeResize(nq);
99  jmodel.jointConfigSelector(upperPositionLimit) = max_config;
100 
101  neutralConfiguration.conservativeResize(nq);
102  NeutralStepAlgo<LieGroupMap,JointModelDerived>::run(jmodel,neutralConfiguration);
103 
104  rotorInertia.conservativeResize(nv);
105  jmodel.jointVelocitySelector(rotorInertia).setZero();
106  rotorGearRatio.conservativeResize(nv);
107  jmodel.jointVelocitySelector(rotorGearRatio).setZero();
108 
109  // Init and add joint index to its parent subtrees.
110  subtrees.push_back(IndexVector(1));
111  subtrees[idx][0] = idx;
112  addJointIndexToParentSubtrees(idx);
113  return idx;
114  }
115 
116  template<typename JointModelDerived>
117  Model::JointIndex Model::addJoint(const Model::JointIndex parent,
118  const JointModelBase<JointModelDerived> & joint_model,
119  const SE3 & joint_placement,
120  const std::string & joint_name
121  )
122  {
123  Eigen::VectorXd max_effort, max_velocity, min_config, max_config;
124 
125  max_effort = Eigen::VectorXd::Constant(joint_model.nv(), std::numeric_limits<double>::max());
126  max_velocity = Eigen::VectorXd::Constant(joint_model.nv(), std::numeric_limits<double>::max());
127  min_config = Eigen::VectorXd::Constant(joint_model.nq(), -std::numeric_limits<double>::max());
128  max_config = Eigen::VectorXd::Constant(joint_model.nq(), std::numeric_limits<double>::max());
129 
130  return addJoint(parent, joint_model, joint_placement, joint_name, max_effort, max_velocity, min_config, max_config);
131  }
132 
133  inline int Model::addJointFrame(const JointIndex& jidx,
134  int fidx)
135  {
136  if(fidx < 0) {
137  // FIXED_JOINT is required because the parent can be the universe and its
138  // type is FIXED_JOINT
139  fidx = (int)getFrameId(names[parents[jidx]], (FrameType)(JOINT | FIXED_JOINT));
140  }
141  assert((size_t)fidx < frames.size() && "Frame index out of bound");
142  // Add a the joint frame attached to itself to the frame vector - redundant information but useful.
143  return addFrame(Frame(names[jidx],jidx,(FrameIndex)fidx,SE3::Identity(),JOINT));
144  }
145 
146 
147  inline void Model::appendBodyToJoint(const Model::JointIndex joint_index,
148  const Inertia & Y,
149  const SE3 & body_placement)
150  {
151  const Inertia & iYf = Y.se3Action(body_placement);
152  inertias[joint_index] += iYf;
153  nbodies++;
154  }
155 
156  inline int Model::addBodyFrame(const std::string & body_name,
157  const JointIndex & parentJoint,
158  const SE3 & body_placement,
159  int previousFrame)
160  {
161  if(previousFrame < 0) {
162  // FIXED_JOINT is required because the parent can be the universe and its
163  // type is FIXED_JOINT
164  previousFrame = (int)getFrameId(names[parentJoint], (FrameType)(JOINT | FIXED_JOINT));
165  }
166  assert((size_t)previousFrame < frames.size() && "Frame index out of bound");
167  return addFrame(Frame(body_name, parentJoint, (FrameIndex)previousFrame, body_placement, BODY));
168  }
169 
170  inline Model::JointIndex Model::getBodyId(const std::string & name) const
171  {
172  return getFrameId(name, BODY);
173  }
174 
175  inline bool Model::existBodyName(const std::string & name) const
176  {
177  return existFrame(name, BODY);
178  }
179 
180 
181  inline Model::JointIndex Model::getJointId(const std::string & name) const
182  {
183  typedef std::vector<std::string>::iterator::difference_type it_diff_t;
184  it_diff_t res = std::find(names.begin(),names.end(),name) - names.begin();
185  assert((res<INT_MAX) && "Id superior to int range. Should never happen.");
186  return Model::JointIndex(res);
187  }
188 
189  inline bool Model::existJointName(const std::string & name) const
190  {
191  return (names.end() != std::find(names.begin(),names.end(),name));
192  }
193 
194  inline const std::string& Model::getJointName(const JointIndex index) const
195  {
196  assert( index < (Model::JointIndex)joints.size() );
197  return names[index];
198  }
199 
200  inline Model::FrameIndex Model::getFrameId( const std::string & name, const FrameType & type ) const
201  {
202  container::aligned_vector<Frame>::const_iterator it = std::find_if( frames.begin()
203  , frames.end()
204  , details::FilterFrame(name, type)
205  );
206  assert(it != frames.end() && "Frame not found");
207  assert((std::find_if( boost::next(it), frames.end(), details::FilterFrame(name, type)) == frames.end())
208  && "Several frames match the filter");
209  return Model::FrameIndex(it - frames.begin());
210  }
211 
212  inline bool Model::existFrame( const std::string & name, const FrameType & type) const
213  {
214  return std::find_if( frames.begin(), frames.end(),
215  details::FilterFrame(name, type)) != frames.end();
216  }
217 
218 
219  inline int Model::addFrame( const Frame & frame )
220  {
221  if( !existFrame(frame.name, frame.type) )
222  {
223  frames.push_back(frame);
224  nframes++;
225  return nframes - 1;
226  }
227  else
228  {
229  return -1;
230  }
231  }
232 
233  inline void Model::addJointIndexToParentSubtrees(const JointIndex joint_id)
234  {
235  for(JointIndex parent = parents[joint_id]; parent>0; parent = parents[parent])
236  subtrees[parent].push_back(joint_id);
237  }
238 
239 } // namespace se3
240 
242 
243 #endif // ifndef __se3_model_hxx__
PINOCCHIO_DEPRECATED const std::string & getJointName(const JointIndex index) const
Get the name of a joint given by its index.
Definition: model.hxx:194
bool existJointName(const std::string &name) const
Check if a joint given by its name exists.
Definition: model.hxx:189
int nq
Dimension of the configuration vector representation.
Definition: model.hpp:49
int nv
Dimension of the velocity vector space.
Definition: model.hpp:52
int addFrame(const Frame &frame)
Adds a frame to the kinematic tree.
Definition: model.hxx:219
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Returns the index of a frame given by its name.
Definition: model.hxx:200
void addJointIndexToParentSubtrees(const JointIndex joint_id)
Add the joint_id to its parent subtrees.
Definition: model.hxx:233
void appendBodyToJoint(const JointIndex joint_index, const Inertia &Y, const SE3 &body_placement=SE3::Identity())
Append a body to a given joint of the kinematic tree.
Definition: model.hxx:147
FrameType type
Type of the frame.
Definition: frame.hpp:105
int nq(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointNqVisitor to get the dimension of the joint configuration spac...
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
Definition: model.hpp:73
int nv(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointNvVisitor to get the dimension of the joint tangent space...
A Plucker coordinate frame attached to a parent joint inside a kinematic tree.
Definition: frame.hpp:44
bool existBodyName(const std::string &name) const
Check if a body given by its name exists.
Definition: model.hxx:175
Specialization of an std::vector with an aligned allocator. This specialization might be used when th...
int addJointFrame(const JointIndex &jointIndex, int frameIndex=-1)
Add a joint to the frame tree.
Definition: model.hxx:133
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
Checks if a frame given by its name exists.
Definition: model.hxx:212
FrameType
Enum on the possible types of frame.
Definition: frame.hpp:31
int njoints
Number of joints.
Definition: model.hpp:55
std::vector< std::string > names
Name of joint i
Definition: model.hpp:76
JointIndex getJointId(const std::string &name) const
Return the index of a joint given by its name.
Definition: model.hxx:181
std::string name
Name of the frame.
Definition: frame.hpp:93
Derived_t se3Action(const SE3 &M) const
aI = aXb.act(bI)
Definition: inertia.hpp:120
int addBodyFrame(const std::string &body_name, const JointIndex &parentJoint, const SE3 &body_placement=SE3::Identity(), int previousFrame=-1)
Add a body to the frame tree.
Definition: model.hxx:156
JointIndex addJoint(const JointIndex parent, const JointModelBase< JointModelDerived > &joint_model, const SE3 &joint_placement, const std::string &joint_name, const Eigen::VectorXd &max_effort, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &min_config, const Eigen::VectorXd &max_config)
Add a joint to the kinematic tree with given bounds.
Definition: model.hxx:57
JointIndex getBodyId(const std::string &name) const
Return the index of a body given by its name.
Definition: model.hxx:170