7 #ifndef FLOAM__LIDAR_IMAGER_NODE_HPP_ 8 #define FLOAM__LIDAR_IMAGER_NODE_HPP_ 12 #include <sensor_msgs/PointCloud2.h> 15 #include <pcl/point_cloud.h> 16 #include <pcl/point_types.h> 36 void handlePoints(
const sensor_msgs::PointCloud2ConstPtr &lidarCloudMsg);
49 std::queue<sensor_msgs::PointCloud2ConstPtr>
m_points;
56 #endif // FLOAM__LIDAR_IMAGER_NODE_HPP_
ros::Publisher m_pubSurfacePoints
ros::Publisher m_pubPointsFiltered
ros::Publisher m_pubEdgePoints
Lidar< floam::lidar::Imager > m_lidar
std::queue< sensor_msgs::PointCloud2ConstPtr > m_points
void handlePoints(const sensor_msgs::PointCloud2ConstPtr &lidarCloudMsg)
Major rewrite Author: Evan Flynn.
ros::Subscriber m_subPoints
ros::NodeHandle m_nodeHandle