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 <console_bridge/console.h>
44 #include <urdf/model.h>
45 #include <srdfdom/model.h>
46 
47 // joint types
54 
55 #include <Eigen/Geometry>
56 #include <iostream>
57 
59 namespace moveit
60 {
62 namespace core
63 {
64 MOVEIT_CLASS_FORWARD(RobotModel);
65 
69 {
70 public:
72  RobotModel(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model);
73 
75  ~RobotModel();
76 
78  const std::string& getName() const
79  {
80  return model_name_;
81  }
82 
87  const std::string& getModelFrame() const
88  {
89  return model_frame_;
90  }
91 
93  bool isEmpty() const
94  {
95  return root_link_ == NULL;
96  }
97 
99  const urdf::ModelInterfaceSharedPtr& getURDF() const
100  {
101  return urdf_;
102  }
103 
106  {
107  return srdf_;
108  }
109 
111  void printModelInfo(std::ostream& out) const;
112 
121  const JointModel* getRootJoint() const;
122 
124  const std::string& getRootJointName() const
125  {
126  return getRootJoint()->getName();
127  }
128 
130  bool hasJointModel(const std::string& name) const;
131 
133  const JointModel* getJointModel(const std::string& joint) const;
134 
136  const JointModel* getJointModel(int index) const;
137 
139  JointModel* getJointModel(const std::string& joint);
140 
143  const std::vector<const JointModel*>& getJointModels() const
144  {
146  }
147 
151  const std::vector<JointModel*>& getJointModels()
152  {
153  return joint_model_vector_;
154  }
155 
157  const std::vector<std::string>& getJointModelNames() const
158  {
160  }
161 
163  const std::vector<const JointModel*>& getActiveJointModels() const
164  {
166  }
167 
169  const std::vector<JointModel*>& getActiveJointModels()
170  {
172  }
173 
175  const std::vector<const JointModel*>& getSingleDOFJointModels() const
176  {
177  return single_dof_joints_;
178  }
179 
181  const std::vector<const JointModel*>& getMultiDOFJointModels() const
182  {
183  return multi_dof_joints_;
184  }
185 
188  const std::vector<const JointModel*>& getContinuousJointModels() const
189  {
191  }
192 
195  const std::vector<const JointModel*>& getMimicJointModels() const
196  {
197  return mimic_joints_;
198  }
199 
200  const JointModel* getJointOfVariable(int variable_index) const
201  {
202  return joints_of_variable_[variable_index];
203  }
204 
205  const JointModel* getJointOfVariable(const std::string& variable) const
206  {
207  return joints_of_variable_[getVariableIndex(variable)];
208  }
209 
210  std::size_t getJointModelCount() const
211  {
212  return joint_model_vector_.size();
213  }
214 
222  const LinkModel* getRootLink() const;
223 
225  const std::string& getRootLinkName() const
226  {
227  return getRootLink()->getName();
228  }
229 
231  bool hasLinkModel(const std::string& name) const;
232 
234  const LinkModel* getLinkModel(const std::string& link) const;
235 
237  const LinkModel* getLinkModel(int index) const;
238 
240  LinkModel* getLinkModel(const std::string& link);
241 
243  const std::vector<const LinkModel*>& getLinkModels() const
244  {
246  }
247 
249  const std::vector<LinkModel*>& getLinkModels()
250  {
251  return link_model_vector_;
252  }
253 
255  const std::vector<std::string>& getLinkModelNames() const
256  {
258  }
259 
261  const std::vector<const LinkModel*>& getLinkModelsWithCollisionGeometry() const
262  {
264  }
265 
267  const std::vector<std::string>& getLinkModelNamesWithCollisionGeometry() const
268  {
270  }
271 
272  std::size_t getLinkModelCount() const
273  {
274  return link_model_vector_.size();
275  }
276 
277  std::size_t getLinkGeometryCount() const
278  {
279  return link_geometry_count_;
280  }
281 
285  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values) const;
286 
288  void getVariableDefaultPositions(double* values) const;
289 
291  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, std::vector<double>& values) const
292  {
293  values.resize(variable_count_);
294  getVariableRandomPositions(rng, &values[0]);
295  }
296 
298  void getVariableDefaultPositions(std::vector<double>& values) const
299  {
300  values.resize(variable_count_);
301  getVariableDefaultPositions(&values[0]);
302  }
303 
306  std::map<std::string, double>& values) const;
307 
309  void getVariableDefaultPositions(std::map<std::string, double>& values) const;
310 
311  bool enforcePositionBounds(double* state) const
312  {
314  }
315  bool enforcePositionBounds(double* state, const JointBoundsVector& active_joint_bounds) const;
316  bool satisfiesPositionBounds(const double* state, double margin = 0.0) const
317  {
319  }
320  bool satisfiesPositionBounds(const double* state, const JointBoundsVector& active_joint_bounds,
321  double margin = 0.0) const;
322  double getMaximumExtent() const
323  {
325  }
326  double getMaximumExtent(const JointBoundsVector& active_joint_bounds) const;
327 
328  double distance(const double* state1, const double* state2) const;
329  void interpolate(const double* from, const double* to, double t, double* state) const;
330 
336  bool hasJointModelGroup(const std::string& group) const;
337 
339  const JointModelGroup* getJointModelGroup(const std::string& name) const;
340 
342  JointModelGroup* getJointModelGroup(const std::string& name);
343 
345  const std::vector<const JointModelGroup*>& getJointModelGroups() const
346  {
348  }
349 
351  const std::vector<JointModelGroup*>& getJointModelGroups()
352  {
353  return joint_model_groups_;
354  }
355 
357  const std::vector<std::string>& getJointModelGroupNames() const
358  {
360  }
361 
363  bool hasEndEffector(const std::string& eef) const;
364 
366  const JointModelGroup* getEndEffector(const std::string& name) const;
367 
369  JointModelGroup* getEndEffector(const std::string& name);
370 
372  const std::vector<const JointModelGroup*>& getEndEffectors() const
373  {
374  return end_effectors_;
375  }
376 
380  std::size_t getVariableCount() const
381  {
382  return variable_count_;
383  }
384 
389  const std::vector<std::string>& getVariableNames() const
390  {
391  return variable_names_;
392  }
393 
395  const VariableBounds& getVariableBounds(const std::string& variable) const
396  {
397  return getJointOfVariable(variable)->getVariableBounds(variable);
398  }
399 
402  {
404  }
405 
406  void getMissingVariableNames(const std::vector<std::string>& variables,
407  std::vector<std::string>& missing_variables) const;
408 
410  int getVariableIndex(const std::string& variable) const;
411 
413  const JointModel* getCommonRoot(const JointModel* a, const JointModel* b) const
414  {
415  if (!a)
416  return b;
417  if (!b)
418  return a;
420  b->getJointIndex()]];
421  }
422 
424  void setKinematicsAllocators(const std::map<std::string, SolverAllocatorFn>& allocators);
425 
426 protected:
427  void computeFixedTransforms(const LinkModel* link, const Eigen::Affine3d& transform,
428  LinkTransformMap& associated_transforms);
429 
431  const JointModel* computeCommonRoot(const JointModel* a, const JointModel* b) const;
432 
434  void updateMimicJoints(double* values) const;
435 
436  // GENERIC INFO
437 
439  std::string model_name_;
440 
442  std::string model_frame_;
443 
445 
446  urdf::ModelInterfaceSharedPtr urdf_;
447 
448  // LINKS
449 
452 
455 
457  std::vector<LinkModel*> link_model_vector_;
458 
460  std::vector<const LinkModel*> link_model_vector_const_;
461 
463  std::vector<std::string> link_model_names_vector_;
464 
466  std::vector<const LinkModel*> link_models_with_collision_geometry_vector_;
467 
470 
472  std::size_t link_geometry_count_;
473 
474  // JOINTS
475 
478 
481 
483  std::vector<JointModel*> joint_model_vector_;
484 
486  std::vector<const JointModel*> joint_model_vector_const_;
487 
489  std::vector<std::string> joint_model_names_vector_;
490 
492  std::vector<JointModel*> active_joint_model_vector_;
493 
495  std::vector<const JointModel*> active_joint_model_vector_const_;
496 
498  std::vector<const JointModel*> continuous_joint_model_vector_;
499 
501  std::vector<const JointModel*> mimic_joints_;
502 
503  std::vector<const JointModel*> single_dof_joints_;
504 
505  std::vector<const JointModel*> multi_dof_joints_;
506 
514  std::vector<int> common_joint_roots_;
515 
516  // INDEXING
517 
520  std::vector<std::string> variable_names_;
521 
523  std::size_t variable_count_;
524 
529 
531 
534 
536  std::vector<const JointModel*> joints_of_variable_;
537 
538  // GROUPS
539 
542 
545 
547  std::vector<JointModelGroup*> joint_model_groups_;
548 
550  std::vector<const JointModelGroup*> joint_model_groups_const_;
551 
553  std::vector<std::string> joint_model_group_names_;
554 
556  std::vector<const JointModelGroup*> end_effectors_;
557 
559  void buildModel(const urdf::ModelInterface& urdf_model, const srdf::Model& srdf_model);
560 
562  void buildGroups(const srdf::Model& srdf_model);
563 
565  void buildGroupsInfo_Subgroups(const srdf::Model& srdf_model);
566 
568  void buildGroupsInfo_EndEffectors(const srdf::Model& srdf_model);
569 
571  void buildMimic(const urdf::ModelInterface& urdf_model);
572 
574  void buildGroupStates(const srdf::Model& srdf_model);
575 
577  void buildJointInfo();
578 
580  void computeDescendants();
581 
583  void computeCommonRoots();
584 
587  JointModel* buildRecursive(LinkModel* parent, const urdf::Link* link, const srdf::Model& srdf_model);
588 
590  bool addJointModelGroup(const srdf::Model::Group& group);
591 
594  JointModel* constructJointModel(const urdf::Joint* urdf_joint_model, const urdf::Link* child_link,
595  const srdf::Model& srdf_model);
596 
598  LinkModel* constructLinkModel(const urdf::Link* urdf_link);
599 
601  shapes::ShapePtr constructShape(const urdf::Geometry* geom);
602 };
603 }
604 }
605 
606 namespace robot_model = moveit::core;
607 namespace robot_state = moveit::core;
608 
609 #endif
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
Definition: robot_model.h:501
std::size_t getLinkGeometryCount() const
Definition: robot_model.h:277
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:267
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:87
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition: robot_model.h:99
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:457
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
Definition: robot_model.h:536
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
Definition: robot_model.h:463
const LinkModel * getRootLink() const
Get the physical root link of the robot.
Definition: robot_model.cpp:75
const std::string & getName() const
Get the model name.
Definition: robot_model.h:78
const std::vector< const LinkModel * > & getLinkModelsWithCollisionGeometry() const
Get the link models that have some collision geometry associated to themselves.
Definition: robot_model.h:261
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:460
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
Definition: robot_model.h:533
LinkModelMap link_model_map_
A map from link names to their instances.
Definition: robot_model.h:454
LinkModel * constructLinkModel(const urdf::Link *urdf_link)
Given a urdf link, build the corresponding LinkModel object.
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:200
void getVariableDefaultPositions(std::vector< double > &values) const
Compute the default values for a RobotState.
Definition: robot_model.h:298
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
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:51
const std::vector< JointModel * > & getActiveJointModels()
Get the array of joints that are active (not fixed, not mimic) in this model.
Definition: robot_model.h:169
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
void buildJointInfo()
Compute helpful information about joints.
const LinkModel * root_link_
The first physical link for the robot.
Definition: robot_model.h:451
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:395
std::size_t getVariableCount() const
Get the number of variables that describe this model.
Definition: robot_model.h:380
JointModelGroupMap end_effectors_map_
The known end effectors.
Definition: robot_model.h:544
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:163
~RobotModel()
Destructor. Clear all memory.
Definition: robot_model.cpp:60
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:249
const JointModel * getJointOfVariable(const std::string &variable) const
Definition: robot_model.h:205
const std::vector< const JointModelGroup * > & getEndEffectors() const
Get the map between end effector names and the groups they correspond to.
Definition: robot_model.h:372
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:68
void buildGroups(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build up the groups in this kinematic model.
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
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:70
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:80
const std::vector< std::string > & getJointModelGroupNames() const
Get the names of all groups that are defined for this model.
Definition: robot_model.h:357
std::string model_name_
The name of the model.
Definition: robot_model.h:439
const std::vector< std::string > & getLinkModelNames() const
Get the link names (of all links)
Definition: robot_model.h:255
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:528
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:541
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:151
void computeFixedTransforms(const LinkModel *link, const Eigen::Affine3d &transform, LinkTransformMap &associated_transforms)
std::size_t getJointModelCount() const
Definition: robot_model.h:210
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:195
std::vector< const JointModel::Bounds * > JointBoundsVector
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::size_t variable_count_
Get the number of variables necessary to describe this model.
Definition: robot_model.h:523
const std::vector< const JointModel * > & getSingleDOFJointModels() const
This is a list of all single-dof joints (including mimic joints)
Definition: robot_model.h:175
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 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:477
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:486
srdf::ModelConstSharedPtr srdf_
Definition: robot_model.h:444
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:550
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:272
bool enforcePositionBounds(double *state) const
Definition: robot_model.h:311
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:188
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:498
std::vector< const JointModel * > single_dof_joints_
Definition: robot_model.h:503
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
Definition: robot_model.h:556
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:492
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
Definition: robot_model.h:472
JointModelMap joint_model_map_
A map from joint names to their instances.
Definition: robot_model.h:480
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
Definition: robot_model.h:489
urdf::ModelInterfaceSharedPtr urdf_
Definition: robot_model.h:446
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:124
std::string model_frame_
The reference frame for this model.
Definition: robot_model.h:442
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const
Compute the random values for a RobotState.
Definition: robot_model.h:291
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:225
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:413
bool isEmpty() const
Return true if the model is empty (has no root link, no joints)
Definition: robot_model.h:93
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:483
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:520
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:530
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:505
const LinkModel * getLinkModel(const std::string &link) const
Get a link by its name. Output error and return NULL when the link is missing.
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:547
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:143
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:157
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:553
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:495
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
Definition: robot_model.h:466
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
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:514
std::map< const LinkModel *, Eigen::Affine3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *, Eigen::Affine3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition: link_model.h:69
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
Definition: robot_model.h:401
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
Definition: robot_model.h:316
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...
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:389
double getMaximumExtent() const
Definition: robot_model.h:322
const std::vector< JointModelGroup * > & getJointModelGroups()
Get the available joint groups.
Definition: robot_model.h:351
const std::vector< const LinkModel * > & getLinkModels() const
Get the array of links.
Definition: robot_model.h:243
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:469
const srdf::ModelConstSharedPtr & getSRDF() const
Get the parsed SRDF model.
Definition: robot_model.h:105
const std::vector< const JointModel * > & getMultiDOFJointModels() const
This is a list of all multi-dof joints.
Definition: robot_model.h:181
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:345


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Jan 21 2018 03:54:29