Skip to content

Commit 911704f

Browse files
committed
Announcement: Thank everyone who has been testing and supporting our LeGO-LOAM package. I have completed my Ph.D. program at Stevens and started a new job at MIT. Due to the limitation of my working bandwidth, the update and answering for the repository may be delayed. Sorry for any inconvenience.
0 parents  commit 911704f

23 files changed

+5231
-0
lines changed

.github/stale.yml

+17
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
# Number of days of inactivity before an issue becomes stale
2+
daysUntilStale: 60
3+
# Number of days of inactivity before a stale issue is closed
4+
daysUntilClose: 7
5+
# Issues with these labels will never be considered stale
6+
exemptLabels:
7+
- pinned
8+
- security
9+
# Label to use when marking an issue as stale
10+
staleLabel: wontfix
11+
# Comment to post when marking an issue as stale. Set to `false` to disable
12+
markComment: >
13+
This issue has been automatically marked as stale because it has not had
14+
recent activity. It will be closed if no further activity occurs. Thank you
15+
for your contributions.
16+
# Comment to post when closing a stale issue. Set to `false` to disable
17+
closeComment: false

LICENSE

+29
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
BSD 3-Clause License
2+
3+
Copyright (c) 2018, Robust Field Autonomy Lab
4+
All rights reserved.
5+
6+
Redistribution and use in source and binary forms, with or without
7+
modification, are permitted provided that the following conditions are met:
8+
9+
* Redistributions of source code must retain the above copyright notice, this
10+
list of conditions and the following disclaimer.
11+
12+
* Redistributions in binary form must reproduce the above copyright notice,
13+
this list of conditions and the following disclaimer in the documentation
14+
and/or other materials provided with the distribution.
15+
16+
* Neither the name of the copyright holder nor the names of its
17+
contributors may be used to endorse or promote products derived from
18+
this software without specific prior written permission.
19+
20+
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21+
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22+
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23+
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24+
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25+
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26+
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27+
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28+
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29+
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

LeGO-LOAM/CMakeLists.txt

+60
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(lego_loam)
3+
4+
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3")
5+
6+
find_package(catkin REQUIRED COMPONENTS
7+
tf
8+
roscpp
9+
rospy
10+
cv_bridge
11+
image_transport
12+
13+
pcl_ros
14+
pcl_conversions
15+
16+
std_msgs
17+
sensor_msgs
18+
geometry_msgs
19+
nav_msgs
20+
cloud_msgs
21+
)
22+
23+
find_package(GTSAM REQUIRED QUIET)
24+
find_package(PCL REQUIRED QUIET)
25+
find_package(OpenCV REQUIRED QUIET)
26+
27+
catkin_package(
28+
INCLUDE_DIRS include
29+
CATKIN_DEPENDS cloud_msgs
30+
DEPENDS PCL
31+
)
32+
33+
include_directories(
34+
include
35+
${catkin_INCLUDE_DIRS}
36+
${PCL_INCLUDE_DIRS}
37+
${OpenCV_INCLUDE_DIRS}
38+
${GTSAM_INCLUDE_DIR}
39+
)
40+
41+
link_directories(
42+
include
43+
${OpenCV_LIBRARY_DIRS}
44+
${PCL_LIBRARY_DIRS}
45+
${GTSAM_LIBRARY_DIRS}
46+
)
47+
48+
add_executable(imageProjection src/imageProjection.cpp)
49+
add_dependencies(imageProjection ${catkin_EXPORTED_TARGETS} cloud_msgs_gencpp)
50+
target_link_libraries(imageProjection ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES})
51+
52+
add_executable(featureAssociation src/featureAssociation.cpp)
53+
add_dependencies(featureAssociation ${catkin_EXPORTED_TARGETS} cloud_msgs_gencpp)
54+
target_link_libraries(featureAssociation ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES})
55+
56+
add_executable(mapOptmization src/mapOptmization.cpp)
57+
target_link_libraries(mapOptmization ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} gtsam)
58+
59+
add_executable(transformFusion src/transformFusion.cpp)
60+
target_link_libraries(transformFusion ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES})

LeGO-LOAM/include/utility.h

