39#include <sensor_msgs/msg/point_cloud2.hpp>
40#include <geometric_shapes/bodies.h>
71 ShapeHandle addShape(
const shapes::ShapeConstPtr& shape,
double scale = 1.0,
double padding = 0.0);
80 void maskContainment(
const sensor_msgs::msg::PointCloud2& data_in,
const Eigen::Vector3d& sensor_pos,
81 const double min_sensor_dist,
const double max_sensor_dist, std::vector<int>& mask);
129 std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator> used_handles_;
Computing a mask for a pointcloud that states which points are inside the robot.
ShapeHandle addShape(const shapes::ShapeConstPtr &shape, double scale=1.0, double padding=0.0)
std::mutex shapes_lock_
Protects, bodies_ and bspheres_. All public methods acquire this mutex for their whole duration.
std::vector< bodies::BoundingSphere > bspheres_
std::set< SeeShape, SortBodies > bodies_
std::function< bool(ShapeHandle, Eigen::Isometry3d &)> TransformCallback
TransformCallback transform_callback_
void removeShape(ShapeHandle handle)
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)
bool operator()(const SeeShape &b1, const SeeShape &b2) const