forked from RobustFieldAutonomyLab/LeGO-LOAM
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
b2b3a62
commit c217ce3
Showing
14 changed files
with
4,666 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,60 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
project(lego_loam) | ||
|
||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3") | ||
|
||
find_package(catkin REQUIRED COMPONENTS | ||
tf | ||
roscpp | ||
rospy | ||
cv_bridge | ||
image_transport | ||
|
||
pcl_ros | ||
pcl_conversions | ||
|
||
std_msgs | ||
sensor_msgs | ||
geometry_msgs | ||
nav_msgs | ||
cloud_msgs | ||
) | ||
|
||
find_package(GTSAM REQUIRED QUIET) | ||
find_package(PCL REQUIRED QUIET) | ||
find_package(OpenCV REQUIRED QUIET) | ||
|
||
catkin_package( | ||
INCLUDE_DIRS include | ||
CATKIN_DEPENDS cloud_msgs | ||
DEPENDS PCL | ||
) | ||
|
||
include_directories( | ||
include | ||
${catkin_INCLUDE_DIRS} | ||
${PCL_INCLUDE_DIRS} | ||
${OpenCV_INCLUDE_DIRS} | ||
${GTSAM_INCLUDE_DIR} | ||
) | ||
|
||
link_directories( | ||
include | ||
${OpenCV_LIBRARY_DIRS} | ||
${PCL_LIBRARY_DIRS} | ||
${GTSAM_LIBRARY_DIRS} | ||
) | ||
|
||
add_executable(imageProjection src/imageProjection.cpp) | ||
add_dependencies(imageProjection ${catkin_EXPORTED_TARGETS} cloud_msgs_gencpp) | ||
target_link_libraries(imageProjection ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES}) | ||
|
||
add_executable(featureAssociation src/featureAssociation.cpp) | ||
add_dependencies(featureAssociation ${catkin_EXPORTED_TARGETS} cloud_msgs_gencpp) | ||
target_link_libraries(featureAssociation ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES}) | ||
|
||
add_executable(mapOptmization src/mapOptmization.cpp) | ||
target_link_libraries(mapOptmization ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} gtsam) | ||
|
||
add_executable(transformFusion src/transformFusion.cpp) | ||
target_link_libraries(transformFusion ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES}) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,125 @@ | ||
#ifndef _UTILITY_LIDAR_ODOMETRY_H_ | ||
#define _UTILITY_LIDAR_ODOMETRY_H_ | ||
|
||
|
||
#include <ros/ros.h> | ||
|
||
#include <sensor_msgs/Imu.h> | ||
#include <sensor_msgs/PointCloud2.h> | ||
#include <nav_msgs/Odometry.h> | ||
|
||
#include "cloud_msgs/cloud_info.h" | ||
|
||
#include <opencv/cv.h> | ||
|
||
#include <pcl/point_cloud.h> | ||
#include <pcl/point_types.h> | ||
#include <pcl_ros/point_cloud.h> | ||
#include <pcl_conversions/pcl_conversions.h> | ||
#include <pcl/range_image/range_image.h> | ||
#include <pcl/filters/filter.h> | ||
#include <pcl/filters/voxel_grid.h> | ||
#include <pcl/kdtree/kdtree_flann.h> | ||
#include <pcl/common/common.h> | ||
#include <pcl/registration/icp.h> | ||
|
||
#include <tf/transform_broadcaster.h> | ||
#include <tf/transform_datatypes.h> | ||
|
||
#include <vector> | ||
#include <cmath> | ||
#include <algorithm> | ||
#include <queue> | ||
#include <deque> | ||
#include <iostream> | ||
#include <fstream> | ||
#include <ctime> | ||
#include <cfloat> | ||
#include <iterator> | ||
#include <sstream> | ||
#include <string> | ||
#include <limits> | ||
#include <iomanip> | ||
#include <array> | ||
#include <thread> | ||
#include <mutex> | ||
|
||
#define PI 3.14159265 | ||
|
||
using namespace std; | ||
|
||
typedef pcl::PointXYZI PointType; | ||
|
||
extern const int N_SCAN = 16; | ||
extern const int Horizon_SCAN = 1800; | ||
extern const float ang_res_x = 0.2; | ||
extern const float ang_res_y = 2.0; | ||
extern const float ang_bottom = 15.0+0.1; | ||
extern const int groundScanInd = 7; | ||
|
||
extern const bool loopClosureEnableFlag = false; | ||
extern const double mappingProcessInterval = 0.3; | ||
|
||
extern const float scanPeriod = 0.1; | ||
extern const int systemDelay = 0; | ||
extern const int imuQueLength = 200; | ||
extern const string imuTopic = "/imu/data"; | ||
|
||
|
||
extern const float sensorMountAngle = 0.0; | ||
extern const float segmentTheta = 1.0472; | ||
extern const int segmentValidPointNum = 5; | ||
extern const int segmentValidLineNum = 3; | ||
extern const float segmentAlphaX = ang_res_x / 180.0 * M_PI; | ||
extern const float segmentAlphaY = ang_res_y / 180.0 * M_PI; | ||
|
||
|
||
extern const int edgeFeatureNum = 2; | ||
extern const int surfFeatureNum = 4; | ||
extern const int sectionsTotal = 6; | ||
extern const float edgeThreshold = 0.1; | ||
extern const float surfThreshold = 0.1; | ||
extern const float nearestFeatureSearchSqDist = 25; | ||
|
||
extern const float surroundingKeyframeSearchRadius = 50.0; | ||
extern const int surroundingKeyframeSearchNum = 50; | ||
|
||
extern const float historyKeyframeSearchRadius = 5.0; | ||
extern const int historyKeyframeSearchNum = 25; | ||
extern const float historyKeyframeFitnessScore = 0.3; | ||
|
||
extern const float globalMapVisualizationSearchRadius = 50.0; | ||
|
||
|
||
struct smoothness_t{ | ||
float value; | ||
size_t ind; | ||
}; | ||
|
||
struct by_value{ | ||
bool operator()(smoothness_t const &left, smoothness_t const &right) { | ||
return left.value < right.value; | ||
} | ||
}; | ||
|
||
struct PointXYZIRPYT | ||
{ | ||
PCL_ADD_POINT4D | ||
PCL_ADD_INTENSITY; | ||
float roll; | ||
float pitch; | ||
float yaw; | ||
double time; | ||
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||
} EIGEN_ALIGN16; | ||
|
||
POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIRPYT, | ||
(float, x, x) (float, y, y) | ||
(float, z, z) (float, intensity, intensity) | ||
(float, roll, roll) (float, pitch, pitch) (float, yaw, yaw) | ||
(double, time, time) | ||
) | ||
|
||
typedef PointXYZIRPYT PointTypePose; | ||
|
||
#endif |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,19 @@ | ||
<launch> | ||
|
||
<!--- Sim Time --> | ||
<param name="/use_sim_time" value="true" /> | ||
|
||
<!--- Run Rviz--> | ||
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find lego_loam)/launch/test.rviz" /> | ||
|
||
<!--- TF --> | ||
<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" /> | ||
<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" /> | ||
|
||
<!--- LeGO-LOAM --> | ||
<node pkg="lego_loam" type="imageProjection" name="imageProjection" output="screen"/> | ||
<node pkg="lego_loam" type="featureAssociation" name="featureAssociation" output="screen"/> | ||
<node pkg="lego_loam" type="mapOptmization" name="mapOptmization" output="screen"/> | ||
<node pkg="lego_loam" type="transformFusion" name="transformFusion" output="screen"/> | ||
|
||
</launch> |
Oops, something went wrong.