heightmap.h
Go to the documentation of this file.
00001 /* -*- mode: C++ -*- */
00002 /*  Copyright (C) 2010 UT-Austin & Austin Robot Technology,
00003  *  David Claridge, Michael Quinlan
00004  * 
00005  *  License: Modified BSD Software License 
00006  */
00007 
00008 
00009 #ifndef _HEIGHT_MAP_H_
00010 #define _HEIGHT_MAP_H_
00011 
00012 #include <ros/ros.h>
00013 #include <pcl_ros/point_cloud.h>
00014 
00015 namespace velodyne_height_map {
00016 
00017 // shorter names for point cloud types in this namespace
00018 typedef pcl::PointXYZI VPoint;
00019 typedef pcl::PointCloud<VPoint> VPointCloud;
00020 
00021 class HeightMap
00022 {
00023 public:
00024 
00030   HeightMap(ros::NodeHandle node, ros::NodeHandle private_nh);
00031   ~HeightMap();
00032 
00039   void processData(const VPointCloud::ConstPtr &scan);
00040 
00041 private:
00042   void constructFullClouds(const VPointCloud::ConstPtr &scan, unsigned npoints,
00043                            size_t &obs_count, size_t &empty_count);
00044   void constructGridClouds(const VPointCloud::ConstPtr &scan, unsigned npoints,
00045                            size_t &obs_count, size_t &empty_count);
00046 
00047 
00048   // Parameters that define the grids and the height threshold
00049   // Can be set via the parameter server
00050   int grid_dim_;
00051   double m_per_cell_;
00052   double height_diff_threshold_;
00053   bool full_clouds_;
00054 
00055   // Point clouds generated in processData
00056   VPointCloud obstacle_cloud_;            
00057   VPointCloud clear_cloud_;            
00058 
00059   // ROS topics
00060   ros::Subscriber velodyne_scan_;
00061   ros::Publisher obstacle_publisher_;
00062   ros::Publisher clear_publisher_;
00063 };
00064 
00065 } // namespace velodyne_height_map
00066 
00067 #endif


velodyne_height_map
Author(s): David Claridge, Michael Quinlan
autogenerated on Thu Jun 6 2019 18:03:08