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 #pragma once
39 
42 #include <urdf/model.h>
43 #include <srdfdom/model.h>
44 
45 // joint types
52 
53 #include <Eigen/Geometry>
54 #include <iostream>
55 
57 namespace moveit
58 {
60 namespace core
61 {
62 MOVEIT_CLASS_FORWARD(RobotModel); // Defines RobotModelPtr, ConstPtr, WeakPtr... etc
63 
64 static inline void checkInterpolationParamBounds(const char LOGNAME[], double t)
65 {
66  if (std::isnan(t) || std::isinf(t))
67  {
68  throw Exception("Interpolation parameter is NaN or inf.");
69  }
70  ROS_WARN_STREAM_COND_NAMED(t < 0. || t > 1., LOGNAME, "Interpolation parameter is not in the range [0, 1]: " << t);
71 }
72 
75 class RobotModel
76 {
77 public:
79  RobotModel(const urdf::ModelInterfaceSharedPtr& urdf_model, const srdf::ModelConstSharedPtr& srdf_model);
80 
82  ~RobotModel();
83 
85  const std::string& getName() const
86  {
87  return model_name_;
88  }
89 
94  const std::string& getModelFrame() const
95  {
96  return model_frame_;
97  }
98 
100  bool isEmpty() const
101  {
102  return root_link_ == nullptr;
103  }
104 
106  const urdf::ModelInterfaceSharedPtr& getURDF() const
107  {
108  return urdf_;
109  }
110 
112  const srdf::ModelConstSharedPtr& getSRDF() const
113  {
114  return srdf_;
115  }
116 
118  void printModelInfo(std::ostream& out) const;
119 
128  const JointModel* getRootJoint() const;
129 
131  const std::string& getRootJointName() const
132  {
133  return getRootJoint()->getName();
134  }
135 
137  bool hasJointModel(const std::string& name) const;
138 
140  const JointModel* getJointModel(const std::string& joint) const;
141 
143  const JointModel* getJointModel(int index) const;
144 
146  JointModel* getJointModel(const std::string& joint);
147 
150  const std::vector<const JointModel*>& getJointModels() const
151  {
153  }
154 
158  const std::vector<JointModel*>& getJointModels()
159  {
161  }
162 
164  const std::vector<std::string>& getJointModelNames() const
165  {
167  }
168 
170  const std::vector<const JointModel*>& getActiveJointModels() const
171  {
173  }
174 
176  const std::vector<std::string>& getActiveJointModelNames() const
177  {
179  }
180 
182  const std::vector<JointModel*>& getActiveJointModels()
183  {
185  }
186 
188  const std::vector<const JointModel*>& getSingleDOFJointModels() const
189  {
190  return single_dof_joints_;
191  }
192 
194  const std::vector<const JointModel*>& getMultiDOFJointModels() const
195  {
196  return multi_dof_joints_;
197  }
198 
201  const std::vector<const JointModel*>& getContinuousJointModels() const
202  {
204  }
205 
208  const std::vector<const JointModel*>& getMimicJointModels() const
209  {
210  return mimic_joints_;
211  }
212 
213  const JointModel* getJointOfVariable(int variable_index) const
214  {
215  return joints_of_variable_[variable_index];
216  }
217 
218  const JointModel* getJointOfVariable(const std::string& variable) const
219  {
220  return joints_of_variable_[getVariableIndex(variable)];
221  }
222 
223  std::size_t getJointModelCount() const
224  {
225  return joint_model_vector_.size();
226  }
227 
235  const LinkModel* getRootLink() const;
236 
238  const std::string& getRootLinkName() const
239  {
240  return getRootLink()->getName();
241  }
242 
246  bool hasLinkModel(const std::string& name) const;
247 
249  const LinkModel* getLinkModel(const std::string& link, bool* has_link = nullptr) const;
250 
252  const LinkModel* getLinkModel(int index) const;
253 
255  LinkModel* getLinkModel(const std::string& link, bool* has_link = nullptr);
256 
269 
271  const std::vector<const LinkModel*>& getLinkModels() const
272  {
274  }
275 
277  const std::vector<LinkModel*>& getLinkModels()
278  {
280  }
281 
283  const std::vector<std::string>& getLinkModelNames() const
284  {
286  }
287 
289  const std::vector<const LinkModel*>& getLinkModelsWithCollisionGeometry() const
290  {
292  }
293 
295  const std::vector<std::string>& getLinkModelNamesWithCollisionGeometry() const
296  {
298  }
299 
300  std::size_t getLinkModelCount() const
301  {
302  return link_model_vector_.size();
303  }
304 
305  std::size_t getLinkGeometryCount() const
306  {
307  return link_geometry_count_;
308  }
309 
313  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values) const;
314 
316  void getVariableDefaultPositions(double* values) const;
317 
319  void getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, std::vector<double>& values) const
320  {
321  values.resize(variable_count_);
322  getVariableRandomPositions(rng, &values[0]);
323  }
324 
326  void getVariableDefaultPositions(std::vector<double>& values) const
327  {
328  values.resize(variable_count_);
329  getVariableDefaultPositions(&values[0]);
330  }
331 
334  std::map<std::string, double>& values) const;
335 
337  void getVariableDefaultPositions(std::map<std::string, double>& values) const;
338 
339  bool enforcePositionBounds(double* state) const
340  {
342  }
343  bool enforcePositionBounds(double* state, const JointBoundsVector& active_joint_bounds) const;
344  bool satisfiesPositionBounds(const double* state, double margin = 0.0) const
345  {
347  }
348  bool satisfiesPositionBounds(const double* state, const JointBoundsVector& active_joint_bounds,
349  double margin = 0.0) const;
350  double getMaximumExtent() const
351  {
353  }
354  double getMaximumExtent(const JointBoundsVector& active_joint_bounds) const;
355 
357  double distance(const double* state1, const double* state2) const;
358 
367  void interpolate(const double* from, const double* to, double t, double* state) const;
368 
374  bool hasJointModelGroup(const std::string& group) const;
375 
377  const JointModelGroup* getJointModelGroup(const std::string& name) const;
378 
380  JointModelGroup* getJointModelGroup(const std::string& name);
381 
383  const std::vector<const JointModelGroup*>& getJointModelGroups() const
384  {
386  }
387 
389  const std::vector<JointModelGroup*>& getJointModelGroups()
390  {
391  return joint_model_groups_;
392  }
393 
395  const std::vector<std::string>& getJointModelGroupNames() const
396  {
398  }
399 
401  bool hasEndEffector(const std::string& eef) const;
402 
404  const JointModelGroup* getEndEffector(const std::string& name) const;
405 
407  JointModelGroup* getEndEffector(const std::string& name);
408 
410  const std::vector<const JointModelGroup*>& getEndEffectors() const
411  {
412  return end_effectors_;
413  }
414 
418  std::size_t getVariableCount() const
419  {
420  return variable_count_;
421  }
422 
427  const std::vector<std::string>& getVariableNames() const
428  {
429  return variable_names_;
430  }
431 
433  const VariableBounds& getVariableBounds(const std::string& variable) const
434  {
435  return getJointOfVariable(variable)->getVariableBounds(variable);
436  }
437 
440  {
442  }
443 
444  void getMissingVariableNames(const std::vector<std::string>& variables,
445  std::vector<std::string>& missing_variables) const;
446 
448  int getVariableIndex(const std::string& variable) const;
449 
451  const JointModel* getCommonRoot(const JointModel* a, const JointModel* b) const
452  {
453  if (!a)
454  return b;
455  if (!b)
456  return a;
458  }
459 
461  void setKinematicsAllocators(const std::map<std::string, SolverAllocatorFn>& allocators);
462 
463 protected:
465  void computeFixedTransforms(const LinkModel* link, const Eigen::Isometry3d& transform,
466  LinkTransformMap& associated_transforms);
467 
469  const JointModel* computeCommonRoot(const JointModel* a, const JointModel* b) const;
470 
472  void updateMimicJoints(double* values) const;
473 
474  // GENERIC INFO
475 
477  std::string model_name_;
478 
481  std::string model_frame_;
482 
484 
485  urdf::ModelInterfaceSharedPtr urdf_;
486 
487  // LINKS
488 
490  const LinkModel* root_link_;
491 
494 
496  std::vector<LinkModel*> link_model_vector_;
497 
499  std::vector<const LinkModel*> link_model_vector_const_;
500 
502  std::vector<std::string> link_model_names_vector_;
503 
505  std::vector<const LinkModel*> link_models_with_collision_geometry_vector_;
506 
508  std::vector<std::string> link_model_names_with_collision_geometry_vector_;
509 
511  std::size_t link_geometry_count_;
512 
513  // JOINTS
514 
516  const JointModel* root_joint_;
517 
520 
522  std::vector<JointModel*> joint_model_vector_;
523 
525  std::vector<const JointModel*> joint_model_vector_const_;
526 
528  std::vector<std::string> joint_model_names_vector_;
529 
531  std::vector<JointModel*> active_joint_model_vector_;
532 
534  std::vector<std::string> active_joint_model_names_vector_;
535 
537  std::vector<const JointModel*> active_joint_model_vector_const_;
538 
540  std::vector<const JointModel*> continuous_joint_model_vector_;
541 
543  std::vector<const JointModel*> mimic_joints_;
544 
545  std::vector<const JointModel*> single_dof_joints_;
546 
547  std::vector<const JointModel*> multi_dof_joints_;
548 
556  std::vector<int> common_joint_roots_;
557 
558  // INDEXING
559 
562  std::vector<std::string> variable_names_;
563 
565  std::size_t variable_count_;
566 
571 
572  std::vector<int> active_joint_model_start_index_;
573 
576 
578  std::vector<const JointModel*> joints_of_variable_;
579 
580  // GROUPS
581 
584 
587 
589  std::vector<JointModelGroup*> joint_model_groups_;
590 
592  std::vector<const JointModelGroup*> joint_model_groups_const_;
593 
595  std::vector<std::string> joint_model_group_names_;
596 
598  std::vector<const JointModelGroup*> end_effectors_;
599 
601  void buildModel(const urdf::ModelInterface& urdf_model, const srdf::Model& srdf_model);
602 
604  void buildGroups(const srdf::Model& srdf_model);
605 
608 
610  void buildGroupsInfoEndEffectors(const srdf::Model& srdf_model);
611 
613  void buildMimic(const urdf::ModelInterface& urdf_model);
614 
616  void buildGroupStates(const srdf::Model& srdf_model);
617 
619  void buildJointInfo();
620 
623 
625  void computeCommonRoots();
626 
629  JointModel* buildRecursive(LinkModel* parent, const urdf::Link* link, const srdf::Model& srdf_model);
630 
632  bool addJointModelGroup(const srdf::Model::Group& group);
633 
636  JointModel* constructJointModel(const urdf::Joint* urdf_joint_model, const urdf::Link* child_link,
637  const srdf::Model& srdf_model);
638 
640  LinkModel* constructLinkModel(const urdf::Link* urdf_link);
641 
643  shapes::ShapePtr constructShape(const urdf::Geometry* geom);
644 };
645 } // namespace core
646 } // namespace moveit
647 
648 namespace robot_model = moveit::core;
moveit::core::LinkModel
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:71
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
moveit::core::RobotModel::getModelFrame
const std::string & getModelFrame() const
Get the frame in which the transforms for this model are computed (when using a RobotState)....
Definition: robot_model.h:160
moveit::core::RobotModel::variable_count_
std::size_t variable_count_
Get the number of variables necessary to describe this model.
Definition: robot_model.h:631
moveit::core::RobotModel::getLinkModels
const std::vector< const LinkModel * > & getLinkModels() const
Get the array of links
Definition: robot_model.h:337
moveit::core::RobotModel::getJointModel
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Output error and return NULL when the joint is missing.
Definition: robot_model.cpp:1185
moveit::core::RobotModel::getActiveJointModelNames
const std::vector< std::string > & getActiveJointModelNames() const
Get the array of active joint names, in the order they appear in the robot state.
Definition: robot_model.h:242
moveit::core::RobotModel::end_effectors_
std::vector< const JointModelGroup * > end_effectors_
The array of end-effectors, in alphabetical order.
Definition: robot_model.h:664
exceptions.h
fixed_joint_model.h
moveit::core::RobotModel::getSRDF
const srdf::ModelConstSharedPtr & getSRDF() const
Get the parsed SRDF model.
Definition: robot_model.h:178
moveit::core::RobotModel::active_joint_model_vector_
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:597
moveit::core::RobotModel::active_joint_model_vector_const_
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:603
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
moveit::core::RobotModel::getURDF
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition: robot_model.h:172
moveit::core::RobotModel::setKinematicsAllocators
void setKinematicsAllocators(const std::map< std::string, SolverAllocatorFn > &allocators)
A map of known kinematics solvers (associated to their group name)
Definition: robot_model.cpp:1378
moveit::core::RobotModel::constructLinkModel
LinkModel * constructLinkModel(const urdf::Link *urdf_link)
Given a urdf link, build the corresponding LinkModel object.
Definition: robot_model.cpp:1060
moveit::core::RobotModel::joint_model_vector_const_
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:591
moveit::core::RobotModel::addJointModelGroup
bool addJointModelGroup(const srdf::Model::Group &group)
Construct a JointModelGroup given a SRDF description group.
Definition: robot_model.cpp:733
moveit::core::RobotModel::joint_model_groups_const_
std::vector< const JointModelGroup * > joint_model_groups_const_
The array of joint model groups, in alphabetical order.
Definition: robot_model.h:658
moveit::core::RobotModel::buildGroupsInfoSubgroups
void buildGroupsInfoSubgroups()
Compute helpful information about groups (that can be queried later)
Definition: robot_model.cpp:621
moveit::core::VariableIndexMap
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:147
moveit::core::JointModel::getName
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:196
moveit::core::RobotModel::link_geometry_count_
std::size_t link_geometry_count_
Total number of geometric shapes in this model.
Definition: robot_model.h:577
moveit::core::RobotModel::computeDescendants
void computeDescendants()
For every joint, pre-compute the list of descendant joints & links.
Definition: robot_model.cpp:295
moveit::core::RobotModel::joint_model_names_vector_
std::vector< std::string > joint_model_names_vector_
The vector of joint names that corresponds to joint_model_vector_.
Definition: robot_model.h:594
moveit::core::RobotModel::getVariableBounds
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:499
moveit::core::RobotModel::continuous_joint_model_vector_
std::vector< const JointModel * > continuous_joint_model_vector_
The set of continuous joints this model contains.
Definition: robot_model.h:606
moveit::core::RobotModel::getRootJoint
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:141
moveit::core::RobotModel::joint_model_vector_
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:588
moveit::core::RobotModel::joint_model_group_map_
JointModelGroupMap joint_model_group_map_
A map from group names to joint groups.
Definition: robot_model.h:649
moveit::core::JointBoundsVector
std::vector< const JointModel::Bounds * > JointBoundsVector
Definition: joint_model_group.h:132
moveit::core::RobotModel::getLinkGeometryCount
std::size_t getLinkGeometryCount() const
Definition: robot_model.h:371
class_forward.h
moveit::core::RobotModel::getVariableCount
std::size_t getVariableCount() const
Get the number of variables that describe this model.
Definition: robot_model.h:484
moveit::core::RobotModel::buildRecursive
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),...
Definition: robot_model.cpp:849
moveit::core::RobotModel::computeCommonRoots
void computeCommonRoots()
For every pair of joints, pre-compute the common roots of the joints.
Definition: robot_model.cpp:264
moveit::core::RobotModel::joint_model_group_names_
std::vector< std::string > joint_model_group_names_
A vector of all group names, in alphabetical order.
Definition: robot_model.h:661
moveit::core::RobotModel::joint_model_groups_
std::vector< JointModelGroup * > joint_model_groups_
The array of joint model groups, in alphabetical order.
Definition: robot_model.h:655
moveit::core::RobotModel::getJointModelGroup
const JointModelGroup * getJointModelGroup(const std::string &name) const
Get a joint group from this model (by name)
Definition: robot_model.cpp:547
moveit::core::RobotModel::buildMimic
void buildMimic(const urdf::ModelInterface &urdf_model)
Given the URDF model, build up the mimic joints (mutually constrained joints)
Definition: robot_model.cpp:450
moveit::core::RobotModel::interpolate
void interpolate(const double *from, const double *to, double t, double *state) const
Definition: robot_model.cpp:1366
moveit::core::RobotModel::joint_model_map_
JointModelMap joint_model_map_
A map from joint names to their instances.
Definition: robot_model.h:585
moveit::core::RobotModel::single_dof_joints_
std::vector< const JointModel * > single_dof_joints_
Definition: robot_model.h:611
planar_joint_model.h
moveit::core::RobotModel::link_model_map_
LinkModelMap link_model_map_
A map from link names to their instances.
Definition: robot_model.h:559
moveit::core::RobotModel::link_model_vector_const_
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:565
moveit::core::RobotModel::srdf_
srdf::ModelConstSharedPtr srdf_
Definition: robot_model.h:549
moveit::core::RobotModel::link_model_vector_
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:562
moveit::core::RobotModel::getEndEffectors
const std::vector< const JointModelGroup * > & getEndEffectors() const
Get the map between end effector names and the groups they correspond to.
Definition: robot_model.h:476
moveit::core::RobotModel::getMaximumExtent
double getMaximumExtent() const
Definition: robot_model.h:416
moveit::core::RobotModel::hasEndEffector
bool hasEndEffector(const std::string &eef) const
Check if an end effector exists.
Definition: robot_model.cpp:509
shapes::ShapePtr
std::shared_ptr< Shape > ShapePtr
moveit::core::JointModelMap
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
Definition: joint_model.h:156
moveit::core::RobotModel::link_models_with_collision_geometry_vector_
std::vector< const LinkModel * > link_models_with_collision_geometry_vector_
Only links that have collision geometry specified.
Definition: robot_model.h:571
moveit::core::RobotModel::common_joint_roots_
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:622
moveit::core::RobotModel::getLinkModelsWithCollisionGeometry
const std::vector< const LinkModel * > & getLinkModelsWithCollisionGeometry() const
Get the link models that have some collision geometry associated to themselves.
Definition: robot_model.h:355
moveit::core::RobotModel::isEmpty
bool isEmpty() const
Return true if the model is empty (has no root link, no joints)
Definition: robot_model.h:166
moveit::core::JointModel::getVariableBounds
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a variable. Throw an exception if the variable was not found.
Definition: joint_model.cpp:191
moveit::core::RobotModel::mimic_joints_
std::vector< const JointModel * > mimic_joints_
The set of mimic joints this model contains.
Definition: robot_model.h:609
moveit::core::RobotModel::getJointModelGroupNames
const std::vector< std::string > & getJointModelGroupNames() const
Get the names of all groups that are defined for this model.
Definition: robot_model.h:461
moveit::core::RobotModel::getVariableNames
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:493
moveit::core::RobotModel::model_frame_
std::string model_frame_
The reference (base) frame for this model. The frame is either extracted from the SRDF as a virtual j...
Definition: robot_model.h:547
moveit::core::RobotModel::multi_dof_joints_
std::vector< const JointModel * > multi_dof_joints_
Definition: robot_model.h:613
moveit::core::RobotModel::root_link_
const LinkModel * root_link_
The first physical link for the robot.
Definition: robot_model.h:556
moveit::core::RobotModel::link_model_names_vector_
std::vector< std::string > link_model_names_vector_
The vector of link names that corresponds to link_model_vector_.
Definition: robot_model.h:568
moveit::core::RobotModel::urdf_
urdf::ModelInterfaceSharedPtr urdf_
Definition: robot_model.h:551
moveit::core::RobotModel::RobotModel
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:123
moveit::core::RobotModel::getJointOfVariable
const JointModel * getJointOfVariable(int variable_index) const
Definition: robot_model.h:279
model.h
moveit::core::RobotModel::buildGroupsInfoEndEffectors
void buildGroupsInfoEndEffectors(const srdf::Model &srdf_model)
Compute helpful information about groups (that can be queried later)
Definition: robot_model.cpp:650
srdf::ModelConstSharedPtr
std::shared_ptr< const Model > ModelConstSharedPtr
moveit::core::RobotModel::computeFixedTransforms
void computeFixedTransforms(const LinkModel *link, const Eigen::Isometry3d &transform, LinkTransformMap &associated_transforms)
Get the transforms between link and all its rigidly attached descendants.
Definition: robot_model.cpp:1499
moveit::core::RobotModel::hasJointModelGroup
bool hasJointModelGroup(const std::string &group) const
Check if the JointModelGroup group exists.
Definition: robot_model.cpp:542
moveit::core::RobotModel::joints_of_variable_
std::vector< const JointModel * > joints_of_variable_
The joints that correspond to each variable index.
Definition: robot_model.h:644
moveit::core::RobotModel::getActiveJointModels
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:236
moveit::core::RobotModel::satisfiesPositionBounds
bool satisfiesPositionBounds(const double *state, double margin=0.0) const
Definition: robot_model.h:410
moveit::core::RobotModel::active_joint_models_bounds_
JointBoundsVector active_joint_models_bounds_
The bounds for all the active joint models.
Definition: robot_model.h:641
moveit::core::RobotModel::getLinkModelCount
std::size_t getLinkModelCount() const
Definition: robot_model.h:366
moveit::core::RobotModel::enforcePositionBounds
bool enforcePositionBounds(double *state) const
Definition: robot_model.h:405
moveit::core::RobotModel::getContinuousJointModels
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:267
moveit::core::RobotModel::constructJointModel
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...
Definition: robot_model.cpp:934
moveit::core::JointModel::getJointIndex
int getJointIndex() const
Get the index of this joint within the robot model.
Definition: joint_model.h:279
moveit::core::RobotModel::link_model_names_with_collision_geometry_vector_
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:574
moveit::core::RobotModel::variable_names_
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:628
moveit::core::LOGNAME
const std::string LOGNAME
Definition: joint_model_group.cpp:165
moveit::core::RobotModel::buildGroupStates
void buildGroupStates(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build the default states defined in the SRDF.
Definition: robot_model.cpp:390
moveit::core::RobotModel::getRootLink
const LinkModel * getRootLink() const
Get the physical root link of the robot.
Definition: robot_model.cpp:146
moveit::core::RobotModel::buildJointInfo
void buildJointInfo()
Compute helpful information about joints.
Definition: robot_model.cpp:315
moveit::core::LinkTransformMap
std::map< const LinkModel *, Eigen::Isometry3d, std::less< const LinkModel * >, Eigen::aligned_allocator< std::pair< const LinkModel *const, Eigen::Isometry3d > > > LinkTransformMap
Map from link model instances to Eigen transforms.
Definition: link_model.h:68
moveit::core::RobotModel::active_joint_model_start_index_
std::vector< int > active_joint_model_start_index_
Definition: robot_model.h:638
moveit::core::RobotModel::getName
const std::string & getName() const
Get the model name.
Definition: robot_model.h:151
ROS_WARN_STREAM_COND_NAMED
#define ROS_WARN_STREAM_COND_NAMED(cond, name, args)
moveit::core::LinkModelMap
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
Definition: link_model.h:58
revolute_joint_model.h
random_numbers::RandomNumberGenerator
moveit::core::RobotModel::printModelInfo
void printModelInfo(std::ostream &out) const
Print information about the constructed model.
Definition: robot_model.cpp:1450
moveit::core::RobotModel::getLinkModel
const LinkModel * getLinkModel(const std::string &link, bool *has_link=nullptr) const
Get a link by its name. Output error and return NULL when the link is missing.
Definition: robot_model.cpp:1214
moveit::core::RobotModel::getMissingVariableNames
void getMissingVariableNames(const std::vector< std::string > &variables, std::vector< std::string > &missing_variables) const
Definition: robot_model.cpp:1304
moveit::core::RobotModel::getRigidlyConnectedParentLinkModel
static const moveit::core::LinkModel * getRigidlyConnectedParentLinkModel(const LinkModel *link)
Get the latest link upwards the kinematic tree, which is only connected via fixed joints.
Definition: robot_model.cpp:1245
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
values
std::vector< double > values
moveit::core::RobotModel::getCommonRoot
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:517
moveit::core::RobotModel::model_name_
std::string model_name_
The name of the robot.
Definition: robot_model.h:543
moveit::core::RobotModel::getJointModelGroups
const std::vector< const JointModelGroup * > & getJointModelGroups() const
Get the available joint groups.
Definition: robot_model.h:449
moveit::core::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(JointModelGroup)
moveit::core::RobotModel::getRootLinkName
const std::string & getRootLinkName() const
Get the name of the root link of the robot.
Definition: robot_model.h:304
moveit::core::RobotModel::getMimicJointModels
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:274
moveit::core::RobotModel::active_joint_model_names_vector_
std::vector< std::string > active_joint_model_names_vector_
The vector of joint names that corresponds to active_joint_model_vector_.
Definition: robot_model.h:600
moveit::core::RobotModel::getVariableIndex
int getVariableIndex(const std::string &variable) const
Get the index of a variable in the robot state.
Definition: robot_model.cpp:1315
moveit::core::RobotModel::getActiveJointModelsBounds
const JointBoundsVector & getActiveJointModelsBounds() const
Get the bounds for all the active joints.
Definition: robot_model.h:505
moveit::core::RobotModel::distance
double distance(const double *state1, const double *state2) const
Return the sum of joint distances between two states. Only considers active joints.
Definition: robot_model.cpp:1356
moveit::core::RobotModel::getLinkModelNames
const std::vector< std::string > & getLinkModelNames() const
Get the link names (of all links)
Definition: robot_model.h:349
moveit::core::RobotModel::getJointModels
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:216
joint_model_group.h
moveit::core::JointModelGroupMap
std::map< std::string, JointModelGroup * > JointModelGroupMap
Map of names to instances for JointModelGroup.
Definition: joint_model_group.h:127
moveit::core::RobotModel::hasJointModel
bool hasJointModel(const std::string &name) const
Check if a joint exists. Return true if it does.
Definition: robot_model.cpp:1175
moveit::core::RobotModel::constructShape
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...
Definition: robot_model.cpp:1136
floating_joint_model.h
moveit::core::RobotModel::joint_variables_index_map_
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:636
srdf::Model::Group
moveit::core::RobotModel::getMultiDOFJointModels
const std::vector< const JointModel * > & getMultiDOFJointModels() const
This is a list of all multi-dof joints.
Definition: robot_model.h:260
srdf::Model
moveit::core::LinkModel::getName
const std::string & getName() const
The name of this link.
Definition: link_model.h:80
moveit::core::RobotModel::getJointModelCount
std::size_t getJointModelCount() const
Definition: robot_model.h:289
moveit::core::RobotModel::getLinkModelNamesWithCollisionGeometry
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:361
moveit::core::RobotModel::root_joint_
const JointModel * root_joint_
The root joint.
Definition: robot_model.h:582
moveit::core::RobotModel::buildGroups
void buildGroups(const srdf::Model &srdf_model)
Given a SRDF model describing the groups, build up the groups in this kinematic model.
Definition: robot_model.cpp:569
moveit::core::RobotModel::getVariableDefaultPositions
void getVariableDefaultPositions(double *values) const
Compute the default values for a RobotState.
Definition: robot_model.cpp:1288
moveit::core::RobotModel::getSingleDOFJointModels
const std::vector< const JointModel * > & getSingleDOFJointModels() const
This is a list of all single-dof joints (including mimic joints)
Definition: robot_model.h:254
moveit::core::checkInterpolationParamBounds
static void checkInterpolationParamBounds(const char LOGNAME[], double t)
Definition: robot_model.h:130
moveit::core::RobotModel::getVariableRandomPositions
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values) const
Compute the random values for a RobotState.
Definition: robot_model.cpp:1271
moveit::core::RobotModel::updateMimicJoints
void updateMimicJoints(double *values) const
Update the variable values for the state of a group with respect to the mimic joints.
Definition: robot_model.cpp:1261
moveit::core::RobotModel::~RobotModel
~RobotModel()
Destructor. Clear all memory.
Definition: robot_model.cpp:131
moveit::core::RobotModel::computeCommonRoot
const JointModel * computeCommonRoot(const JointModel *a, const JointModel *b) const
Given two joints, find their common root.
moveit::core::RobotModel::buildModel
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:151
moveit::core::RobotModel::getJointModelNames
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:230
moveit::core::JointModel
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:173
moveit::core::RobotModel::getRootJointName
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:197
moveit::core::RobotModel::hasLinkModel
bool hasLinkModel(const std::string &name) const
Check if a link exists. Return true if it does.
Definition: robot_model.cpp:1180
moveit::core::RobotModel::getEndEffector
const JointModelGroup * getEndEffector(const std::string &name) const
Get the joint group that corresponds to a given end-effector name.
Definition: robot_model.cpp:514
moveit::core::RobotModel::end_effectors_map_
JointModelGroupMap end_effectors_map_
The known end effectors.
Definition: robot_model.h:652
prismatic_joint_model.h


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 21 2021 03:25:56