36 #ifndef JSK_RECOGNITION_UTILS_GEO_GRID_PLANE_H_ 37 #define JSK_RECOGNITION_UTILS_GEO_GRID_PLANE_H_ 39 #include <Eigen/Geometry> 40 #include <pcl/point_cloud.h> 41 #include <pcl/PointIndices.h> 42 #include <pcl/point_types.h> 43 #include <boost/tuple/tuple.hpp> 50 #include <jsk_recognition_msgs/SimpleOccupancyGrid.h> 83 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
84 double distance_threshold);
86 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
87 double distance_threshold,
88 std::set<int>& non_plane_indices);
90 pcl::PointCloud<pcl::PointNormal>::Ptr& cloud,
91 double distance_threshold,
92 double normal_threshold,
93 std::set<int>& non_plane_indices);
96 virtual jsk_recognition_msgs::SimpleOccupancyGrid
toROSMsg();
103 const jsk_recognition_msgs::SimpleOccupancyGrid& rosmsg,
104 const Eigen::Affine3f& offset);
105 virtual bool isOccupied(
const IndexPair& pair);
GridPlane(ConvexPolygon::Ptr plane, const double resolution)
virtual IndexPair projectLocalPointAsIndexPair(const Eigen::Vector3f &p)
Project 3-D point to GridPlane::IndexPair. p should be represented in local coordinates.
boost::shared_ptr< GridPlane > Ptr
virtual GridPlane::Ptr erode(int num)
Erode grid cells with specified number of pixels.
virtual Eigen::Vector3f unprojectIndexPairAsLocalPoint(const IndexPair &pair)
Unproject GridPlane::IndexPair to 3-D local point.
virtual size_t fillCellsFromPointCloud(pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, double distance_threshold)
virtual GridPlane::Ptr clone()
virtual Eigen::Vector3f unprojectIndexPairAsGlobalPoint(const IndexPair &pair)
Unproject GridPlane::IndexPair to 3-D global point.
std::set< IndexPair > IndexPairSet
virtual bool isOccupied(const IndexPair &pair)
virtual ConvexPolygon::Ptr getPolygon()
return ConvexPolygon pointer of this instance.
Grid based representation of planar region.
virtual double getResolution()
virtual bool isOccupiedGlobal(const Eigen::Vector3f &p)
p should be global coordinate
static GridPlane fromROSMsg(const jsk_recognition_msgs::SimpleOccupancyGrid &rosmsg, const Eigen::Affine3f &offset)
Construct GridPlane object from jsk_recognition_msgs::SimpleOccupancyGrid.
virtual void fillCellsFromCube(Cube &cube)
ConvexPolygon::Ptr convex_
virtual void addIndexPair(IndexPair pair)
Add IndexPair to this instance.
virtual jsk_recognition_msgs::SimpleOccupancyGrid toROSMsg()
boost::tuple< int, int > IndexPair
virtual GridPlane::Ptr dilate(int num)
Dilate grid cells with specified number of pixels.