#include <height_from_plane_map.h>
Public Member Functions | |
HeightFromPlaneMap () | |
Private Member Functions | |
float | distance_from_plane (double x, double y, double z, std::vector< float > coefs) |
void | height_map_callback (const pcl::ModelCoefficients::ConstPtr &coefficients_msg, const sensor_msgs::PointCloud2::ConstPtr &pcl2_msg) |
void | reconfigureCallback (iri_pcl_filters::IriPclFiltersParametersConfig &config, uint32_t level) |
Private Attributes | |
message_filters::Subscriber < pcl::ModelCoefficients > | coefficients_sub_ |
dynamic_reconfigure::Server < iri_pcl_filters::IriPclFiltersParametersConfig > | dyn_reconfig_srv |
CMutex | mutex |
ros::NodeHandle | nh_ |
ros::Publisher | pcl2_pub_ |
sensor_msgs::PointCloud2 | pcl2_score_map_msg_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | pcl2_sub_ |
pcl::PointCloud< pcl::PointXYZRGB > | pcl_xyzrgb_ |
message_filters::TimeSynchronizer < pcl::ModelCoefficients, sensor_msgs::PointCloud2 > * | sync_ |
Definition at line 48 of file height_from_plane_map.h.
Definition at line 6 of file height_from_plane_map.cpp.
float HeightFromPlaneMap::distance_from_plane | ( | double | x, |
double | y, | ||
double | z, | ||
std::vector< float > | coefs | ||
) | [private] |
Definition at line 76 of file height_from_plane_map.cpp.
void HeightFromPlaneMap::height_map_callback | ( | const pcl::ModelCoefficients::ConstPtr & | coefficients_msg, |
const sensor_msgs::PointCloud2::ConstPtr & | pcl2_msg | ||
) | [private] |
Definition at line 47 of file height_from_plane_map.cpp.
void HeightFromPlaneMap::reconfigureCallback | ( | iri_pcl_filters::IriPclFiltersParametersConfig & | config, |
uint32_t | level | ||
) | [private] |
Definition at line 36 of file height_from_plane_map.cpp.
Definition at line 62 of file height_from_plane_map.h.
dynamic_reconfigure::Server<iri_pcl_filters::IriPclFiltersParametersConfig> HeightFromPlaneMap::dyn_reconfig_srv [private] |
Definition at line 69 of file height_from_plane_map.h.
CMutex HeightFromPlaneMap::mutex [private] |
Definition at line 54 of file height_from_plane_map.h.
ros::NodeHandle HeightFromPlaneMap::nh_ [private] |
Definition at line 56 of file height_from_plane_map.h.
ros::Publisher HeightFromPlaneMap::pcl2_pub_ [private] |
Definition at line 66 of file height_from_plane_map.h.
sensor_msgs::PointCloud2 HeightFromPlaneMap::pcl2_score_map_msg_ [private] |
Definition at line 67 of file height_from_plane_map.h.
message_filters::Subscriber<sensor_msgs::PointCloud2> HeightFromPlaneMap::pcl2_sub_ [private] |
Definition at line 63 of file height_from_plane_map.h.
pcl::PointCloud<pcl::PointXYZRGB> HeightFromPlaneMap::pcl_xyzrgb_ [private] |
Definition at line 58 of file height_from_plane_map.h.
message_filters::TimeSynchronizer<pcl::ModelCoefficients, sensor_msgs::PointCloud2>* HeightFromPlaneMap::sync_ [private] |
Definition at line 60 of file height_from_plane_map.h.