moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
44#include <eigen_stl_containers/eigen_stl_vector_container.h>
46#include <geometric_shapes/check_isometry.h>
47
48namespace shapes
49{
50MOVEIT_CLASS_FORWARD(Shape); // Defines ShapePtr, ConstPtr, WeakPtr... etc
51}
52
53namespace moveit
54{
55namespace core
56{
57class JointModel;
58class LinkModel;
59
61typedef std::map<std::string, LinkModel*> LinkModelMap;
62
64using LinkModelMapConst = std::map<std::string, const LinkModel*>;
65
67using LinkTransformMap = std::map<const LinkModel*, Eigen::Isometry3d, std::less<const LinkModel*>,
68 Eigen::aligned_allocator<std::pair<const LinkModel* const, Eigen::Isometry3d> > >;
69
72{
73public:
75
82 LinkModel(const std::string& name, size_t link_index);
84
86 const std::string& getName() const
87 {
88 return name_;
89 }
90
92 size_t getLinkIndex() const
93 {
94 return link_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
118 {
119 return parent_link_model_;
120 }
121
123 {
124 parent_link_model_ = link;
125 }
126
128 const std::vector<const JointModel*>& getChildJointModels() const
129 {
130 return child_joint_models_;
131 }
132
134 {
135 child_joint_models_.push_back(joint);
136 }
137
143 const Eigen::Isometry3d& getJointOriginTransform() const
144 {
145 return joint_origin_transform_;
146 }
147
149 {
150 return joint_origin_transform_is_identity_;
151 }
152
154 {
155 return is_parent_joint_fixed_;
156 }
157
158 void setJointOriginTransform(const Eigen::Isometry3d& transform);
159
164 const EigenSTL::vector_Isometry3d& getCollisionOriginTransforms() const
165 {
166 return collision_origin_transform_;
167 }
168
170 const std::vector<int>& areCollisionOriginTransformsIdentity() const
171 {
172 return collision_origin_transform_is_identity_;
173 }
174
176 const std::vector<shapes::ShapeConstPtr>& getShapes() const
177 {
178 return shapes_;
179 }
180
181 void setGeometry(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& origins);
182
186 const Eigen::Vector3d& getShapeExtentsAtOrigin() const
187 {
188 return shape_extents_;
189 }
190
192 const Eigen::Vector3d& getCenteredBoundingBoxOffset() const
193 {
194 return centered_bounding_box_offset_;
195 }
196
200 {
201 return associated_fixed_transforms_;
202 }
203
205 void addAssociatedFixedTransform(const LinkModel* link_model, const Eigen::Isometry3d& transform)
206 {
207 ASSERT_ISOMETRY(transform); // unsanitized input, could contain a non-isometry
208 associated_fixed_transforms_[link_model] = transform;
209 }
210
212 const std::string& getVisualMeshFilename() const
213 {
214 return visual_mesh_filename_;
215 }
216
218 const Eigen::Vector3d& getVisualMeshScale() const
219 {
220 return visual_mesh_scale_;
221 }
222
224 const Eigen::Isometry3d& getVisualMeshOrigin() const
225 {
226 return visual_mesh_origin_;
227 }
228
229 void setVisualMesh(const std::string& visual_mesh, const Eigen::Isometry3d& origin, const Eigen::Vector3d& scale);
230
231private:
233 std::string name_;
234
236 size_t link_index_;
237
239 const JointModel* parent_joint_model_;
240
242 const LinkModel* parent_link_model_;
243
245 std::vector<const JointModel*> child_joint_models_;
246
248 bool is_parent_joint_fixed_;
249
251 bool joint_origin_transform_is_identity_;
252
254 Eigen::Isometry3d joint_origin_transform_;
255
257 EigenSTL::vector_Isometry3d collision_origin_transform_;
258
261 std::vector<int> collision_origin_transform_is_identity_;
262
264 LinkTransformMap associated_fixed_transforms_;
265
267 std::vector<shapes::ShapeConstPtr> shapes_;
268
270 Eigen::Vector3d shape_extents_;
271
273 Eigen::Vector3d centered_bounding_box_offset_;
274
276 std::string visual_mesh_filename_;
277
279 Eigen::Isometry3d visual_mesh_origin_;
280
282 Eigen::Vector3d visual_mesh_scale_;
283
286 int first_collision_body_transform_index_;
287};
288} // namespace core
289} // namespace moveit
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
#define MOVEIT_CLASS_FORWARD(C)
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
int getFirstCollisionBodyTransformIndex() const
Definition link_model.h:97
const std::string & getName() const
The name of this link.
Definition link_model.h:86
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:205
bool jointOriginTransformIsIdentity() const
Definition link_model.h:148
const Eigen::Isometry3d & getVisualMeshOrigin() const
Get the transform for the visual mesh origin.
Definition link_model.h:224
const std::string & getVisualMeshFilename() const
Get the filename of the mesh resource used for visual display of this link.
Definition link_model.h:212
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
const Eigen::Vector3d & getVisualMeshScale() const
Get the scale of the mesh resource for this link.
Definition link_model.h:218
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:192
void setFirstCollisionBodyTransformIndex(int index)
Definition link_model.h:102
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:164
void addChildJointModel(const JointModel *joint)
Definition link_model.h:133
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &origins)
void setParentLinkModel(const LinkModel *link)
Definition link_model.h:122
bool parentJointIsFixed() const
Definition link_model.h:153
void setParentJointModel(const JointModel *joint)
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 std::vector< int > & areCollisionOriginTransformsIdentity() const
Return flags for each transform specifying whether they are identity or not.
Definition link_model.h:170
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition link_model.h:176
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:143
void setVisualMesh(const std::string &visual_mesh, const Eigen::Isometry3d &origin, const Eigen::Vector3d &scale)
void setJointOriginTransform(const Eigen::Isometry3d &transform)
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's geometry (dimensions of axis-aligned bounding box around all shapes tha...
Definition link_model.h:186
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:199
size_t getLinkIndex() const
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition link_model.h:92
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
std::map< std::string, const LinkModel * > LinkModelMapConst
Map of names to const instances for LinkModel.
Definition link_model.h:64
std::map< std::string, LinkModel * > LinkModelMap
Map of names to instances for LinkModel.
Definition link_model.h:61
Main namespace for MoveIt.
Definition exceptions.h:43
Definition world.h:49