lidar_scanner_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 #include <cmath>
9 #include <vector>
10 #include <mutex>
11 #include <queue>
12 #include <thread>
13 #include <chrono>
14 
15 //ros lib
16 #include <ros/ros.h>
17 #include <sensor_msgs/Imu.h>
18 #include <sensor_msgs/PointCloud2.h>
19 #include <nav_msgs/Odometry.h>
21 #include <tf/transform_datatypes.h>
23 #include <pcl_ros/transforms.h>
24 
25 //pcl lib
27 #include <pcl/point_cloud.h>
28 #include <pcl/point_types.h>
29 #include <pcl/filters/filter.h>
30 #include <pcl/filters/conditional_removal.h>
31 
32 //local lib
34 #include "floam/lidar.hpp"
35 #include "floam/lidar_utils.hpp"
36 
37 namespace floam
38 {
39 namespace lidar
40 {
41 
43 : m_tf2Listener(m_tf2Buffer)
44 {
45  // constructor
46 }
47 
49 {
50  // destructor
51 }
52 
54 {
56  // defaults
57  std::string points_topic = "points";
58  // frameId has to already be published and be connected to your lidar's frame_id
59  std::string frameId = "base_link";
60  int scan_lines = 64;
61  double vertical_angle = 2.0;
62  double horizontal_angle = 360.0;
63  double scan_period= 0.1;
64  double max_dis = 60.0;
65  double min_dis = 2.0;
66  double edgeThreshold = 0.05;
67  int skipPoints = 25;
68  int searchK = 10;
69  double searchRadius = 0.25;
70 
71  m_nodeHandle.getParam("points_topic", points_topic);
72  m_nodeHandle.getParam("scan_period", scan_period);
73  m_nodeHandle.getParam("vertical_angle", vertical_angle);
74  m_nodeHandle.getParam("horizontal_angle", horizontal_angle);
75  m_nodeHandle.getParam("max_dis", max_dis);
76  m_nodeHandle.getParam("min_dis", min_dis);
77  m_nodeHandle.getParam("scan_lines", scan_lines);
78  m_nodeHandle.getParam("edge_threshold", edgeThreshold);
79  m_nodeHandle.getParam("skip_points", skipPoints);
80  m_nodeHandle.getParam("search_radius", searchRadius);
81  m_nodeHandle.getParam("search_k", searchK);
82  m_nodeHandle.getParam("frame_id", frameId);
83 
84  m_lidar.m_settings.period = scan_period;
85  m_lidar.m_settings.lines = scan_lines;
86  m_lidar.m_settings.skipPoints = skipPoints;
87  m_lidar.m_settings.searchK = searchK;
88  m_lidar.m_settings.searchRadius = searchRadius;
91  m_lidar.m_settings.common.fov.vertical = vertical_angle;
92  m_lidar.m_settings.common.fov.horizontal = horizontal_angle;
95 
97 
98  m_pubEdgePoints = m_nodeHandle.advertise<sensor_msgs::PointCloud2>("points_edge", 100);
99  m_pubSurfacePoints = m_nodeHandle.advertise<sensor_msgs::PointCloud2>("points_surface", 100);
100  m_pubEdgesAndSurfaces = m_nodeHandle.advertise<sensor_msgs::PointCloud2>("points_filtered", 100);
101 }
102 
103 void ScanningLidarNode::handlePoints(const sensor_msgs::PointCloud2ConstPtr & points)
104 {
105  // convert msg to pcl format, only XYZ and remove NaN points
106  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudWithNaN(new pcl::PointCloud<pcl::PointXYZ>());
107  pcl::PointCloud<pcl::PointXYZ>::Ptr cloudTransformed(new pcl::PointCloud<pcl::PointXYZ>());
108  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>());
110  pcl::fromROSMsg(*points, *cloudWithNaN);
111 
112  // geometry_msgs::TransformStamped transformStamped;
113  // transformStamped = m_tf2Buffer.lookupTransform(
114  // m_lidar.m_settings.common.frameId,
115  // points->header.frame_id,
116  // ros::Time(0));
117  // transform pointclouds to new coordinate frame
118  // pcl_ros::transformPointCloud<pcl::PointXYZ>(*cloudWithNaN, *cloudTransformed, transformStamped.transform);
119 
120  std::vector<int> indices;
122  pcl::removeNaNFromPointCloud(*cloudWithNaN, *cloud, indices);
123 
124  // initialize timers to calculate how long the processing takes
125  std::chrono::time_point<std::chrono::system_clock> start, end;
126  start = std::chrono::system_clock::now();
127 
128  // initialize edge and surface clouds
129  pcl::PointCloud<pcl::PointXYZL>::Ptr edgesAndSurfaces(new pcl::PointCloud<pcl::PointXYZL>());
130  pcl::PointCloud<pcl::PointXYZL>::Ptr surfaces(new pcl::PointCloud<pcl::PointXYZL>());
131  pcl::PointCloud<pcl::PointXYZL>::Ptr edges(new pcl::PointCloud<pcl::PointXYZL>());
132 
133  // for scanners, edge pointcloud should also include surface information
134  m_lidar.detectEdges(cloud, edgesAndSurfaces);
135 
136  // separate edge cloud into edge and surface clouds
137  auto edge_cond = pcl::make_shared<floam::lidar::GenericCondition<pcl::PointXYZL>>(
138  [](const pcl::PointXYZL & point) {
139  return point.label > 0;
140  }
141  );
142 
143  auto surface_cond = pcl::make_shared<floam::lidar::GenericCondition<pcl::PointXYZL>>(
144  [](const pcl::PointXYZL & point) {
145  return point.label == 0;
146  }
147  );
148 
149  // remove surfaces to get edges
150  pcl::ConditionalRemoval<pcl::PointXYZL> surface_removal;
151  pcl::ConditionalRemoval<pcl::PointXYZL> edge_removal;
152 
153  surface_removal.setCondition(edge_cond);
154  surface_removal.setInputCloud(edgesAndSurfaces);
155  surface_removal.filter(*edges);
156 
157  edge_removal.setCondition(surface_cond);
158  edge_removal.setInputCloud(edgesAndSurfaces);
159  edge_removal.filter(*surfaces);
160 
161  std::vector <pcl::PointIndices> labelIndices;
162 
163  // end processing time
164  end = std::chrono::system_clock::now();
165  std::chrono::duration<float> elapsed_seconds = end - start;
166 
167  // increment total frame counter
169  // add time to total time
170  float time_temp = elapsed_seconds.count() * 1000;
171  m_lidar.m_total.time += time_temp;
172  // ROS_INFO("average lidar processing time %f ms", m_lidar.m_total.time / m_lidar.m_total.frames);
173 
174  // TODO(flynneva): transform pointclouds to new coordinate frame?
175  // convert edge pcl to ROS message
176  sensor_msgs::PointCloud2 edgeMsg;
177  pcl::toROSMsg(*edges, edgeMsg);
178 
179  // convert surface pcl to ROS message
180  sensor_msgs::PointCloud2 surfaceMsg;
181  pcl::toROSMsg(*surfaces, surfaceMsg);
182 
183  // convert edges and surfaces pcl to ROS message
184  sensor_msgs::PointCloud2 edgeAndSurfaceMsg;
185  pcl::toROSMsg(*edgesAndSurfaces, edgeAndSurfaceMsg);
186 
187  // set header timestamp same as input pointcloud
188  edgeMsg.header = points->header;
189  surfaceMsg.header = points->header;
190  edgeAndSurfaceMsg.header = points->header;
191 
192  // set new frame_id
193  std::string floamLidarFrame = m_lidar.m_settings.common.frameId;
194  edgeMsg.header.frame_id = floamLidarFrame;
195  surfaceMsg.header.frame_id = floamLidarFrame;
196  edgeAndSurfaceMsg.header.frame_id = floamLidarFrame;
197 
198  // publish filtered, edge and surface clouds
199  m_pubEdgePoints.publish(edgeMsg);
200  m_pubSurfacePoints.publish(surfaceMsg);
201  m_pubEdgesAndSurfaces.publish(edgeAndSurfaceMsg);
202 }
203 
204 } // namespace lidar
205 } // namespace floam
206 
207 #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::FOV::vertical
double vertical
Definition: lidar_utils.hpp:42
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::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
lidar.hpp
floam::lidar::Scanner::searchK
int searchK
Definition: lidar_utils.hpp:60
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(floam::lidar::LidarMappingNode, nodelet::Nodelet)
floam::lidar::Scanner::searchRadius
double searchRadius
Definition: lidar_utils.hpp:61
floam::lidar::Scanner::period
double period
Definition: lidar_utils.hpp:62
floam::lidar::Limits::distance
Distance distance
Definition: lidar_utils.hpp:31
floam::lidar::ScanningLidarNode::m_lidar
Lidar< floam::lidar::Scanner > m_lidar
Definition: lidar_scanner_node.hpp:39
floam::lidar::Scanner::lines
int lines
Definition: lidar_utils.hpp:58
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
floam::lidar::Limits::edgeThreshold
double edgeThreshold
Definition: lidar_utils.hpp:33
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
transforms.h
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
class_list_macros.h
floam::lidar::Total::time
double time
Definition: lidar_utils.hpp:76
floam::lidar::ScanningLidarNode::~ScanningLidarNode
~ScanningLidarNode()
Definition: lidar_scanner_node.cpp:48
frameId
std::string const * frameId(const M &m)
floam::lidar::ScanningLidarNode::m_subPoints
ros::Subscriber m_subPoints
Definition: lidar_scanner_node.hpp:44
floam::lidar::Settings::fov
FOV fov
Definition: lidar_utils.hpp:49
floam::lidar::Scanner::skipPoints
int skipPoints
Definition: lidar_utils.hpp:59
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::Settings::frameId
std::string frameId
Definition: lidar_utils.hpp:47
floam::lidar::ScanningLidarNode::onInit
void onInit()
Definition: lidar_scanner_node.cpp:53
floam::lidar::Distance::min
double min
Definition: lidar_utils.hpp:27
transform_listener.h
start
ROSCPP_DECL void start()
lidar_utils.hpp
nodelet::Nodelet
transform_datatypes.h
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::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::Scanner::common
Settings common
Definition: lidar_utils.hpp:64
lidar_scanner_node.hpp
floam::lidar::FOV::horizontal
double horizontal
Definition: lidar_utils.hpp:43
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
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