moveit2
The MoveIt Motion Planning Framework for ROS 2.
shape_mask.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 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/body_operations.h>
39 #include <sensor_msgs/point_cloud2_iterator.hpp>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 
43 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.perception.shape_mask");
44 
46  : transform_callback_(transform_callback), next_handle_(1), min_handle_(1)
47 {
48 }
49 
51 {
52  freeMemory();
53 }
54 
55 void point_containment_filter::ShapeMask::freeMemory()
56 {
57  for (const SeeShape& body : bodies_)
58  delete body.body;
59  bodies_.clear();
60 }
61 
63 {
64  std::scoped_lock _(shapes_lock_);
65  transform_callback_ = transform_callback;
66 }
67 
69  double scale, double padding)
70 {
71  std::scoped_lock _(shapes_lock_);
72  SeeShape ss;
73  ss.body = bodies::createEmptyBodyFromShapeType(shape->type);
74  if (ss.body)
75  {
76  ss.body->setDimensionsDirty(shape.get());
77  ss.body->setScaleDirty(scale);
78  ss.body->setPaddingDirty(padding);
79  ss.body->updateInternalData();
80  ss.volume = ss.body->computeVolume();
81  ss.handle = next_handle_;
82  std::pair<std::set<SeeShape, SortBodies>::iterator, bool> insert_op = bodies_.insert(ss);
83  if (!insert_op.second)
84  RCLCPP_ERROR(LOGGER, "Internal error in management of bodies in ShapeMask. This is a serious error.");
85  used_handles_[next_handle_] = insert_op.first;
86  }
87  else
88  return 0;
89 
90  ShapeHandle ret = next_handle_;
91  const std::size_t sz = min_handle_ + bodies_.size() + 1;
92  for (std::size_t i = min_handle_; i < sz; ++i)
93  if (used_handles_.find(i) == used_handles_.end())
94  {
95  next_handle_ = i;
96  break;
97  }
98  min_handle_ = next_handle_;
99 
100  return ret;
101 }
102 
104 {
105  std::scoped_lock _(shapes_lock_);
106  std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator>::iterator it = used_handles_.find(handle);
107  if (it != used_handles_.end())
108  {
109  delete it->second->body;
110  bodies_.erase(it->second);
111  used_handles_.erase(it);
112  min_handle_ = handle;
113  }
114  else
115  RCLCPP_ERROR(LOGGER, "Unable to remove shape handle %u", handle);
116 }
117 
118 void point_containment_filter::ShapeMask::maskContainment(const sensor_msgs::msg::PointCloud2& data_in,
119  const Eigen::Vector3d& /*sensor_origin*/,
120  const double min_sensor_dist, const double max_sensor_dist,
121  std::vector<int>& mask)
122 {
123  std::scoped_lock _(shapes_lock_);
124  const unsigned int np = data_in.data.size() / data_in.point_step;
125  mask.resize(np);
126 
127  if (bodies_.empty())
128  std::fill(mask.begin(), mask.end(), static_cast<int>(OUTSIDE));
129  else
130  {
131  Eigen::Isometry3d tmp;
132  bspheres_.resize(bodies_.size());
133  std::size_t j = 0;
134  for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end(); ++it)
135  {
136  if (!transform_callback_(it->handle, tmp))
137  {
138  if (!it->body)
139  RCLCPP_ERROR_STREAM(LOGGER, "Missing transform for shape with handle " << it->handle << " without a body");
140  else
141  RCLCPP_ERROR_STREAM(LOGGER,
142  "Missing transform for shape " << it->body->getType() << " with handle " << it->handle);
143  }
144  else
145  {
146  it->body->setPose(tmp);
147  it->body->computeBoundingSphere(bspheres_[j++]);
148  }
149  }
150 
151  // compute a sphere that bounds the entire robot
152  bodies::BoundingSphere bound;
153  bodies::mergeBoundingSpheres(bspheres_, bound);
154  const double radius_squared = bound.radius * bound.radius;
155 
156  // we now decide which points we keep
157  sensor_msgs::PointCloud2ConstIterator<float> iter_x(data_in, "x");
158  sensor_msgs::PointCloud2ConstIterator<float> iter_y(data_in, "y");
159  sensor_msgs::PointCloud2ConstIterator<float> iter_z(data_in, "z");
160 
161  // Cloud iterators are not incremented in the for loop, because of the pragma
162  // Comment out below parallelization as it can result in very high CPU consumption
163  //#pragma omp parallel for schedule(dynamic)
164  for (int i = 0; i < static_cast<int>(np); ++i)
165  {
166  Eigen::Vector3d pt = Eigen::Vector3d(*(iter_x + i), *(iter_y + i), *(iter_z + i));
167  double d = pt.norm();
168  int out = OUTSIDE;
169  if (d < min_sensor_dist || d > max_sensor_dist)
170  out = CLIP;
171  else if ((bound.center - pt).squaredNorm() < radius_squared)
172  for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it)
173  if (it->body->containsPoint(pt))
174  out = INSIDE;
175  mask[i] = out;
176  }
177  }
178 }
179 
181 {
182  std::scoped_lock _(shapes_lock_);
183 
184  int out = OUTSIDE;
185  for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it)
186  if (it->body->containsPoint(pt))
187  out = INSIDE;
188  return out;
189 }
190 
192 {
193  return getMaskContainment(Eigen::Vector3d(x, y, z));
194 }
ShapeHandle addShape(const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
Definition: shape_mask.cpp:68
std::function< bool(ShapeHandle, Eigen::Isometry3d &)> TransformCallback
Definition: shape_mask.h:63
void removeShape(ShapeHandle handle)
Definition: shape_mask.cpp:103
ShapeMask(const TransformCallback &transform_callback=TransformCallback())
Construct the filter.
Definition: shape_mask.cpp:45
void maskContainment(const sensor_msgs::msg::PointCloud2 &data_in, const Eigen::Vector3d &sensor_pos, const double min_sensor_dist, const double max_sensor_dist, std::vector< int > &mask)
Compute the containment mask (INSIDE or OUTSIDE) for a given pointcloud. If a mask element is INSIDE,...
Definition: shape_mask.cpp:118
int getMaskContainment(double x, double y, double z) const
Get the containment mask (INSIDE or OUTSIDE) value for an individual point. It is assumed the point i...
Definition: shape_mask.cpp:191
virtual ~ShapeMask()
Destructor to clean up.
Definition: shape_mask.cpp:50
void setTransformCallback(const TransformCallback &transform_callback)
Definition: shape_mask.cpp:62
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
x
Definition: pick.py:64
y
Definition: pick.py:65
z
Definition: pick.py:66
unsigned int ShapeHandle
Definition: shape_mask.h:49
d
Definition: setup.py:4
const rclcpp::Logger LOGGER
Definition: async_test.h:31