attached_body.cpp
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 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 
40 #include <boost/algorithm/string/predicate.hpp>
41 
42 namespace moveit
43 {
44 namespace core
45 {
46 AttachedBody::AttachedBody(const LinkModel* parent, const std::string& id, const Eigen::Isometry3d& pose,
47  const std::vector<shapes::ShapeConstPtr>& shapes,
48  const EigenSTL::vector_Isometry3d& shape_poses, const std::set<std::string>& touch_links,
49  const trajectory_msgs::JointTrajectory& detach_posture,
50  const FixedTransformsMap& subframe_poses)
51  : parent_link_model_(parent)
52  , id_(id)
53  , pose_(pose)
54  , shapes_(shapes)
55  , shape_poses_(shape_poses)
56  , touch_links_(touch_links)
57  , detach_posture_(detach_posture)
58  , subframe_poses_(subframe_poses)
59  , global_subframe_poses_(subframe_poses)
60 {
61  ASSERT_ISOMETRY(pose) // unsanitized input, could contain a non-isometry
62  for (const auto& t : shape_poses_)
63  {
64  ASSERT_ISOMETRY(t) // unsanitized input, could contain a non-isometry
65  }
66  for (const auto& t : subframe_poses_)
67  {
68  ASSERT_ISOMETRY(t.second) // unsanitized input, could contain a non-isometry
69  }
70 
71  // Global poses are initialized to identity to allow efficient Isometry calculations
72  global_pose_.setIdentity();
73  global_collision_body_transforms_.resize(shape_poses.size());
74  for (Eigen::Isometry3d& global_collision_body_transform : global_collision_body_transforms_)
75  global_collision_body_transform.setIdentity();
76 
77  shape_poses_in_link_frame_.clear();
78  shape_poses_in_link_frame_.reserve(shape_poses_.size());
79  for (const auto& shape_pose : shape_poses_)
80  {
81  shape_poses_in_link_frame_.push_back(pose_ * shape_pose);
82  }
83 }
84 
85 AttachedBody::~AttachedBody() = default;
86 
87 void AttachedBody::setScale(double scale)
88 {
89  for (shapes::ShapeConstPtr& shape : shapes_)
90  {
91  // if this shape is only owned here (and because this is a non-const function), we can safely const-cast:
92  if (shape.unique())
93  const_cast<shapes::Shape*>(shape.get())->scale(scale);
94  else
95  {
96  // if the shape is owned elsewhere, we make a copy:
97  shapes::Shape* copy = shape->clone();
98  copy->scale(scale);
99  shape.reset(copy);
100  }
101  }
102 }
103 
104 void AttachedBody::computeTransform(const Eigen::Isometry3d& parent_link_global_transform)
105 {
106  ASSERT_ISOMETRY(parent_link_global_transform) // unsanitized input, could contain a non-isometry
107  global_pose_ = parent_link_global_transform * pose_;
108 
109  // update collision body transforms
110  for (std::size_t i = 0; i < global_collision_body_transforms_.size(); ++i)
111  global_collision_body_transforms_[i] = global_pose_ * shape_poses_[i]; // valid isometry
112 
113  // update subframe transforms
114  for (auto global = global_subframe_poses_.begin(), end = global_subframe_poses_.end(), local = subframe_poses_.begin();
115  global != end; ++global, ++local)
116  global->second = global_pose_ * local->second; // valid isometry
117 }
118 
119 void AttachedBody::setPadding(double padding)
120 {
121  for (shapes::ShapeConstPtr& shape : shapes_)
122  {
123  // if this shape is only owned here (and because this is a non-const function), we can safely const-cast:
124  if (shape.unique())
125  const_cast<shapes::Shape*>(shape.get())->padd(padding);
126  else
127  {
128  // if the shape is owned elsewhere, we make a copy:
129  shapes::Shape* copy = shape->clone();
130  copy->padd(padding);
131  shape.reset(copy);
132  }
133  }
134 }
135 
136 const Eigen::Isometry3d& AttachedBody::getSubframeTransform(const std::string& frame_name, bool* found) const
137 {
138  if (boost::starts_with(frame_name, id_) && frame_name[id_.length()] == '/')
139  {
140  auto it = subframe_poses_.find(frame_name.substr(id_.length() + 1));
141  if (it != subframe_poses_.end())
142  {
143  if (found)
144  *found = true;
145  return it->second;
146  }
147  }
148  static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
149  if (found)
150  *found = false;
151  return IDENTITY_TRANSFORM;
152 }
153 
154 const Eigen::Isometry3d& AttachedBody::getGlobalSubframeTransform(const std::string& frame_name, bool* found) const
155 {
156  if (boost::starts_with(frame_name, id_) && frame_name[id_.length()] == '/')
157  {
158  auto it = global_subframe_poses_.find(frame_name.substr(id_.length() + 1));
159  if (it != global_subframe_poses_.end())
160  {
161  if (found)
162  *found = true;
163  return it->second;
164  }
165  }
166  static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
167  if (found)
168  *found = false;
169  return IDENTITY_TRANSFORM;
170 }
171 
172 bool AttachedBody::hasSubframeTransform(const std::string& frame_name) const
173 {
174  bool found;
175  getSubframeTransform(frame_name, &found);
176  return found;
177 }
178 
179 } // namespace core
180 } // namespace moveit
moveit::core::AttachedBody::computeTransform
void computeTransform(const Eigen::Isometry3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link.
Definition: attached_body.cpp:168
shapes
EigenSTL::vector_Isometry3d
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
moveit::core::AttachedBody::getGlobalSubframeTransform
const Eigen::Isometry3d & getGlobalSubframeTransform(const std::string &frame_name, bool *found=nullptr) const
Get the fixed transform to a named subframe on this body, relative to the world frame....
Definition: attached_body.cpp:218
check_isometry.h
moveit::core::AttachedBody::AttachedBody
AttachedBody(const LinkModel *parent, const std::string &id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses, const std::set< std::string > &touch_links, const trajectory_msgs::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Construct an attached body for a specified link.
Definition: attached_body.cpp:110
moveit::core::AttachedBody::~AttachedBody
~AttachedBody()
attached_body.h
moveit::core::AttachedBody::subframe_poses_
moveit::core::FixedTransformsMap subframe_poses_
Transforms to subframes on the object, relative to the object's pose.
Definition: attached_body.h:303
shapes::Shape::scale
void scale(double scale)
shapes::Shape
moveit::core::AttachedBody::global_subframe_poses_
moveit::core::FixedTransformsMap global_subframe_poses_
Transforms to subframes on the object, relative to the model frame.
Definition: attached_body.h:306
shapes::Shape::padd
void padd(double padding)
moveit::core::AttachedBody::setScale
void setScale(double scale)
Set the scale for the shapes of this attached object.
Definition: attached_body.cpp:151
moveit::core::AttachedBody::id_
std::string id_
string id for reference
Definition: attached_body.h:275
moveit::core::AttachedBody::setPadding
void setPadding(double padding)
Set the padding for the shapes of this attached object.
Definition: attached_body.cpp:183
moveit::core::AttachedBody::shape_poses_
EigenSTL::vector_Isometry3d shape_poses_
The transforms from the object's pose to the object's geometries.
Definition: attached_body.h:287
moveit::core::AttachedBody::hasSubframeTransform
bool hasSubframeTransform(const std::string &frame_name) const
Check whether a subframe of given.
Definition: attached_body.cpp:236
ASSERT_ISOMETRY
#define ASSERT_ISOMETRY(transform)
shapes.h
moveit::core::FixedTransformsMap
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.h:117
moveit::core::AttachedBody::getSubframeTransform
const Eigen::Isometry3d & getSubframeTransform(const std::string &frame_name, bool *found=nullptr) const
Get the fixed transform to a named subframe on this body (relative to the body's pose)
Definition: attached_body.cpp:200
pose_
const geometry_msgs::Pose * pose_
Definition: planning_scene.cpp:799
moveit
Main namespace for MoveIt.
Definition: background_processing.h:46
moveit::core::AttachedBody::pose_
Eigen::Isometry3d pose_
The transform from the parent link to the attached body's pose.
Definition: attached_body.h:278
moveit::core::AttachedBody::global_collision_body_transforms_
EigenSTL::vector_Isometry3d global_collision_body_transforms_
The global transforms for the attached bodies (computed by forward kinematics)
Definition: attached_body.h:293
shapes::Shape::clone
virtual Shape * clone() const=0
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
moveit::core::AttachedBody::shapes_
std::vector< shapes::ShapeConstPtr > shapes_
The geometries of the attached body.
Definition: attached_body.h:284
t
geometry_msgs::TransformStamped t
moveit::core::AttachedBody::global_pose_
Eigen::Isometry3d global_pose_
The transform from the model frame to the attached body's pose
Definition: attached_body.h:281


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:35