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>
53 : transform_callback_(transform_callback), next_handle_(1), min_handle_(1)
62 void point_containment_filter::ShapeMask::freeMemory()
64 for (
const SeeShape& body : bodies_)
71 std::scoped_lock _(shapes_lock_);
72 transform_callback_ = transform_callback;
76 double scale,
double padding)
78 std::scoped_lock _(shapes_lock_);
80 ss.
body = bodies::createEmptyBodyFromShapeType(shape->type);
83 ss.
body->setDimensionsDirty(shape.get());
84 ss.
body->setScaleDirty(scale);
85 ss.
body->setPaddingDirty(padding);
86 ss.
body->updateInternalData();
89 std::pair<std::set<SeeShape, SortBodies>::iterator,
bool> insert_op = bodies_.insert(ss);
90 if (!insert_op.second)
92 RCLCPP_ERROR(
getLogger(),
"Internal error in management of bodies in ShapeMask. This is a serious error.");
94 used_handles_[next_handle_] = insert_op.first;
100 const std::size_t sz = min_handle_ + bodies_.size() + 1;
101 for (std::size_t i = min_handle_; i < sz; ++i)
103 if (used_handles_.find(i) == used_handles_.end())
109 min_handle_ = next_handle_;
116 std::scoped_lock _(shapes_lock_);
117 std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator>::iterator it = used_handles_.find(handle);
118 if (it != used_handles_.end())
120 delete it->second->body;
121 bodies_.erase(it->second);
122 used_handles_.erase(it);
123 min_handle_ = handle;
126 RCLCPP_ERROR(
getLogger(),
"Unable to remove shape handle %u", handle);
131 const double min_sensor_dist,
const double max_sensor_dist,
132 std::vector<int>& mask)
134 std::scoped_lock _(shapes_lock_);
135 const unsigned int np = data_in.data.size() / data_in.point_step;
140 std::fill(mask.begin(), mask.end(),
static_cast<int>(OUTSIDE));
144 Eigen::Isometry3d tmp;
145 bspheres_.resize(bodies_.size());
147 for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end(); ++it)
149 if (!transform_callback_(it->handle, tmp))
154 "Missing transform for shape with handle " << it->handle <<
" without a body");
159 "Missing transform for shape " << it->body->getType() <<
" with handle " << it->handle);
164 it->body->setPose(tmp);
165 it->body->computeBoundingSphere(bspheres_[j++]);
170 bodies::BoundingSphere bound;
171 bodies::mergeBoundingSpheres(bspheres_, bound);
172 const double radius_squared = bound.radius * bound.radius;
175 sensor_msgs::PointCloud2ConstIterator<float> iter_x(data_in,
"x");
176 sensor_msgs::PointCloud2ConstIterator<float> iter_y(data_in,
"y");
177 sensor_msgs::PointCloud2ConstIterator<float> iter_z(data_in,
"z");
182 for (
int i = 0; i < static_cast<int>(np); ++i)
185 double d = pt.norm();
187 if (d < min_sensor_dist || d > max_sensor_dist)
191 else if ((bound.center - pt).squaredNorm() < radius_squared)
193 for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it)
195 if (it->body->containsPoint(pt))
206 std::scoped_lock _(shapes_lock_);
209 for (std::set<SeeShape>::const_iterator it = bodies_.begin(); it != bodies_.end() && out == OUTSIDE; ++it)
211 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)
rclcpp::Logger getLogger()
Vec3fX< details::Vec3Data< double > > Vector3d
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.