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 
42 
43 namespace moveit
44 {
45 namespace core
46 {
47 LinkModel::LinkModel(const std::string& name)
48  : name_(name)
49  , parent_joint_model_(nullptr)
50  , parent_link_model_(nullptr)
51  , is_parent_joint_fixed_(false)
52  , joint_origin_transform_is_identity_(true)
53  , first_collision_body_transform_index_(-1)
54  , link_index_(-1)
55 {
56  joint_origin_transform_.setIdentity();
57 }
58 
59 LinkModel::~LinkModel() = default;
60 
61 void LinkModel::setJointOriginTransform(const Eigen::Isometry3d& transform)
62 {
63  ASSERT_ISOMETRY(transform) // unsanitized input, could contain a non-isometry
64  joint_origin_transform_ = transform;
65  joint_origin_transform_is_identity_ =
66  joint_origin_transform_.linear().isIdentity() &&
67  joint_origin_transform_.translation().norm() < std::numeric_limits<double>::epsilon();
68 }
69 
70 void LinkModel::setParentJointModel(const JointModel* joint)
71 {
72  parent_joint_model_ = joint;
73  is_parent_joint_fixed_ = joint->getType() == JointModel::FIXED;
74 }
75 
76 void LinkModel::setGeometry(const std::vector<shapes::ShapeConstPtr>& shapes, const EigenSTL::vector_Isometry3d& origins)
77 {
78  shapes_ = shapes;
79  collision_origin_transform_ = origins;
80  collision_origin_transform_is_identity_.resize(collision_origin_transform_.size());
81 
82  core::AABB aabb;
83 
84  for (std::size_t i = 0; i < shapes_.size(); ++i)
85  {
86  ASSERT_ISOMETRY(collision_origin_transform_[i]) // unsanitized input, could contain a non-isometry
87  collision_origin_transform_is_identity_[i] =
88  (collision_origin_transform_[i].linear().isIdentity() &&
89  collision_origin_transform_[i].translation().norm() < std::numeric_limits<double>::epsilon()) ?
90  1 :
91  0;
92  Eigen::Isometry3d transform = collision_origin_transform_[i];
93 
94  if (shapes_[i]->type != shapes::MESH)
95  {
97  aabb.extendWithTransformedBox(transform, extents);
98  }
99  else
100  {
101  // we cannot use shapes::computeShapeExtents() for meshes, since that method does not provide information about
102  // the offset of the mesh origin
103  const shapes::Mesh* mesh = dynamic_cast<const shapes::Mesh*>(shapes_[i].get());
104  for (unsigned int j = 0; j < mesh->vertex_count; ++j)
105  {
106  aabb.extend(transform * Eigen::Map<Eigen::Vector3d>(&mesh->vertices[3 * j]));
107  }
108  }
109  }
110 
111  centered_bounding_box_offset_ = aabb.center();
112  if (shapes_.empty())
113  shape_extents_.setZero();
114  else
115  shape_extents_ = aabb.sizes();
116 }
117 
118 void LinkModel::setVisualMesh(const std::string& visual_mesh, const Eigen::Isometry3d& origin,
119  const Eigen::Vector3d& scale)
120 {
121  visual_mesh_filename_ = visual_mesh;
122  visual_mesh_origin_ = origin;
123  visual_mesh_scale_ = scale;
124 }
125 
126 } // end of namespace core
127 } // end of namespace moveit
shapes
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
check_isometry.h
shape_operations.h
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
shapes::Mesh
get
def get(url)
moveit::core::LinkModel::LinkModel
EIGEN_MAKE_ALIGNED_OPERATOR_NEW LinkModel(const std::string &name)
Definition: link_model.cpp:111
shapes::MESH
MESH
name
std::string name
shapes::Mesh::vertex_count
unsigned int vertex_count
ASSERT_ISOMETRY
#define ASSERT_ISOMETRY(transform)
shapes::Mesh::vertices
double * vertices
aabb.h
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
joint_model.h
shapes::computeShapeExtents
Eigen::Vector3d computeShapeExtents(const Shape *shape)
aabb
SaPCollisionManager< S >::SaPAABB * aabb
extents
std::array< S, 6 > & extents()
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89


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