link_model.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #ifndef MOVEIT_CORE_ROBOT_MODEL_LINK_MODEL_
38 #define MOVEIT_CORE_ROBOT_MODEL_LINK_MODEL_
39 
40 #include <string>
41 #include <vector>
42 #include <utility>
43 #include <map>
44 #include <Eigen/Geometry>
47 
48 namespace shapes
49 {
51 }
52 
53 namespace moveit
54 {
55 namespace core
56 {
57 class JointModel;
58 class LinkModel;
59 
61 typedef std::map<std::string, LinkModel*> LinkModelMap;
62 
64 typedef std::map<std::string, const LinkModel*> LinkModelMapConst;
65 
67 typedef std::map<const LinkModel*, Eigen::Affine3d, std::less<const LinkModel*>,
68  Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Affine3d> > >
70 
72 class LinkModel
73 {
74 public:
76 
77  LinkModel(const std::string& name);
78  ~LinkModel();
79 
81  const std::string& getName() const
82  {
83  return name_;
84  }
85 
87  int getLinkIndex() const
88  {
89  return link_index_;
90  }
91 
92  void setLinkIndex(int index)
93  {
94  link_index_ = index;
95  }
96 
98  {
99  return first_collision_body_transform_index_;
100  }
101 
103  {
104  first_collision_body_transform_index_ = index;
105  }
106 
109  {
110  return parent_joint_model_;
111  }
112 
113  void setParentJointModel(const JointModel* joint);
114 
117  const LinkModel* getParentLinkModel() const
118  {
119  return parent_link_model_;
120  }
121 
122  void setParentLinkModel(const LinkModel* link)
123  {
124  parent_link_model_ = link;
125  }
126 
128  const std::vector<const JointModel*>& getChildJointModels() const
129  {
130  return child_joint_models_;
131  }
132 
133  void addChildJointModel(const JointModel* joint)
134  {
135  child_joint_models_.push_back(joint);
136  }
137 
142  const Eigen::Affine3d& getJointOriginTransform() const
143  {
144  return joint_origin_transform_;
145  }
146 
148  {
149  return joint_origin_transform_is_identity_;
150  }
151 
152  bool parentJointIsFixed() const
153  {
154  return is_parent_joint_fixed_;
155  }
156 
157  void setJointOriginTransform(const Eigen::Affine3d& transform);
158 
163  {
164  return collision_origin_transform_;
165  }
166 
168  const std::vector<int>& areCollisionOriginTransformsIdentity() const
169  {
170  return collision_origin_transform_is_identity_;
171  }
172 
174  const std::vector<shapes::ShapeConstPtr>& getShapes() const
175  {
176  return shapes_;
177  }
178 
179  void setGeometry(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Affine3d& origins);
180 
184  const Eigen::Vector3d& getShapeExtentsAtOrigin() const
185  {
186  return shape_extents_;
187  }
188 
190  const Eigen::Vector3d& getCenteredBoundingBoxOffset() const
191  {
192  return centered_bounding_box_offset_;
193  }
194 
197  {
198  return associated_fixed_transforms_;
199  }
200 
202  void addAssociatedFixedTransform(const LinkModel* link_model, const Eigen::Affine3d& transform)
203  {
204  associated_fixed_transforms_[link_model] = transform;
205  }
206 
208  const std::string& getVisualMeshFilename() const
209  {
210  return visual_mesh_filename_;
211  }
212 
214  const Eigen::Vector3d& getVisualMeshScale() const
215  {
216  return visual_mesh_scale_;
217  }
218 
220  const Eigen::Affine3d& getVisualMeshOrigin() const
221  {
222  return visual_mesh_origin_;
223  }
224 
225  void setVisualMesh(const std::string& visual_mesh, const Eigen::Affine3d& origin, const Eigen::Vector3d& scale);
226 
227 private:
229  std::string name_;
230 
233 
235  const LinkModel* parent_link_model_;
236 
238  std::vector<const JointModel*> child_joint_models_;
239 
242 
245 
247  Eigen::Affine3d joint_origin_transform_;
248 
251 
255 
258 
260  std::vector<shapes::ShapeConstPtr> shapes_;
261 
263  Eigen::Vector3d shape_extents_;
264 
267 
270 
272  Eigen::Affine3d visual_mesh_origin_;
273 
275  Eigen::Vector3d visual_mesh_scale_;
276 
280 
283 };
284 }
285 }
286 
287 #endif
const std::string & getName() const
The name of this link.
Definition: link_model.h:81
std::vector< const JointModel * > child_joint_models_
List of directly descending joints (each connects to a child link)
Definition: link_model.h:238
std::map< std::string, const LinkModel * > LinkModelMapConst
Map of names to const instances for LinkModel.
Definition: link_model.h:64
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
Definition: link_model.h:208
const Eigen::Vector3d & getCenteredBoundingBoxOffset() const
Get the offset of the center of the bounding box of this link when the link is positioned at origin...
Definition: link_model.h:190
int first_collision_body_transform_index_
Index of the transform for the first shape that makes up the geometry of this link in the full robot ...
Definition: link_model.h:279
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
const std::vector< const JointModel * > & getChildJointModels() const
A link may have 0 or more child joints. From those joints there will certainly be other descendant li...
Definition: link_model.h:128
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
Get the extents of the link&#39;s geometry (dimensions of axis-aligned bounding box around all shapes tha...
Definition: link_model.h:184
LinkTransformMap associated_fixed_transforms_
The set of links that are attached to this one via fixed transforms.
Definition: link_model.h:257
const EigenSTL::vector_Affine3d & getCollisionOriginTransforms() const
In addition to the link transform, the geometry of a link that is used for collision checking may hav...
Definition: link_model.h:162
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
Eigen::Vector3d visual_mesh_scale_
Scale factor associated with the visual geometry mesh of this link.
Definition: link_model.h:275
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
void setFirstCollisionBodyTransformIndex(int index)
Definition: link_model.h:102
void addChildJointModel(const JointModel *joint)
Definition: link_model.h:133
const JointModel * parent_joint_model_
JointModel that connects this link to the parent link.
Definition: link_model.h:232
const std::vector< int > & areCollisionOriginTransformsIdentity() const
Return flags for each transform specifying whether they are identity or not.
Definition: link_model.h:168
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.h:108
std::vector< int > collision_origin_transform_is_identity_
Flag indicating if the constant transform applied to the collision geometry of the link (local) is id...
Definition: link_model.h:254
int getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition: link_model.h:87
const Eigen::Affine3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
Definition: link_model.h:220
MOVEIT_CLASS_FORWARD(Shape)
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition: link_model.h:174
void addAssociatedFixedTransform(const LinkModel *link_model, const Eigen::Affine3d &transform)
Remember that link_model is attached to this link using a fixed transform.
Definition: link_model.h:202
Eigen::Affine3d visual_mesh_origin_
The additional origin transform for the mesh.
Definition: link_model.h:272
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
Definition: joint_model.h:108
void setLinkIndex(int index)
Definition: link_model.h:92
bool parentJointIsFixed() const
Definition: link_model.h:152
Eigen::Vector3d shape_extents_
The extents of shape (dimensions of axis aligned bounding box when shape is at origin).
Definition: link_model.h:263
void setParentLinkModel(const LinkModel *link)
Definition: link_model.h:122
bool joint_origin_transform_is_identity_
True of the joint origin transform is identity.
Definition: link_model.h:244
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
Definition: link_model.h:58
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
Definition: link_model.h:214
Eigen::Vector3d centered_bounding_box_offset_
Center of the axis aligned bounding box with size shape_extents_ (zero if symmetric along all axes)...
Definition: link_model.h:266
bool jointOriginTransformIsIdentity() const
Definition: link_model.h:147
std::string visual_mesh_filename_
Filename associated with the visual geometry mesh of this link. If empty, no mesh was used...
Definition: link_model.h:269
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms.
Definition: link_model.h:196
Eigen::Affine3d joint_origin_transform_
The constant transform applied to the link (local)
Definition: link_model.h:247
int link_index_
Index of the transform for this link in the full robot frame.
Definition: link_model.h:282
A link from the robot. Contains the constant transform applied to the link and its geometry...
Definition: link_model.h:72
const Eigen::Affine3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link&#39;s origin...
Definition: link_model.h:142
EigenSTL::vector_Affine3d collision_origin_transform_
The constant transform applied to the collision geometry of the link (local)
Definition: link_model.h:250
const LinkModel * getParentLinkModel() const
Get the link model whose child this link is (through some joint). There may not always be a parent li...
Definition: link_model.h:117
const LinkModel * parent_link_model_
The parent link model (NULL for the root link)
Definition: link_model.h:235
Main namespace for MoveIt!
std::vector< shapes::ShapeConstPtr > shapes_
The collision geometry of the link.
Definition: link_model.h:260
std::string name_
Name of the link.
Definition: link_model.h:229
bool is_parent_joint_fixed_
True if the parent joint of this link is fixed.
Definition: link_model.h:241


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