lidar_imager_node.cpp
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 
8 //c++ lib
9 #include <cmath>
10 #include <vector>
11 #include <mutex>
12 #include <queue>
13 #include <thread>
14 #include <chrono>
15 
16 //ros lib
17 #include <ros/ros.h>
18 #include <sensor_msgs/Imu.h>
19 #include <sensor_msgs/PointCloud2.h>
20 #include <nav_msgs/Odometry.h>
21 #include <tf/transform_datatypes.h>
23 
24 //pcl lib
26 #include <pcl/point_cloud.h>
27 #include <pcl/point_types.h>
28 
29 //local lib
31 #include "floam/lidar.hpp"
32 
33 
34 namespace floam
35 {
36 namespace lidar
37 {
38 
40 {
41  // constructor
42 }
43 
45 {
46  // destructor
47 }
48 
50 {
52 
53  std::string points_topic = "points";
54  std::string frameId = "base_link";
55  double vertical_angle = 2.0;
56  double horizontal_angle = 120.0;
57  double max_dis = 60.0;
58  double min_dis = 2.0;
59  double framerate = 30.0;
60 
61  m_nodeHandle.getParam("points_topic", points_topic);
62  m_nodeHandle.getParam("vertical_angle", vertical_angle);
63  m_nodeHandle.getParam("horizontal_angle", horizontal_angle);
64  m_nodeHandle.getParam("max_dis", max_dis);
65  m_nodeHandle.getParam("min_dis", min_dis);
66  m_nodeHandle.getParam("framerate", framerate);
67  m_nodeHandle.getParam("frame_id", frameId);
68 
69 
70  m_lidar.m_settings.framerate = framerate;
72  m_lidar.m_settings.common.fov.vertical = vertical_angle;
73  m_lidar.m_settings.common.fov.horizontal = horizontal_angle;
76 
78 
79  m_pubEdgePoints = m_nodeHandle.advertise<sensor_msgs::PointCloud2>("points_edge", 100);
80 
81  m_pubSurfacePoints = m_nodeHandle.advertise<sensor_msgs::PointCloud2>("points_surface", 100);
82 }
83 
84 void ImagingLidarNode::handlePoints(const sensor_msgs::PointCloud2ConstPtr & points)
85 {
86  // convert msg to pcl format, only XYZ
87  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>());
88  pcl::fromROSMsg(*points, *cloud);
89 
90  // initialize timers to calculate how long the processing takes
91  std::chrono::time_point<std::chrono::system_clock> start, end;
92  start = std::chrono::system_clock::now();
93 
94  // initialize edge and surface clouds
95  pcl::PointCloud<pcl::PointXYZL>::Ptr edges(new pcl::PointCloud<pcl::PointXYZL>());
96  pcl::PointCloud<pcl::PointNormal>::Ptr normals(new pcl::PointCloud<pcl::PointNormal>());
97 
98  m_lidar.detectSurfaces(cloud, normals);
99  m_lidar.detectEdges(cloud, edges);
100 
101  std::vector <pcl::PointIndices> labelIndices;
102 
103  // end processing time
104  end = std::chrono::system_clock::now();
105  std::chrono::duration<float> elapsed_seconds = end - start;
106 
107  // increment total frame counter
109  // add time to total time
110  float time_temp = elapsed_seconds.count() * 1000;
111  m_lidar.m_total.time += time_temp;
112  // ROS_INFO("average lidar processing time %f ms", m_lidar.m_total.time / m_lidar.m_total.frames);
113 
114  // convert edge pcl to ROS message
115  sensor_msgs::PointCloud2 edgePoints;
116  pcl::toROSMsg(*edges, edgePoints);
117 
118  // convert surface pcl to ROS message
119  sensor_msgs::PointCloud2 surfacePoints;
120  pcl::toROSMsg(*normals, surfacePoints);
121 
122  // set header information
123  edgePoints.header = points->header;
124  surfacePoints.header = points->header;
125 
126  // publish filtered, edge and surface clouds
127  m_pubEdgePoints.publish(edgePoints);
128  m_pubSurfacePoints.publish(surfacePoints);
129 }
130 
131 } // namespace lidar
132 } // namespace floam
133 
134 #include <pluginlib/class_list_macros.h> // NO LINT
floam::lidar::Lidar::m_total
floam::lidar::Total m_total
Total counters (i.e. frames and time)
Definition: lidar.hpp:46
floam::lidar::ImagingLidarNode::ImagingLidarNode
ImagingLidarNode()
Definition: lidar_imager_node.cpp:39
floam::lidar::Lidar::detectSurfaces
void detectSurfaces(const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointNormal >::Ptr &normals)
floam::lidar::FOV::vertical
double vertical
Definition: lidar_utils.hpp:42
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
lidar.hpp
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(floam::lidar::LidarMappingNode, nodelet::Nodelet)
floam::lidar::Limits::distance
Distance distance
Definition: lidar_utils.hpp:31
floam::lidar::ImagingLidarNode::handlePoints
void handlePoints(const sensor_msgs::PointCloud2ConstPtr &lidarCloudMsg)
Definition: lidar_imager_node.cpp:84
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
transform_broadcaster.h
class_list_macros.h
floam::lidar::Total::time
double time
Definition: lidar_utils.hpp:76
frameId
std::string const * frameId(const M &m)
floam::lidar::ImagingLidarNode::m_subPoints
ros::Subscriber m_subPoints
Definition: lidar_imager_node.hpp:43
floam::lidar::ImagingLidarNode::m_nodeHandle
ros::NodeHandle m_nodeHandle
Definition: lidar_imager_node.hpp:41
floam::lidar::Settings::fov
FOV fov
Definition: lidar_utils.hpp:49
floam::lidar::ImagingLidarNode::m_pubSurfacePoints
ros::Publisher m_pubSurfacePoints
Definition: lidar_imager_node.hpp:46
lidar_imager_node.hpp
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
floam::lidar::ImagingLidarNode::onInit
void onInit()
Definition: lidar_imager_node.cpp:49
floam::lidar::Settings::frameId
std::string frameId
Definition: lidar_utils.hpp:47
floam::lidar::Distance::min
double min
Definition: lidar_utils.hpp:27
start
ROSCPP_DECL void start()
nodelet::Nodelet
transform_datatypes.h
floam::lidar::Imager::common
Settings common
Definition: lidar_utils.hpp:72
floam::lidar::Lidar::m_settings
T m_settings
Settings for specific Lidar type.
Definition: lidar.hpp:44
floam::lidar::Lidar::detectEdges
void detectEdges(const pcl::PointCloud< pcl::PointXYZ >::Ptr &points, pcl::PointCloud< pcl::PointXYZL >::Ptr &edges)
floam::lidar::ImagingLidarNode
Definition: lidar_imager_node.hpp:28
floam::lidar::Distance::max
double max
Definition: lidar_utils.hpp:26
floam::lidar::Total::frames
int frames
Definition: lidar_utils.hpp:77
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
floam::lidar::Settings::limits
Limits limits
Definition: lidar_utils.hpp:51
floam::lidar::ImagingLidarNode::~ImagingLidarNode
~ImagingLidarNode()
Definition: lidar_imager_node.cpp:44
floam::lidar::FOV::horizontal
double horizontal
Definition: lidar_utils.hpp:43
floam::lidar::ImagingLidarNode::m_lidar
Lidar< floam::lidar::Imager > m_lidar
Definition: lidar_imager_node.hpp:38
floam
Major rewrite Author: Evan Flynn.
Definition: lidar.hpp:15
floam::lidar::ImagingLidarNode::m_pubEdgePoints
ros::Publisher m_pubEdgePoints
Definition: lidar_imager_node.hpp:45
floam::lidar::Imager::framerate
double framerate
Definition: lidar_utils.hpp:71
pcl_conversions.h


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