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 #pragma once
38 
39 #include <string>
40 #include <vector>
41 #include <utility>
42 #include <map>
43 #include <Eigen/Geometry>
47 
48 namespace shapes
49 {
50 MOVEIT_CLASS_FORWARD(Shape); // Defines ShapePtr, ConstPtr, WeakPtr... etc
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 using LinkModelMapConst = std::map<std::string, const LinkModel*>;
65 
67 using LinkTransformMap = std::map<const LinkModel*, Eigen::Isometry3d, std::less<const LinkModel*>,
68  Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Isometry3d> > >;
69 
71 class LinkModel
72 {
73 public:
74  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
75 
76  LinkModel(const std::string& name);
77  ~LinkModel();
78 
80  const std::string& getName() const
81  {
82  return name_;
83  }
84 
86  int getLinkIndex() const
87  {
88  return link_index_;
89  }
90 
91  void setLinkIndex(int index)
92  {
94  }
95 
97  {
99  }
100 
102  {
104  }
105 
108  {
109  return parent_joint_model_;
110  }
111 
112  void setParentJointModel(const JointModel* joint);
113 
117  {
118  return parent_link_model_;
119  }
120 
121  void setParentLinkModel(const LinkModel* link)
122  {
123  parent_link_model_ = link;
124  }
125 
127  const std::vector<const JointModel*>& getChildJointModels() const
128  {
129  return child_joint_models_;
130  }
131 
132  void addChildJointModel(const JointModel* joint)
133  {
134  child_joint_models_.push_back(joint);
135  }
136 
142  const Eigen::Isometry3d& getJointOriginTransform() const
143  {
145  }
146 
148  {
150  }
151 
152  bool parentJointIsFixed() const
153  {
154  return is_parent_joint_fixed_;
155  }
156 
157  void setJointOriginTransform(const Eigen::Isometry3d& transform);
158 
164  {
166  }
167 
169  const std::vector<int>& areCollisionOriginTransformsIdentity() const
170  {
172  }
173 
175  const std::vector<shapes::ShapeConstPtr>& getShapes() const
176  {
177  return shapes_;
178  }
179 
180  void setGeometry(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& origins);
181 
186  {
187  return shape_extents_;
188  }
189 
192  {
194  }
195 
199  {
201  }
202 
204  void addAssociatedFixedTransform(const LinkModel* link_model, const Eigen::Isometry3d& transform)
205  {
206  ASSERT_ISOMETRY(transform); // unsanitized input, could contain a non-isometry
208  }
209 
211  const std::string& getVisualMeshFilename() const
212  {
213  return visual_mesh_filename_;
214  }
215 
218  {
219  return visual_mesh_scale_;
220  }
221 
223  const Eigen::Isometry3d& getVisualMeshOrigin() const
224  {
225  return visual_mesh_origin_;
226  }
227 
228  void setVisualMesh(const std::string& visual_mesh, const Eigen::Isometry3d& origin, const Eigen::Vector3d& scale);
229 
230 private:
232  std::string name_;
233 
236 
239 
241  std::vector<const JointModel*> child_joint_models_;
242 
245 
248 
250  Eigen::Isometry3d joint_origin_transform_;
251 
254 
258 
261 
263  std::vector<shapes::ShapeConstPtr> shapes_;
264 
267 
270 
273 
275  Eigen::Isometry3d visual_mesh_origin_;
276 
279 
283 
286 };
287 } // namespace core
288 } // namespace moveit
moveit::core::LinkModel::getJointOriginTransform
const Eigen::Isometry3d & getJointOriginTransform() const
When transforms are computed for this link, they are usually applied to the link's origin....
Definition: link_model.h:142
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::LinkModel::shapes_
std::vector< shapes::ShapeConstPtr > shapes_
The collision geometry of the link.
Definition: link_model.h:263
moveit::core::LinkModel::first_collision_body_transform_index_
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:282
moveit::core::LinkModel::visual_mesh_origin_
Eigen::Isometry3d visual_mesh_origin_
The additional origin transform for the mesh.
Definition: link_model.h:275
moveit::core::LinkModel::setJointOriginTransform
void setJointOriginTransform(const Eigen::Isometry3d &transform)
Definition: link_model.cpp:125
shapes
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
moveit::core::LinkModel::setGeometry
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &origins)
Definition: link_model.cpp:140
moveit::core::LinkModel::getVisualMeshFilename
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
Definition: link_model.h:211
moveit::core::LinkModel::getChildJointModels
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:127
check_isometry.h
moveit::core::LinkModel::visual_mesh_scale_
Eigen::Vector3d visual_mesh_scale_
Scale factor associated with the visual geometry mesh of this link.
Definition: link_model.h:278
moveit::core::LinkModel::getShapeExtentsAtOrigin
const Eigen::Vector3d & getShapeExtentsAtOrigin() const
Get the extents of the link's geometry (dimensions of axis-aligned bounding box around all shapes tha...
Definition: link_model.h:185
moveit::core::LinkModel::getParentJointModel
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.h:107
moveit::core::LinkModel::child_joint_models_
std::vector< const JointModel * > child_joint_models_
List of directly descending joints (each connects to a child link)
Definition: link_model.h:241
class_forward.h
shapes::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(Shape)
moveit::core::LinkModel::getCenteredBoundingBoxOffset
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:191
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
moveit::core::LinkModel::~LinkModel
~LinkModel()
moveit::core::LinkModel::LinkModel
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel(const std::string &name)
Definition: link_model.cpp:111
moveit::core::LinkModel::setParentJointModel
void setParentJointModel(const JointModel *joint)
Definition: link_model.cpp:134
moveit::core::LinkModel::joint_origin_transform_
Eigen::Isometry3d joint_origin_transform_
The constant transform applied to the link (local)
Definition: link_model.h:250
moveit::core::LinkModel::areCollisionOriginTransformsIdentity
const std::vector< int > & areCollisionOriginTransformsIdentity() const
Return flags for each transform specifying whether they are identity or not.
Definition: link_model.h:169
moveit::core::LinkModel::getVisualMeshScale
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
Definition: link_model.h:217
moveit::core::LinkModel::name_
std::string name_
Name of the link.
Definition: link_model.h:232
moveit::core::LinkModel::link_index_
int link_index_
Index of the transform for this link in the full robot frame.
Definition: link_model.h:285
moveit::core::LinkModel::is_parent_joint_fixed_
bool is_parent_joint_fixed_
True if the parent joint of this link is fixed.
Definition: link_model.h:244
name
std::string name
moveit::core::LinkModel::setLinkIndex
void setLinkIndex(int index)
Definition: link_model.h:91
moveit::core::LinkModel::visual_mesh_filename_
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:272
ASSERT_ISOMETRY
#define ASSERT_ISOMETRY(transform)
moveit::core::LinkModel::getAssociatedFixedTransforms
const LinkTransformMap & getAssociatedFixedTransforms() const
Get the set of links that are attached to this one via fixed transforms. The returned transforms are ...
Definition: link_model.h:198
moveit::core::LinkModel::addChildJointModel
void addChildJointModel(const JointModel *joint)
Definition: link_model.h:132
moveit::core::LinkModel::parent_link_model_
const LinkModel * parent_link_model_
The parent link model (NULL for the root link)
Definition: link_model.h:238
moveit::core::LinkModel::collision_origin_transform_
EigenSTL::vector_Isometry3d collision_origin_transform_
The constant transform applied to the collision geometry of the link (local)
Definition: link_model.h:253
moveit::core::LinkModel::getCollisionOriginTransforms
const EigenSTL::vector_Isometry3d & 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:163
moveit::core::LinkModel::getFirstCollisionBodyTransformIndex
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:96
moveit::core::LinkModel::associated_fixed_transforms_
LinkTransformMap associated_fixed_transforms_
The set of links that are attached to this one via fixed transforms.
Definition: link_model.h:260
moveit::core::LinkModelMapConst
std::map< std::string, const LinkModel * > LinkModelMapConst
Map of names to const instances for LinkModel.
Definition: link_model.h:64
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::LinkModelMap
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
Definition: link_model.h:58
moveit::core::LinkModel::setParentLinkModel
void setParentLinkModel(const LinkModel *link)
Definition: link_model.h:121
moveit::core::LinkModel::joint_origin_transform_is_identity_
bool joint_origin_transform_is_identity_
True of the joint origin transform is identity.
Definition: link_model.h:247
moveit::core::LinkModel::setFirstCollisionBodyTransformIndex
void setFirstCollisionBodyTransformIndex(int index)
Definition: link_model.h:101
moveit::core::LinkModel::getLinkIndex
int getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition: link_model.h:86
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
moveit::core::LinkModel::getVisualMeshOrigin
const Eigen::Isometry3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
Definition: link_model.h:223
moveit::core::LinkModel::jointOriginTransformIsIdentity
bool jointOriginTransformIsIdentity() const
Definition: link_model.h:147
index
unsigned int index
moveit::core::LinkModel::parent_joint_model_
const JointModel * parent_joint_model_
JointModel that connects this link to the parent link.
Definition: link_model.h:235
moveit::core::LinkModel::getShapes
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition: link_model.h:175
moveit::core::LinkModel::getName
const std::string & getName() const
The name of this link.
Definition: link_model.h:80
moveit::core::LinkModel::centered_bounding_box_offset_
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:269
moveit::core::LinkModel::addAssociatedFixedTransform
void addAssociatedFixedTransform(const LinkModel *link_model, const Eigen::Isometry3d &transform)
Remember that link_model is attached to this link using a fixed transform.
Definition: link_model.h:204
moveit::core::LinkModel::collision_origin_transform_is_identity_
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:257
eigen_stl_vector_container.h
moveit::core::LinkModel::setVisualMesh
void setVisualMesh(const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale)
Definition: link_model.cpp:182
moveit::core::LinkModel::parentJointIsFixed
bool parentJointIsFixed() const
Definition: link_model.h:152
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::LinkModel::getParentLinkModel
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:116
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
moveit::core::LinkModel::shape_extents_
Eigen::Vector3d shape_extents_
The extents of shape (dimensions of axis aligned bounding box when shape is at origin).
Definition: link_model.h:266


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:40