Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MOVEIT_POINT_CONTAINMENT_FILTER_SELF_MASK_
00038 #define MOVEIT_POINT_CONTAINMENT_FILTER_SELF_MASK_
00039
00040 #include <sensor_msgs/PointCloud2.h>
00041 #include <geometric_shapes/bodies.h>
00042 #include <boost/function.hpp>
00043 #include <string>
00044 #include <vector>
00045 #include <set>
00046 #include <map>
00047
00048 #include <boost/thread/mutex.hpp>
00049
00050 namespace point_containment_filter
00051 {
00052 typedef unsigned int ShapeHandle;
00053
00055 class ShapeMask
00056 {
00057 public:
00059 enum
00060 {
00061 INSIDE = 0,
00062 OUTSIDE = 1,
00063 CLIP = 2
00064 };
00065
00066 typedef boost::function<bool(ShapeHandle, Eigen::Affine3d&)> TransformCallback;
00067
00069 ShapeMask(const TransformCallback& transform_callback = TransformCallback());
00070
00072 ~ShapeMask();
00073
00074 ShapeHandle addShape(const shapes::ShapeConstPtr& shape, double scale = 1.0, double padding = 0.0);
00075 void removeShape(ShapeHandle handle);
00076
00077 void setTransformCallback(const TransformCallback& transform_callback);
00078
00083 void maskContainment(const sensor_msgs::PointCloud2& data_in, const Eigen::Vector3d& sensor_pos,
00084 const double min_sensor_dist, const double max_sensor_dist, std::vector<int>& mask);
00085
00088 int getMaskContainment(double x, double y, double z) const;
00089
00092 int getMaskContainment(const Eigen::Vector3d& pt) const;
00093
00094 private:
00095 struct SeeShape
00096 {
00097 SeeShape()
00098 {
00099 body = NULL;
00100 }
00101
00102 bodies::Body* body;
00103 ShapeHandle handle;
00104 double volume;
00105 };
00106
00107 struct SortBodies
00108 {
00109 bool operator()(const SeeShape& b1, const SeeShape& b2)
00110 {
00111 if (b1.volume > b2.volume)
00112 return true;
00113 if (b1.volume < b2.volume)
00114 return false;
00115 return b1.handle < b2.handle;
00116 }
00117 };
00118
00120 void freeMemory();
00121
00122 TransformCallback transform_callback_;
00123 ShapeHandle next_handle_;
00124 ShapeHandle min_handle_;
00125
00126 mutable boost::mutex shapes_lock_;
00127 std::set<SeeShape, SortBodies> bodies_;
00128 std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator> used_handles_;
00129 std::vector<bodies::BoundingSphere> bspheres_;
00130 };
00131 }
00132
00133 #endif