#include <heightmap.h>
Public Member Functions | |
HeightMap (ros::NodeHandle node, ros::NodeHandle private_nh) | |
void | processData (const VPointCloud::ConstPtr &scan) |
~HeightMap () | |
Private Member Functions | |
void | constructFullClouds (const VPointCloud::ConstPtr &scan, unsigned npoints, size_t &obs_count, size_t &empty_count) |
void | constructGridClouds (const VPointCloud::ConstPtr &scan, unsigned npoints, size_t &obs_count, size_t &empty_count) |
Private Attributes | |
VPointCloud | clear_cloud_ |
ros::Publisher | clear_publisher_ |
bool | full_clouds_ |
int | grid_dim_ |
double | height_diff_threshold_ |
double | m_per_cell_ |
VPointCloud | obstacle_cloud_ |
ros::Publisher | obstacle_publisher_ |
ros::Subscriber | velodyne_scan_ |
Definition at line 21 of file heightmap.h.
velodyne_height_map::HeightMap::HeightMap | ( | ros::NodeHandle | node, |
ros::NodeHandle | private_nh | ||
) |
Constructor
node | NodeHandle of this instance |
private_nh | private NodeHandle of this instance |
Definition at line 40 of file heightmap.cpp.
Definition at line 64 of file heightmap.cpp.
void velodyne_height_map::HeightMap::constructFullClouds | ( | const VPointCloud::ConstPtr & | scan, |
unsigned | npoints, | ||
size_t & | obs_count, | ||
size_t & | empty_count | ||
) | [private] |
Definition at line 66 of file heightmap.cpp.
void velodyne_height_map::HeightMap::constructGridClouds | ( | const VPointCloud::ConstPtr & | scan, |
unsigned | npoints, | ||
size_t & | obs_count, | ||
size_t & | empty_count | ||
) | [private] |
Definition at line 113 of file heightmap.cpp.
void velodyne_height_map::HeightMap::processData | ( | const VPointCloud::ConstPtr & | scan | ) |
callback to process data input
scan | vector of input 3D data points |
stamp | time stamp of data |
frame_id | data frame of reference |
point cloud input callback
Definition at line 188 of file heightmap.cpp.
Definition at line 57 of file heightmap.h.
Definition at line 62 of file heightmap.h.
bool velodyne_height_map::HeightMap::full_clouds_ [private] |
Definition at line 53 of file heightmap.h.
int velodyne_height_map::HeightMap::grid_dim_ [private] |
Definition at line 50 of file heightmap.h.
double velodyne_height_map::HeightMap::height_diff_threshold_ [private] |
Definition at line 52 of file heightmap.h.
double velodyne_height_map::HeightMap::m_per_cell_ [private] |
Definition at line 51 of file heightmap.h.
Definition at line 56 of file heightmap.h.
Definition at line 61 of file heightmap.h.
Definition at line 60 of file heightmap.h.