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>
43 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.perception.shape_mask");
46 : transform_callback_(transform_callback), next_handle_(1), min_handle_(1)
55 void point_containment_filter::ShapeMask::freeMemory()
57 for (
const SeeShape& body : bodies_)
64 std::scoped_lock _(shapes_lock_);
65 transform_callback_ = transform_callback;
69 double scale,
double padding)
71 std::scoped_lock _(shapes_lock_);
73 ss.
body = bodies::createEmptyBodyFromShapeType(shape->type);
76 ss.
body->setDimensionsDirty(shape.get());
77 ss.
body->setScaleDirty(scale);
78 ss.
body->setPaddingDirty(padding);
79 ss.
body->updateInternalData();
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;
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())
98 min_handle_ = next_handle_;
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())
109 delete it->second->body;
110 bodies_.erase(it->second);
111 used_handles_.erase(it);
112 min_handle_ = handle;
115 RCLCPP_ERROR(LOGGER,
"Unable to remove shape handle %u", handle);
120 const double min_sensor_dist,
const double max_sensor_dist,
121 std::vector<int>& mask)
123 std::scoped_lock _(shapes_lock_);
124 const unsigned int np = data_in.data.size() / data_in.point_step;
128 std::fill(mask.begin(), mask.end(),
static_cast<int>(OUTSIDE));
131 Eigen::Isometry3d tmp;
132 bspheres_.resize(bodies_.size());
134 for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end(); ++it)
136 if (!transform_callback_(it->handle, tmp))
139 RCLCPP_ERROR_STREAM(LOGGER,
"Missing transform for shape with handle " << it->handle <<
" without a body");
141 RCLCPP_ERROR_STREAM(LOGGER,
142 "Missing transform for shape " << it->body->getType() <<
" with handle " << it->handle);
146 it->body->setPose(tmp);
147 it->body->computeBoundingSphere(bspheres_[j++]);
152 bodies::BoundingSphere bound;
153 bodies::mergeBoundingSpheres(bspheres_, bound);
154 const double radius_squared = bound.radius * bound.radius;
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");
164 for (
int i = 0; i < static_cast<int>(np); ++i)
167 double d = pt.norm();
169 if (d < min_sensor_dist || d > max_sensor_dist)
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))
182 std::scoped_lock _(shapes_lock_);
185 for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it)
186 if (it->body->containsPoint(pt))
ShapeHandle addShape(const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
std::function< bool(ShapeHandle, Eigen::Isometry3d &)> TransformCallback
void removeShape(ShapeHandle handle)
ShapeMask(const TransformCallback &transform_callback=TransformCallback())
Construct the filter.
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,...
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...
virtual ~ShapeMask()
Destructor to clean up.
void setTransformCallback(const TransformCallback &transform_callback)
Vec3fX< details::Vec3Data< double > > Vector3d
const rclcpp::Logger LOGGER