+161
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,161 @@
1+
#ifndef _UTILITY_LIDAR_ODOMETRY_H_
2+
#define _UTILITY_LIDAR_ODOMETRY_H_
3+
4+
5+
#include <ros/ros.h>
6+
7+
#include <sensor_msgs/Imu.h>
8+
#include <sensor_msgs/PointCloud2.h>
9+
#include <nav_msgs/Odometry.h>
10+
11+
#include "cloud_msgs/cloud_info.h"
12+
13+
#include <opencv/cv.h>
14+
15+
#include <pcl/point_cloud.h>
16+
#include <pcl/point_types.h>
17+
#include <pcl_ros/point_cloud.h>
18+
#include <pcl_conversions/pcl_conversions.h>
19+
#include <pcl/range_image/range_image.h>
20+
#include <pcl/filters/filter.h>
21+
#include <pcl/filters/voxel_grid.h>
22+
#include <pcl/kdtree/kdtree_flann.h>
23+
#include <pcl/common/common.h>
24+
#include <pcl/registration/icp.h>
25+
26+
#include <tf/transform_broadcaster.h>
27+
#include <tf/transform_datatypes.h>
28+
29+
#include <vector>
30+
#include <cmath>
31+
#include <algorithm>
32+
#include <queue>
33+
#include <deque>
34+
#include <iostream>
35+
#include <fstream>
36+
#include <ctime>
37+
#include <cfloat>
38+
#include <iterator>
39+
#include <sstream>
40+
#include <string>
41+
#include <limits>
42+
#include <iomanip>
43+
#include <array>
44+
#include <thread>
45+
#include <mutex>
46+
47+
#define PI 3.14159265
48+
49+
using namespace std;
50+
51+
typedef pcl::PointXYZI PointType;
52+
53+
extern const string pointCloudTopic = "/velodyne_points";
54+
extern const string imuTopic = "/imu/data";
55+
56+
// Save pcd
57+
extern const string fileDirectory = "/tmp/";
58+
59+
// VLP-16
60+
extern const int N_SCAN = 16;
61+
extern const int Horizon_SCAN = 1800;
62+
extern const float ang_res_x = 0.2;
63+
extern const float ang_res_y = 2.0;
64+
extern const float ang_bottom = 15.0+0.1;
65+
extern const int groundScanInd = 7;
66+
67+
// HDL-32E
68+
// extern const int N_SCAN = 32;
69+
// extern const int Horizon_SCAN = 1800;
70+
// extern const float ang_res_x = 360.0/float(Horizon_SCAN);
71+
// extern const float ang_res_y = 41.33/float(N_SCAN-1);
72+
// extern const float ang_bottom = 30.67;
73+
// extern const int groundScanInd = 20;
74+
75+
// Ouster users may need to uncomment line 159 in imageProjection.cpp
76+
// Usage of Ouster imu data is not fully supported yet, please just publish point cloud data
77+
// Ouster OS1-16
78+
// extern const int N_SCAN = 16;
79+
// extern const int Horizon_SCAN = 1024;
80+
// extern const float ang_res_x = 360.0/float(Horizon_SCAN);
81+
// extern const float ang_res_y = 33.2/float(N_SCAN-1);
82+
// extern const float ang_bottom = 16.6+0.1;
83+
// extern const int groundScanInd = 7;
84+
85+
// Ouster OS1-64
86+
// extern const int N_SCAN = 64;
87+
// extern const int Horizon_SCAN = 1024;
88+
// extern const float ang_res_x = 360.0/float(Horizon_SCAN);
89+
// extern const float ang_res_y = 33.2/float(N_SCAN-1);
90+
// extern const float ang_bottom = 16.6+0.1;
91+
// extern const int groundScanInd = 15;
92+
93+
extern const bool loopClosureEnableFlag = false;
94+
extern const double mappingProcessInterval = 0.3;
95+
96+
extern const float scanPeriod = 0.1;
97+
extern const int systemDelay = 0;
98+
extern const int imuQueLength = 200;
99+
100+
extern const float sensorMountAngle = 0.0;
101+
extern const float segmentTheta = 60.0/180.0*M_PI; // decrese this value may improve accuracy
102+
extern const int segmentValidPointNum = 5;
103+
extern const int segmentValidLineNum = 3;
104+
extern const float segmentAlphaX = ang_res_x / 180.0 * M_PI;
105+
extern const float segmentAlphaY = ang_res_y / 180.0 * M_PI;
106+
107+
108+
extern const int edgeFeatureNum = 2;
109+
extern const int surfFeatureNum = 4;
110+
extern const int sectionsTotal = 6;
111+
extern const float edgeThreshold = 0.1;
112+
extern const float surfThreshold = 0.1;
113+
extern const float nearestFeatureSearchSqDist = 25;
114+
115+
116+
// Mapping Params
117+
extern const float surroundingKeyframeSearchRadius = 50.0; // key frame that is within n meters from current pose will be considerd for scan-to-map optimization (when loop closure disabled)
118+
extern const int surroundingKeyframeSearchNum = 50; // submap size (when loop closure enabled)
119+
// history key frames (history submap for loop closure)
120+
extern const float historyKeyframeSearchRadius = 7.0; // key frame that is within n meters from current pose will be considerd for loop closure
121+
extern const int historyKeyframeSearchNum = 25; // 2n+1 number of hostory key frames will be fused into a submap for loop closure
122+
extern const float historyKeyframeFitnessScore = 0.3; // the smaller the better alignment
123+
124+
extern const float globalMapVisualizationSearchRadius = 500.0; // key frames with in n meters will be visualized
125+
126+
127+
struct smoothness_t{
128+
float value;
129+
size_t ind;
130+
};
131+
132+
struct by_value{
133+
bool operator()(smoothness_t const &left, smoothness_t const &right) {
134+
return left.value < right.value;
135+
}
136+
};
137+
138+
/*
139+
* A point cloud type that has 6D pose info ([x,y,z,roll,pitch,yaw] intensity is time stamp)
140+
*/
141+
struct PointXYZIRPYT
142+
{
143+
PCL_ADD_POINT4D
144+
PCL_ADD_INTENSITY;
145+
float roll;
146+
float pitch;
147+
float yaw;
148+
double time;
149+
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150+
} EIGEN_ALIGN16;
151+
152+
POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIRPYT,
153+
(float, x, x) (float, y, y)
154+
(float, z, z) (float, intensity, intensity)
155+
(float, roll, roll) (float, pitch, pitch) (float, yaw, yaw)
156+
(double, time, time)
157+
)
158+
159+
typedef PointXYZIRPYT PointTypePose;
160+
161+
#endif

