lidar_scanner_node.hpp
Go to the documentation of this file.
1 
3 
4 // Original Author of FLOAM: Wang Han
5 // Email wh200720041@gmail.com
6 // Homepage https://wanghan.pro
7 #ifndef FLOAM__LIDAR_SCANNER_NODE_HPP_
8 #define FLOAM__LIDAR_SCANNER_NODE_HPP_
9 
10 #include <ros/ros.h>
11 #include <nodelet/nodelet.h>
12 #include <sensor_msgs/PointCloud2.h>
13 #include <tf/transform_listener.h>
14 
16 #include <pcl/point_cloud.h>
17 #include <pcl/point_types.h>
18 
19 //local lib
20 #include "floam/lidar.hpp"
21 #include "floam/lidar_utils.hpp"
22 
23 namespace floam
24 {
25 namespace lidar
26 {
27 
28 
30 {
31 public:
34 
35  void onInit();
36 
37  void handlePoints(const sensor_msgs::PointCloud2ConstPtr &lidarCloudMsg);
38 
40 
41 private:
43 
45 
49 
52 
53  std::queue<sensor_msgs::PointCloud2ConstPtr> m_points;
54 };
55 
56 } // namespace lidar
57 } // namespace floam
58 
59 #endif // FLOAM__LIDAR_SCANNER_NODE_HPP_
floam::lidar::ScanningLidarNode::m_tf2Listener
tf2_ros::TransformListener m_tf2Listener
Definition: lidar_scanner_node.hpp:51
ros::Publisher
floam::lidar::ScanningLidarNode::m_pubEdgePoints
ros::Publisher m_pubEdgePoints
Definition: lidar_scanner_node.hpp:46
floam::lidar::ScanningLidarNode::ScanningLidarNode
ScanningLidarNode()
Definition: lidar_scanner_node.cpp:42
ros.h
lidar.hpp
floam::lidar::ScanningLidarNode::m_lidar
Lidar< floam::lidar::Scanner > m_lidar
Definition: lidar_scanner_node.hpp:39
floam::lidar::ScanningLidarNode::m_pubSurfacePoints
ros::Publisher m_pubSurfacePoints
Definition: lidar_scanner_node.hpp:47
floam::lidar::ScanningLidarNode
Definition: lidar_scanner_node.hpp:29
floam::lidar::ScanningLidarNode::m_pubEdgesAndSurfaces
ros::Publisher m_pubEdgesAndSurfaces
Definition: lidar_scanner_node.hpp:48
tf2_ros::TransformListener
floam::lidar::ScanningLidarNode::~ScanningLidarNode
~ScanningLidarNode()
Definition: lidar_scanner_node.cpp:48
floam::lidar::ScanningLidarNode::m_subPoints
ros::Subscriber m_subPoints
Definition: lidar_scanner_node.hpp:44
floam::lidar::Lidar< floam::lidar::Scanner >
floam::lidar::ScanningLidarNode::m_tf2Buffer
tf2_ros::Buffer m_tf2Buffer
Definition: lidar_scanner_node.hpp:50
tf2_ros::Buffer
floam::lidar::ScanningLidarNode::onInit
void onInit()
Definition: lidar_scanner_node.cpp:53
transform_listener.h
lidar_utils.hpp
nodelet::Nodelet
nodelet.h
floam::lidar::ScanningLidarNode::m_points
std::queue< sensor_msgs::PointCloud2ConstPtr > m_points
Definition: lidar_scanner_node.hpp:53
floam
Major rewrite Author: Evan Flynn.
Definition: lidar.hpp:15
floam::lidar::ScanningLidarNode::m_nodeHandle
ros::NodeHandle m_nodeHandle
Definition: lidar_scanner_node.hpp:42
ros::NodeHandle
ros::Subscriber
floam::lidar::ScanningLidarNode::handlePoints
void handlePoints(const sensor_msgs::PointCloud2ConstPtr &lidarCloudMsg)
Definition: lidar_scanner_node.cpp:103
pcl_conversions.h


floam
Author(s): Han Wang
autogenerated on Wed Mar 2 2022 00:23:09