link_model.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 the Willow Garage 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 
41 
42 namespace moveit
43 {
44 namespace core
45 {
46 LinkModel::LinkModel(const std::string& name)
47  : name_(name)
48  , parent_joint_model_(nullptr)
49  , parent_link_model_(nullptr)
50  , is_parent_joint_fixed_(false)
51  , joint_origin_transform_is_identity_(true)
52  , first_collision_body_transform_index_(-1)
53  , link_index_(-1)
54 {
55  joint_origin_transform_.setIdentity();
56 }
57 
58 LinkModel::~LinkModel() = default;
59 
60 void LinkModel::setJointOriginTransform(const Eigen::Affine3d& transform)
61 {
62  joint_origin_transform_ = transform;
64  joint_origin_transform_.linear().isIdentity() &&
65  joint_origin_transform_.translation().norm() < std::numeric_limits<double>::epsilon();
66 }
67 
69 {
70  parent_joint_model_ = joint;
72 }
73 
74 void LinkModel::setGeometry(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Affine3d& origins)
75 {
76  shapes_ = shapes;
79 
80  core::AABB aabb;
81 
82  for (std::size_t i = 0; i < shapes_.size(); ++i)
83  {
85  (collision_origin_transform_[i].linear().isIdentity() &&
86  collision_origin_transform_[i].translation().norm() < std::numeric_limits<double>::epsilon()) ?
87  1 :
88  0;
89  Eigen::Affine3d transform = collision_origin_transform_[i];
90 
91  if (shapes_[i]->type != shapes::MESH)
92  {
93  Eigen::Vector3d extents = shapes::computeShapeExtents(shapes_[i].get());
94  aabb.extendWithTransformedBox(transform, extents);
95  }
96  else
97  {
98  // we cannot use shapes::computeShapeExtents() for meshes, since that method does not provide information about
99  // the offset of the mesh origin
100  const shapes::Mesh* mesh = dynamic_cast<const shapes::Mesh*>(shapes_[i].get());
101  for (unsigned int j = 0; j < mesh->vertex_count; ++j)
102  {
103  aabb.extend(transform * Eigen::Map<Eigen::Vector3d>(&mesh->vertices[3 * j]));
104  }
105  }
106  }
107 
108  centered_bounding_box_offset_ = aabb.center();
109  if (shapes_.empty())
110  shape_extents_.setZero();
111  else
112  shape_extents_ = aabb.sizes();
113 }
114 
115 void LinkModel::setVisualMesh(const std::string& visual_mesh, const Eigen::Affine3d& origin,
116  const Eigen::Vector3d& scale)
117 {
118  visual_mesh_filename_ = visual_mesh;
119  visual_mesh_origin_ = origin;
120  visual_mesh_scale_ = scale;
121 }
122 
123 } // end of namespace core
124 } // end of namespace moveit
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
void setJointOriginTransform(const Eigen::Affine3d &transform)
Definition: link_model.cpp:60
Eigen::Vector3d visual_mesh_scale_
Scale factor associated with the visual geometry mesh of this link.
Definition: link_model.h:275
const JointModel * parent_joint_model_
JointModel that connects this link to the parent link.
Definition: link_model.h:232
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
unsigned int vertex_count
double * vertices
void extendWithTransformedBox(const Eigen::Affine3d &transform, const Eigen::Vector3d &box)
Extend with a box transformed by the given transform.
Definition: aabb.cpp:39
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
Eigen::Vector3d shape_extents_
The extents of shape (dimensions of axis aligned bounding box when shape is at origin).
Definition: link_model.h:263
bool joint_origin_transform_is_identity_
True of the joint origin transform is identity.
Definition: link_model.h:244
void setGeometry(const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Affine3d &origins)
Definition: link_model.cpp:74
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
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
Eigen::Affine3d joint_origin_transform_
The constant transform applied to the link (local)
Definition: link_model.h:247
EigenSTL::vector_Affine3d collision_origin_transform_
The constant transform applied to the collision geometry of the link (local)
Definition: link_model.h:250
void setParentJointModel(const JointModel *joint)
Definition: link_model.cpp:68
Main namespace for MoveIt!
Eigen::Vector3d computeShapeExtents(const ShapeMsg &shape_msg)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel(const std::string &name)
Definition: link_model.cpp:46
JointType getType() const
Get the type of joint.
Definition: joint_model.h:137
void setVisualMesh(const std::string &visual_mesh, const Eigen::Affine3d &origin, const Eigen::Vector3d &scale)
Definition: link_model.cpp:115
std::vector< shapes::ShapeConstPtr > shapes_
The collision geometry of the link.
Definition: link_model.h:260
Represents an axis-aligned bounding box.
Definition: aabb.h:47
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