LeGO-LOAM/launch/block.png

31.8 KB
Loading

LeGO-LOAM/launch/dataset-demo.gif

3.54 MB
Loading

LeGO-LOAM/launch/demo.gif

18.3 MB
Loading

LeGO-LOAM/launch/google-earth.png

926 KB
Loading

LeGO-LOAM/launch/jackal-label.jpg

31.6 KB
Loading

LeGO-LOAM/launch/odometry.jpg

21.6 KB
Loading

LeGO-LOAM/launch/run.launch

+19
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
<launch>
2+
3+
<!--- Sim Time -->
4+
<param name="/use_sim_time" value="true" />
5+
6+
<!--- Run Rviz-->
7+
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find lego_loam)/launch/test.rviz" />
8+
9+
<!--- TF -->
10+
<node pkg="tf" type="static_transform_publisher" name="camera_init_to_map" args="0 0 0 1.570795 0 1.570795 /map /camera_init 10" />
11+
<node pkg="tf" type="static_transform_publisher" name="base_link_to_camera" args="0 0 0 -1.570795 -1.570795 0 /camera /base_link 10" />
12+
13+
<!--- LeGO-LOAM -->
14+
<node pkg="lego_loam" type="imageProjection" name="imageProjection" output="screen"/>
15+
<node pkg="lego_loam" type="featureAssociation" name="featureAssociation" output="screen"/>
16+
<node pkg="lego_loam" type="mapOptmization" name="mapOptmization" output="screen"/>
17+
<node pkg="lego_loam" type="transformFusion" name="transformFusion" output="screen"/>
18+
19+
</launch>

LeGO-LOAM/launch/seg-total.jpg

136 KB
Loading

0 commit comments

Comments
 (0)