Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Typedefs
Enumerations
Enumerator
Classes
Class List
Class Hierarchy
Class Members
All
_
a
c
d
e
f
g
h
i
l
m
n
o
p
s
t
u
v
~
Functions
a
c
d
e
g
h
i
l
o
p
s
u
~
Variables
_
a
c
d
e
f
h
i
l
m
n
p
s
t
v
Typedefs
Files
File List
File Members
All
Functions
Macros
include
floam
lidar_mapping_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
8
#ifndef FLOAM__LIDAR_MAPPING_NODE_HPP_
9
#define FLOAM__LIDAR_MAPPING_NODE_HPP_
10
11
#include <
ros/ros.h
>
12
#include <
nodelet/nodelet.h
>
13
#include <sensor_msgs/PointCloud2.h>
14
#include <nav_msgs/Odometry.h>
15
#include <
tf/transform_datatypes.h
>
16
#include <
tf/transform_broadcaster.h
>
17
#include <
message_filters/synchronizer.h
>
18
#include <
message_filters/sync_policies/exact_time.h
>
19
#include <
message_filters/sync_policies/approximate_time.h
>
20
21
#include <
pcl_conversions/pcl_conversions.h
>
22
#include <pcl/point_cloud.h>
23
#include <pcl/point_types.h>
24
25
#include "
floam/lidar_mapping.hpp
"
26
#include "
floam/lidar_utils.hpp
"
27
28
namespace
floam
29
{
30
namespace
lidar
31
{
32
33
typedef
message_filters::sync_policies::ExactTime<nav_msgs::Odometry, sensor_msgs::PointCloud2>
ExactSyncPolicy
;
34
typedef
message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::PointCloud2>
ApproximateSyncPolicy
;
35
36
class
LidarMappingNode
:
public
nodelet::Nodelet
37
{
38
public
:
42
LidarMappingNode
();
43
47
~LidarMappingNode
();
48
54
void
onInit
();
55
56
private
:
57
ros::NodeHandle
m_nodeHandle
;
58
ros::Publisher
m_pubMap
;
59
60
typedef
message_filters::Synchronizer<ApproximateSyncPolicy>
ApproximateSynchronizer
;
61
typedef
message_filters::Synchronizer<ExactSyncPolicy>
ExactSynchronizer
;
62
63
message_filters::Subscriber<sensor_msgs::PointCloud2>
m_subPoints
;
64
message_filters::Subscriber<nav_msgs::Odometry>
m_subOdom
;
65
66
std::shared_ptr<ApproximateSynchronizer>
m_approximateSync
;
67
std::shared_ptr<ExactSynchronizer>
m_exactSync
;
68
69
void
generateMap
(
70
const
nav_msgs::OdometryConstPtr & odom,
71
const
sensor_msgs::PointCloud2ConstPtr & cloud);
72
73
LidarMapping
m_lidarMapping
;
74
75
bool
m_useExactSync
=
false
;
76
int
m_queueSize
= 5;
77
};
78
79
}
// namespace lidar
80
}
// namespace floam
81
82
#endif // FLOAM__LIDAR_MAPPING_NODE_HPP_
ros::Publisher
floam::lidar::LidarMappingNode::m_queueSize
int m_queueSize
Definition:
lidar_mapping_node.hpp:76
message_filters::Synchronizer
floam::lidar::LidarMappingNode::m_exactSync
std::shared_ptr< ExactSynchronizer > m_exactSync
Definition:
lidar_mapping_node.hpp:67
floam::lidar::LidarMappingNode::m_useExactSync
bool m_useExactSync
Definition:
lidar_mapping_node.hpp:75
floam::lidar::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< nav_msgs::Odometry, sensor_msgs::PointCloud2 > ApproximateSyncPolicy
Definition:
lidar_mapping_node.hpp:34
ros.h
floam::lidar::LidarMappingNode::onInit
void onInit()
Definition:
lidar_mapping_node.cpp:39
floam::lidar::ExactSyncPolicy
message_filters::sync_policies::ExactTime< nav_msgs::Odometry, sensor_msgs::PointCloud2 > ExactSyncPolicy
Definition:
lidar_mapping_node.hpp:33
floam::lidar::LidarMappingNode::~LidarMappingNode
~LidarMappingNode()
Definition:
lidar_mapping_node.cpp:34
floam::lidar::LidarMappingNode::m_subPoints
message_filters::Subscriber< sensor_msgs::PointCloud2 > m_subPoints
Definition:
lidar_mapping_node.hpp:63
floam::lidar::LidarMapping
Definition:
lidar_mapping.hpp:43
floam::lidar::LidarMappingNode::generateMap
void generateMap(const nav_msgs::OdometryConstPtr &odom, const sensor_msgs::PointCloud2ConstPtr &cloud)
Definition:
lidar_mapping_node.cpp:71
floam::lidar::LidarMappingNode::m_subOdom
message_filters::Subscriber< nav_msgs::Odometry > m_subOdom
Definition:
lidar_mapping_node.hpp:64
transform_broadcaster.h
floam::lidar::LidarMappingNode::m_pubMap
ros::Publisher m_pubMap
Definition:
lidar_mapping_node.hpp:58
message_filters::Subscriber< sensor_msgs::PointCloud2 >
message_filters::sync_policies::ApproximateTime
floam::lidar::LidarMappingNode::LidarMappingNode
LidarMappingNode()
Definition:
lidar_mapping_node.cpp:29
floam::lidar::LidarMappingNode
Definition:
lidar_mapping_node.hpp:36
floam::lidar::LidarMappingNode::ApproximateSynchronizer
message_filters::Synchronizer< ApproximateSyncPolicy > ApproximateSynchronizer
Definition:
lidar_mapping_node.hpp:60
exact_time.h
lidar_mapping.hpp
lidar_utils.hpp
nodelet::Nodelet
transform_datatypes.h
nodelet.h
synchronizer.h
floam::lidar::LidarMappingNode::m_nodeHandle
ros::NodeHandle m_nodeHandle
Definition:
lidar_mapping_node.hpp:57
floam::lidar::LidarMappingNode::m_lidarMapping
LidarMapping m_lidarMapping
Definition:
lidar_mapping_node.hpp:73
approximate_time.h
message_filters::sync_policies::ExactTime
floam::lidar::LidarMappingNode::ExactSynchronizer
message_filters::Synchronizer< ExactSyncPolicy > ExactSynchronizer
Definition:
lidar_mapping_node.hpp:61
floam::lidar::LidarMappingNode::m_approximateSync
std::shared_ptr< ApproximateSynchronizer > m_approximateSync
Definition:
lidar_mapping_node.hpp:66
floam
Major rewrite Author: Evan Flynn.
Definition:
lidar.hpp:15
ros::NodeHandle
pcl_conversions.h
floam
Author(s): Han Wang
autogenerated on Wed Mar 2 2022 00:23:09