robot_model.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ioan A. Sucan
5  * Copyright (c) 2008-2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Ioan Sucan */
37 
38 #ifndef MOVEIT_CORE_ROBOT_MODEL_
39 #define MOVEIT_CORE_ROBOT_MODEL_
40 
43 #include <urdf/model.h>
44 #include <srdfdom/model.h>
45 
46 // joint types
53 
54 #include <Eigen/Geometry>
55 #include <iostream>
56 
58 namespace moveit
59 {
61 namespace core
62 {
63 MOVEIT_CLASS_FORWARD(RobotModel);
64 
68 {
69 public:
71  RobotModel(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model);
72 
74  ~RobotModel();
75 
77  const std::string& getName() const
78  {
79  return model_name_;
80  }
81 
86  const std::string& getModelFrame() const
87  {
88  return model_frame_;
89  }
90 
92  bool isEmpty() const
93  {
94  return root_link_ == NULL;
95  }
96 
98  const urdf::ModelInterfaceSharedPtr& getURDF() const
99  {
100  return urdf_;
101  }
102 
105  {
106  return srdf_;
107  }
108 
110  void printModelInfo(std::ostream& out) const;
111 
120  const JointModel* getRootJoint() const;
121 
123  const std::string& getRootJointName() const
124  {
125  return getRootJoint()->getName();
126  }
127 
129  bool hasJointModel(const std::string& name) const;
130 
132  const JointModel* getJointModel(const std::string& joint) const;
133 
135  const JointModel* getJointModel(int index) const;
136 
138  JointModel* getJointModel(const std::string& joint);
139 
142  const std::vector<const JointModel*>& getJointModels() const
143  {
145  }
146 
150  const std::vector<JointModel*>& getJointModels()
151  {
152  return joint_model_vector_;
153  }
154 
156  const std::vector<std::string>& getJointModelNames() const
157  {
159  }
160 
162  const std::vector<const JointModel*>& getActiveJointModels() const
163  {
165  }
166 
168  const std::vector<JointModel*>& getActiveJointModels()
169  {
171  }
172 
174  const std::vector<const JointModel*>& getSingleDOFJointModels() const
175  {
176  return single_dof_joints_;
177  }
178 
180  const std::vector<const JointModel*>& getMultiDOFJointModels() const
181  {
182  return multi_dof_joints_;
183  }
184 
187  const std::vector<const JointModel*>& getContinuousJointModels() const
188  {
190  }
191 
194  const std::vector<const JointModel*>& getMimicJointModels() const
195  {
196  return mimic_joints_;
197  }
198 
199  const JointModel* getJointOfVariable(int variable_index) const
200  {
201  return joints_of_variable_[variable_index];
202  }
203 
204  const JointModel* getJointOfVariable(const std::string& variable) const
205  {
206  return joints_of_variable_[getVariableIndex(variable)];
207  }
208 
209  std::size_t getJointModelCount() const
210  {
211  return joint_model_vector_.size();
212  }
213 
221  const LinkModel* getRootLink() const;
222 
224  const std::string& getRootLinkName() const
225  {
226  return getRootLink()->getName();
227  }
228 
230  bool hasLinkModel(const std::string& name) const;
231 
233  const LinkModel* getLinkModel(const std::string& link) const;
234 
236  const LinkModel* getLinkModel(int index) const;
237 
239  LinkModel* getLinkModel(const std::string& link);
240 
253 
255  const std::vector<const LinkModel*>& getLinkModels() const
256  {
258  }
259 
261  const std::vector<LinkModel*>& getLinkModels()
262  {
263  return link_model_vector_;
264  }
265 
267  const std::vector<std::string>& getLinkModelNames() const
268  {
270  }
271 
273  const std::vector<const LinkModel*>& getLinkModelsWithCollisionGeometry() const
274  {
276  }
277 
279  const std::vector<std::string>& getLinkModelNamesWithCollisionGeometry() const
280  {
282  }
283 
284  std::size_t getLinkModelCount() const
285  {
286  return link_model_vector_.size();
287  }
288 
289  std::size_t getLinkGeometryCount() const
290  {
291  return link_geometry_count_;
292  }
293 
297  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values) const;
298 
300  void getVariableDefaultPositions(double* values) const;
301 
303  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, std::vector<double>& values) const
304  {
305  values.resize(variable_count_);
306  getVariableRandomPositions(rng, &values[0]);
307  }
308 
310  void getVariableDefaultPositions(std::vector<double>& values) const
311  {
312  values.resize(variable_count_);
313  getVariableDefaultPositions(&values[0]);
314  }
315 
318  std::map<std::string, double>& values) const;
319 
321  void getVariableDefaultPositions(std::map<std::string, double>& values) const;
322 
323  bool enforcePositionBounds(double* state) const
324  {
326  }
327  bool enforcePositionBounds(double* state, const JointBoundsVector& active_joint_bounds) const;
328  bool satisfiesPositionBounds(const double* state, double margin = 0.0) const
329  {
331  }
332  bool satisfiesPositionBounds(const double* state, const JointBoundsVector& active_joint_bounds,
333  double margin = 0.0) const;
334  double getMaximumExtent() const
335  {
337  }
338  double getMaximumExtent(const JointBoundsVector& active_joint_bounds) const;
339 
340  double distance(const double* state1, const double* state2) const;
341  void interpolate(const double* from, const double* to, double t, double* state) const;
342 
348  bool hasJointModelGroup(const std::string& group) const;
349 
351  const JointModelGroup* getJointModelGroup(const std::string& name) const;
352 
354  JointModelGroup* getJointModelGroup(const std::string& name);
355 
357  const std::vector<const JointModelGroup*>& getJointModelGroups() const
358  {
360  }
361 
363  const std::vector<JointModelGroup*>& getJointModelGroups()
364  {
365  return joint_model_groups_;
366  }
367 
369  const std::vector<std::string>& getJointModelGroupNames() const
370  {
372  }
373 
375  bool hasEndEffector(const std::string& eef) const;
376 
378  const JointModelGroup* getEndEffector(const std::string& name) const;
379 
381  JointModelGroup* getEndEffector(const std::string& name);
382 
384  const std::vector<const JointModelGroup*>& getEndEffectors() const
385  {
386  return end_effectors_;
387  }
388 
392  std::size_t getVariableCount() const
393  {
394  return variable_count_;
395  }
396 
401  const std::vector<std::string>& getVariableNames() const
402  {
403  return variable_names_;
404  }
405 
407  const VariableBounds& getVariableBounds(const std::string& variable) const
408  {
409  return getJointOfVariable(variable)->getVariableBounds(variable);
410  }
411 
414  {
416  }
417 
418  void getMissingVariableNames(const std::vector<std::string>& variables,
419  std::vector<std::string>& missing_variables) const;
420 
422  int getVariableIndex(const std::string& variable) const;
423 
425  const JointModel* getCommonRoot(const JointModel* a, const JointModel* b) const
426  {
427  if (!a)
428  return b;
429  if (!b)
430  return a;
432  b->getJointIndex()]];
433  }
434 
436  void setKinematicsAllocators(const std::map<std::string, SolverAllocatorFn>& allocators);
437 
438 protected:
440  void computeFixedTransforms(const LinkModel* link, const Eigen::Affine3d& transform,
441  LinkTransformMap& associated_transforms);
442 
444  const JointModel* computeCommonRoot(const JointModel* a, const JointModel* b) const;
445 
447  void updateMimicJoints(double* values) const;
448 
449  // GENERIC INFO
450 
452  std::string model_name_;
453 
455  std::string model_frame_;
456 
458 
459  urdf::ModelInterfaceSharedPtr urdf_;
460 
461  // LINKS
462 
465 
468 
470  std::vector<LinkModel*> link_model_vector_;
471 
473  std::vector<const LinkModel*> link_model_vector_const_;
474 
476  std::vector<std::string> link_model_names_vector_;
477 
479  std::vector<const LinkModel*> link_models_with_collision_geometry_vector_;
480 
483 
485  std::size_t link_geometry_count_;
486 
487  // JOINTS
488 
491 
494 
496  std::vector<JointModel*> joint_model_vector_;
497 
499  std::vector<const JointModel*> joint_model_vector_const_;
500 
502  std::vector<std::string> joint_model_names_vector_;
503 
505  std::vector<JointModel*> active_joint_model_vector_;
506 
508  std::vector<const JointModel*> active_joint_model_vector_const_;
509 
511  std::vector<const JointModel*> continuous_joint_model_vector_;
512 
514  std::vector<const JointModel*> mimic_joints_;
515 
516  std::vector<const JointModel*> single_dof_joints_;
517 
518  std::vector<const JointModel*> multi_dof_joints_;
519 
527  std::vector<int> common_joint_roots_;
528 
529  // INDEXING
530 
533  std::vector<std::string> variable_names_;
534 
536  std::size_t variable_count_;
537 
542 
544 
547 
549  std::vector<const JointModel*> joints_of_variable_;
550 
551  // GROUPS
552 
555 
558 
560  std::vector<JointModelGroup*> joint_model_groups_;
561 
563  std::vector<const JointModelGroup*> joint_model_groups_const_;
564 
566  std::vector<std::string> joint_model_group_names_;
567 
569  std::vector<const JointModelGroup*> end_effectors_;
570 
572  void buildModel(const urdf::ModelInterface& urdf_model, const srdf::Model& srdf_model);
573 
575  void buildGroups(const srdf::Model& srdf_model);
576 
578  void buildGroupsInfo_Subgroups(const srdf::Model& srdf_model);
579 
581  void buildGroupsInfo_EndEffectors(const srdf::Model& srdf_model);
582 
584  void buildMimic(const urdf::ModelInterface& urdf_model);
585 
587  void buildGroupStates(const srdf::Model& srdf_model);
588 
590  void buildJointInfo();
591 
593  void computeDescendants();
594 
596  void computeCommonRoots();
597 
600  JointModel* buildRecursive(LinkModel* parent, const urdf::Link* link, const srdf::Model& srdf_model);
601 
603  bool addJointModelGroup(const srdf::Model::Group& group);
604 
607  JointModel* constructJointModel(const urdf::Joint* urdf_joint_model, const urdf::Link* child_link,
608  const srdf::Model& srdf_model);
609 
611  LinkModel* constructLinkModel(const urdf::Link* urdf_link);
612 
614  shapes::ShapePtr constructShape(const urdf::Geometry* geom);
615 };
616 }
617 }
618 
619 namespace robot_model = moveit::core;
620 namespace robot_state = moveit::core;
621 
622 #endif
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
Definition: robot_model.h:514
std::size_t getLinkGeometryCount() const
Definition: robot_model.h:289
const std::vector< std::string > & getLinkModelNamesWithCollisionGeometry() const
Get the names of the link models that have some collision geometry associated to themselves.
Definition: robot_model.h:279
const std::string & getName() const
The name of this link.
Definition: link_model.h:81
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState). This frame depends on the root joint. As such, the frame is either extracted from SRDF, or it is assumed to be the name of the root link.
Definition: robot_model.h:86
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition: robot_model.h:98
void printModelInfo(std::ostream &out) const
Print information about the constructed model.
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:131
Core components of MoveIt!
std::vector< LinkModel * > link_model_vector_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
Definition: robot_model.h:470
JointModel * constructJointModel(const urdf::Joint *urdf_joint_model, const urdf::Link *child_link, const srdf::Model &srdf_model)
Given a urdf joint model, a child link and a set of virtual joints, build up the corresponding JointM...
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
Definition: robot_model.h:549
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
Definition: robot_model.h:476
const std::string & getName() const
Get the model name.
Definition: robot_model.h:77
const std::vector< const LinkModel * > & getLinkModelsWithCollisionGeometry() const
Get the link models that have some collision geometry associated to themselves.
Definition: robot_model.h:273
std::vector< const LinkModel * > link_model_vector_const_
The vector of links that are updated when computeTransforms() is called, in the order they are update...
Definition: robot_model.h:473
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
Definition: robot_model.h:546
static const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const LinkModel *link)
Get the latest link upwards the kinematic tree, which is only connected via fixed joints...
LinkModelMap link_model_map_
A map from link names to their instances.
Definition: robot_model.h:467
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute the random values for a RobotState.
const JointModel * getJointOfVariable(int variable_index) const
Definition: robot_model.h:199
void getVariableDefaultPositions(std::vector< double > &values) const
Compute the default values for a RobotState.
Definition: robot_model.h:310
RobotModel(const urdf::ModelInterfaceSharedPtr &urdf_model, const srdf::ModelConstSharedPtr &srdf_model)
Construct a kinematic model from a parsed description and a list of planning groups.
Definition: robot_model.cpp:55
const std::vector< JointModel * > & getActiveJointModels()
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition: robot_model.h:168
void buildJointInfo()
Compute helpful information about joints.
const LinkModel * getLinkModel(const std::string &link) const
Get a link by its name. Output error and return NULL when the link is missing.
const LinkModel * root_link_
The first physical link for the robot.
Definition: robot_model.h:464
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
Definition: robot_model.h:407
std::size_t getVariableCount() const
Get the number of variables that describe this model.
Definition: robot_model.h:392
JointModelGroupMap end_effectors_map_
The known end effectors.
Definition: robot_model.h:557
std::map< std::string, JointModelGroup * > JointModelGroupMap
Map of names to instances for JointModelGroup.
const std::vector< const JointModel * > & getActiveJointModels() const
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition: robot_model.h:162
~RobotModel()
Destructor. Clear all memory.
Definition: robot_model.cpp:63
const JointModel * getRootJoint() const
Get the root joint. There will be one root joint unless the model is empty. This is either extracted ...
Definition: robot_model.cpp:73
std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Affine3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition: link_model.h:69
double distance(const double *state1, const double *state2) const
std::shared_ptr< Shape > ShapePtr
const std::vector< LinkModel * > & getLinkModels()
Get the array of links.
Definition: robot_model.h:261
const JointModel * getJointOfVariable(const std::string &variable) const
Definition: robot_model.h:204
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
const std::vector< const JointModelGroup * > & getEndEffectors() const
Get the map between end effector names and the groups they correspond to.
Definition: robot_model.h:384
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:67
void buildGroups(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build up the groups in this kinematic model.
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
void buildModel(const urdf::ModelInterface &urdf_model, const srdf::Model &srdf_model)
Given an URDF model and a SRDF model, build a full kinematic model.
Definition: robot_model.cpp:83
const std::vector< std::string > & getJointModelGroupNames() const
Get the names of all groups that are defined for this model.
Definition: robot_model.h:369
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Output error and return NULL when the joint is missing.
std::string model_name_
The name of the model.
Definition: robot_model.h:452
const std::vector< std::string > & getLinkModelNames() const
Get the link names (of all links)
Definition: robot_model.h:267
LinkModel * constructLinkModel(const urdf::Link *urdf_link)
Given a urdf link, build the corresponding LinkModel object.
shapes::ShapePtr constructShape(const urdf::Geometry *geom)
Given a geometry spec from the URDF and a filename (for a mesh), construct the corresponding shape ob...
unsigned int index
VariableIndexMap joint_variables_index_map_
The state includes all the joint variables that make up the joints the state consists of...
Definition: robot_model.h:541
void computeDescendants()
For every joint, pre-compute the list of descendant joints & links.
int getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:214
MOVEIT_CLASS_FORWARD(RobotModel)
JointModelGroupMap joint_model_group_map_
A map from group names to joint groups.
Definition: robot_model.h:554
const std::vector< JointModel * > & getJointModels()
Get the array of joints, in the order they appear in the robot state. This includes all types of join...
Definition: robot_model.h:150
void computeFixedTransforms(const LinkModel *link, const Eigen::Affine3d &transform, LinkTransformMap &associated_transforms)
Get the transforms between link and all its rigidly attached descendants.
std::size_t getJointModelCount() const
Definition: robot_model.h:209
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
Definition: joint_model.h:91
const std::vector< const JointModel * > & getMimicJointModels() const
Get the array of mimic joints, in the order they appear in the robot state.
Definition: robot_model.h:194
std::vector< const JointModel::Bounds * > JointBoundsVector
std::size_t variable_count_
Get the number of variables necessary to describe this model.
Definition: robot_model.h:536
const std::vector< const JointModel * > & getSingleDOFJointModels() const
This is a list of all single-dof joints (including mimic joints)
Definition: robot_model.h:174
const JointModel * computeCommonRoot(const JointModel *a, const JointModel *b) const
Given two joints, find their common root.
const JointModel * root_joint_
The root joint.
Definition: robot_model.h:490
std::vector< const JointModel * > joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:499
srdf::ModelConstSharedPtr srdf_
Definition: robot_model.h:457
std::map< std::string, int > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
Definition: joint_model.h:82
std::vector< const JointModelGroup * > joint_model_groups_const_
The array of joint model groups, in alphabetical order.
Definition: robot_model.h:563
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
Definition: joint_model.h:108
std::size_t getLinkModelCount() const
Definition: robot_model.h:284
bool enforcePositionBounds(double *state) const
Definition: robot_model.h:323
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints, in the order they appear in the robot state.
Definition: robot_model.h:187
void buildGroupsInfo_EndEffectors(const srdf::Model &srdf_model)
Compute helpful information about groups (that can be queried later)
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this model contains.
Definition: robot_model.h:511
std::vector< const JointModel * > single_dof_joints_
Definition: robot_model.h:516
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
Definition: robot_model.h:569
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints.
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
Definition: link_model.h:58
void computeCommonRoots()
For every pair of joints, pre-compute the common roots of the joints.
std::vector< JointModel * > active_joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:505
const LinkModel * getRootLink() const
Get the physical root link of the robot.
Definition: robot_model.cpp:78
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
Definition: robot_model.h:485
JointModelMap joint_model_map_
A map from joint names to their instances.
Definition: robot_model.h:493
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
Definition: robot_model.h:502
urdf::ModelInterfaceSharedPtr urdf_
Definition: robot_model.h:459
bool hasJointModel(const std::string &name) const
Check if a joint exists. Return true if it does.
const std::string & getRootJointName() const
Return the name of the root joint. Throws an exception if there is no root joint. ...
Definition: robot_model.h:123
std::string model_frame_
The reference frame for this model.
Definition: robot_model.h:455
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const
Compute the random values for a RobotState.
Definition: robot_model.h:303
void buildGroupsInfo_Subgroups(const srdf::Model &srdf_model)
Compute helpful information about groups (that can be queried later)
const std::string & getRootLinkName() const
Get the name of the root link of the robot.
Definition: robot_model.h:224
const JointModel * getCommonRoot(const JointModel *a, const JointModel *b) const
Get the deepest joint in the kinematic tree that is a common parent of both joints passed as argument...
Definition: robot_model.h:425
bool isEmpty() const
Return true if the model is empty (has no root link, no joints)
Definition: robot_model.h:92
std::vector< JointModel * > joint_model_vector_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:496
std::vector< std::string > variable_names_
The names of the DOF that make up this state (this is just a sequence of joint variable names; not ne...
Definition: robot_model.h:533
void getMissingVariableNames(const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
bool addJointModelGroup(const srdf::Model::Group &group)
Construct a JointModelGroup given a SRDF description group.
void interpolate(const double *from, const double *to, double t, double *state) const
A link from the robot. Contains the constant transform applied to the link and its geometry...
Definition: link_model.h:72
std::vector< int > active_joint_model_start_index_
Definition: robot_model.h:543
int getVariableIndex(const std::string &variable) const
Get the index of a variable in the robot state.
bool hasEndEffector(const std::string &eef) const
Check if an end effector exists.
std::vector< const JointModel * > multi_dof_joints_
Definition: robot_model.h:518
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
void buildMimic(const urdf::ModelInterface &urdf_model)
Given the URDF model, build up the mimic joints (mutually constrained joints)
std::vector< JointModelGroup * > joint_model_groups_
The array of joint model groups, in alphabetical order.
Definition: robot_model.h:560
const std::vector< const JointModel * > & getJointModels() const
Get the array of joints, in the order they appear in the robot state.
Definition: robot_model.h:142
const std::vector< std::string > & getJointModelNames() const
Get the array of joint names, in the order they appear in the robot state.
Definition: robot_model.h:156
Main namespace for MoveIt!
std::vector< std::string > joint_model_group_names_
A vector of all group names, in alphabetical order.
Definition: robot_model.h:566
void buildGroupStates(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build the default states defined in the SRDF...
std::vector< const JointModel * > active_joint_model_vector_const_
The vector of joints in the model, in the order they appear in the state vector.
Definition: robot_model.h:508
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
Definition: robot_model.h:479
std::vector< int > common_joint_roots_
For every two joints, the index of the common root for thw joints is stored.
Definition: robot_model.h:527
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
JointModel * buildRecursive(LinkModel *parent, const urdf::Link *link, const srdf::Model &srdf_model)
(This function is mostly intended for internal use). Given a parent link, build up (recursively)...
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
Definition: robot_model.h:413
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
Definition: robot_model.h:328
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints that form this state. Fixed joints have no DOF...
Definition: robot_model.h:401
double getMaximumExtent() const
Definition: robot_model.h:334
const std::vector< JointModelGroup * > & getJointModelGroups()
Get the available joint groups.
Definition: robot_model.h:363
const std::vector< const LinkModel * > & getLinkModels() const
Get the array of links.
Definition: robot_model.h:255
bool hasJointModelGroup(const std::string &group) const
Check if the JointModelGroup group exists.
std::vector< std::string > link_model_names_with_collision_geometry_vector_
The vector of link names that corresponds to link_models_with_collision_geometry_vector_.
Definition: robot_model.h:482
const srdf::ModelConstSharedPtr & getSRDF() const
Get the parsed SRDF model.
Definition: robot_model.h:104
const std::vector< const JointModel * > & getMultiDOFJointModels() const
This is a list of all multi-dof joints.
Definition: robot_model.h:180
void getVariableDefaultPositions(double *values) const
Compute the default values for a RobotState.
const std::vector< const JointModelGroup * > & getJointModelGroups() const
Get the available joint groups.
Definition: robot_model.h:357


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:05