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 #ifndef MOVEIT_POINT_CONTAINMENT_FILTER_SELF_MASK_
00033 #define MOVEIT_POINT_CONTAINMENT_FILTER_SELF_MASK_
00034
00035 #include <sensor_msgs/PointCloud.h>
00036 #include <geometric_shapes/bodies.h>
00037 #include <boost/function.hpp>
00038 #include <string>
00039 #include <vector>
00040 #include <set>
00041 #include <map>
00042
00043 #include <boost/thread/mutex.hpp>
00044 #include <pcl/point_cloud.h>
00045 #include <pcl/point_types.h>
00046
00047 namespace point_containment_filter
00048 {
00049
00050 typedef unsigned int ShapeHandle;
00051
00053 class ShapeMask
00054 {
00055
00056 public:
00057
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
00082 void maskContainment(const pcl::PointCloud<pcl::PointXYZ>& data_in, const Eigen::Vector3d &sensor_pos,
00083 const double min_sensor_dist, const double max_sensor_dist, std::vector<int> &mask);
00084
00087 int getMaskContainment(double x, double y, double z) const;
00088
00089
00092 int getMaskContainment(const Eigen::Vector3d &pt) const;
00093
00094 private:
00095
00096 struct SeeShape
00097 {
00098 SeeShape()
00099 {
00100 body = NULL;
00101 }
00102
00103 bodies::Body *body;
00104 ShapeHandle handle;
00105 double volume;
00106 };
00107
00108 struct SortBodies
00109 {
00110 bool operator()(const SeeShape &b1, const SeeShape &b2)
00111 {
00112 if (b1.volume > b2.volume)
00113 return true;
00114 if (b1.volume < b2.volume)
00115 return false;
00116 return b1.handle < b2.handle;
00117 }
00118 };
00119
00121 void freeMemory();
00122
00123 TransformCallback transform_callback_;
00124 ShapeHandle next_handle_;
00125 ShapeHandle min_handle_;
00126
00127 mutable boost::mutex shapes_lock_;
00128 std::set<SeeShape, SortBodies> bodies_;
00129 std::map<ShapeHandle, std::set<SeeShape, SortBodies>::iterator> used_handles_;
00130 std::vector<bodies::BoundingSphere> bspheres_;
00131 };
00132
00133 }
00134
00135 #endif