forked from hyye/lio-mapping
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmapping_node.cc
75 lines (61 loc) · 1.92 KB
/
mapping_node.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
/**
* This file is part of LIO-mapping.
*
* Copyright (C) 2019 Haoyang Ye <hy.ye at connect dot ust dot hk>,
* Robotics and Multiperception Lab (RAM-LAB <https://ram-lab.com>),
* The Hong Kong University of Science and Technology
*
* For more information please see <https://ram-lab.com/file/hyye/lio-mapping>
* or <https://sites.google.com/view/lio-mapping>.
* If you use this code, please cite the respective publications as
* listed on the above websites.
*
* LIO-mapping is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* LIO-mapping is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with LIO-mapping. If not, see <http://www.gnu.org/licenses/>.
*/
//
// Created by hyye on 3/25/18.
//
//
// Created by hyye on 3/15/18.
//
#include <gtest/gtest.h>
#include <gflags/gflags.h>
#include <glog/logging.h>
#include <pcl/io/pcd_io.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf/transform_datatypes.h>
#include <geometry_msgs/Quaternion.h>
#include "point_processor/PointMapping.h"
#include "utils/TicToc.h"
using namespace lio;
using namespace std;
using namespace mathutils;
int main(int argc, char **argv) {
google::InitGoogleLogging(argv[0]);
FLAGS_alsologtostderr = true;
ros::init(argc, argv, "point_mapping");
ros::NodeHandle nh("~");;
PointMapping mapper;
mapper.SetupRos(nh);
mapper.Reset();
ros::Rate r(100);
while (ros::ok()) {
mapper.Process();
ros::spinOnce();
r.sleep();
}
return 0;
}