moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
38#include <geometric_shapes/check_isometry.h>
39#include <geometric_shapes/shapes.h>
40
41namespace moveit
42{
43namespace core
44{
45AttachedBody::AttachedBody(const LinkModel* parent, const std::string& id, const Eigen::Isometry3d& pose,
46 const std::vector<shapes::ShapeConstPtr>& shapes,
47 const EigenSTL::vector_Isometry3d& shape_poses, const std::set<std::string>& touch_links,
48 const trajectory_msgs::msg::JointTrajectory& detach_posture,
49 const FixedTransformsMap& subframe_poses)
50 : parent_link_model_(parent)
51 , id_(id)
52 , pose_(pose)
53 , shapes_(shapes)
54 , shape_poses_(shape_poses)
55 , touch_links_(touch_links)
56 , detach_posture_(detach_posture)
57 , subframe_poses_(subframe_poses)
58 , global_subframe_poses_(subframe_poses)
59{
60 ASSERT_ISOMETRY(pose) // unsanitized input, could contain a non-isometry
61 for (const auto& t : shape_poses_)
62 {
63 ASSERT_ISOMETRY(t) // unsanitized input, could contain a non-isometry
64 }
65 for (const auto& t : subframe_poses_)
66 {
67 ASSERT_ISOMETRY(t.second) // unsanitized input, could contain a non-isometry
68 }
69
70 // Global poses are initialized to identity to allow efficient Isometry calculations
71 global_pose_.setIdentity();
72 global_collision_body_transforms_.resize(shape_poses.size());
73 for (Eigen::Isometry3d& global_collision_body_transform : global_collision_body_transforms_)
74 global_collision_body_transform.setIdentity();
75
76 shape_poses_in_link_frame_.clear();
77 shape_poses_in_link_frame_.reserve(shape_poses_.size());
78 for (const auto& shape_pose : shape_poses_)
79 {
80 shape_poses_in_link_frame_.push_back(pose_ * shape_pose);
81 }
82}
83
85
86void AttachedBody::setScale(double scale)
87{
88 for (shapes::ShapeConstPtr& shape : shapes_)
89 {
90 // if this shape is only owned here (and because this is a non-const function), we can safely const-cast:
91 if (shape.unique())
92 {
93 const_cast<shapes::Shape*>(shape.get())->scale(scale);
94 }
95 else
96 {
97 // if the shape is owned elsewhere, we make a copy:
98 shapes::Shape* copy = shape->clone();
99 copy->scale(scale);
100 shape.reset(copy);
101 }
102 }
103}
104
105void AttachedBody::computeTransform(const Eigen::Isometry3d& parent_link_global_transform)
106{
107 ASSERT_ISOMETRY(parent_link_global_transform) // unsanitized input, could contain a non-isometry
108 global_pose_ = parent_link_global_transform * pose_;
109
110 // update collision body transforms
111 for (std::size_t i = 0; i < global_collision_body_transforms_.size(); ++i)
112 global_collision_body_transforms_[i] = global_pose_ * shape_poses_[i]; // valid isometry
113
114 // update subframe transforms
115 for (auto global = global_subframe_poses_.begin(), end = global_subframe_poses_.end(), local = subframe_poses_.begin();
116 global != end; ++global, ++local)
117 global->second = global_pose_ * local->second; // valid isometry
118}
119
120void AttachedBody::setPadding(double padding)
121{
122 for (shapes::ShapeConstPtr& shape : shapes_)
123 {
124 // if this shape is only owned here (and because this is a non-const function), we can safely const-cast:
125 if (shape.unique())
126 {
127 const_cast<shapes::Shape*>(shape.get())->padd(padding);
128 }
129 else
130 {
131 // if the shape is owned elsewhere, we make a copy:
132 shapes::Shape* copy = shape->clone();
133 copy->padd(padding);
134 shape.reset(copy);
135 }
136 }
137}
138
139const Eigen::Isometry3d& AttachedBody::getSubframeTransform(const std::string& frame_name, bool* found) const
140{
141 if (frame_name.rfind(id_, 0) == 0 && frame_name[id_.length()] == '/')
142 {
143 auto it = subframe_poses_.find(frame_name.substr(id_.length() + 1));
144 if (it != subframe_poses_.end())
145 {
146 if (found)
147 *found = true;
148 return it->second;
149 }
150 }
151 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
152 if (found)
153 *found = false;
154 return IDENTITY_TRANSFORM;
155}
156
157const Eigen::Isometry3d& AttachedBody::getGlobalSubframeTransform(const std::string& frame_name, bool* found) const
158{
159 if (frame_name.rfind(id_, 0) == 0 && frame_name[id_.length()] == '/')
160 {
161 auto it = global_subframe_poses_.find(frame_name.substr(id_.length() + 1));
162 if (it != global_subframe_poses_.end())
163 {
164 if (found)
165 *found = true;
166 return it->second;
167 }
168 }
169 static const Eigen::Isometry3d IDENTITY_TRANSFORM = Eigen::Isometry3d::Identity();
170 if (found)
171 *found = false;
172 return IDENTITY_TRANSFORM;
173}
174
175bool AttachedBody::hasSubframeTransform(const std::string& frame_name) const
176{
177 bool found;
178 getSubframeTransform(frame_name, &found);
179 return found;
180}
181
182} // namespace core
183} // namespace moveit
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)
void setPadding(double padding)
Set the padding for the shapes of this attached object.
bool hasSubframeTransform(const std::string &frame_name) const
Check whether a subframe of given @frame_name is present in this object.
void computeTransform(const Eigen::Isometry3d &parent_link_global_transform)
Recompute global_collision_body_transform given the transform of the parent link.
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::msg::JointTrajectory &detach_posture, const moveit::core::FixedTransformsMap &subframe_poses=moveit::core::FixedTransformsMap())
Construct an attached body for a specified link.
void setScale(double scale)
Set the scale for the shapes of this attached object.
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....
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition link_model.h:72
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:53
Main namespace for MoveIt.
Definition exceptions.h:43
Definition world.h:49