Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions LeGO-LOAM/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 2.8.3)
project(lego_loam)

set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -O3")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -O3")

find_package(catkin REQUIRED COMPONENTS
tf
Expand All @@ -23,6 +23,7 @@ find_package(catkin REQUIRED COMPONENTS
find_package(GTSAM REQUIRED QUIET)
find_package(PCL REQUIRED QUIET)
find_package(OpenCV REQUIRED QUIET)
find_package(Boost REQUIRED thread serialization timer chrono)

catkin_package(
INCLUDE_DIRS include
Expand Down Expand Up @@ -57,4 +58,4 @@ 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})
target_link_libraries(transformFusion ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES})
23 changes: 16 additions & 7 deletions LeGO-LOAM/include/utility.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@

#include "cloud_msgs/cloud_info.h"

#include <opencv/cv.h>
//#include <opencv/cv.h>
#include <opencv2/opencv.hpp>

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
Expand Down Expand Up @@ -60,12 +61,12 @@ extern const string fileDirectory = "/tmp/";
extern const bool useCloudRing = true; // if true, ang_res_y and ang_bottom are not used

// VLP-16
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 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;

// HDL-32E
// extern const int N_SCAN = 32;
Expand All @@ -75,6 +76,14 @@ extern const int groundScanInd = 7;
// extern const float ang_bottom = 30.67;
// extern const int groundScanInd = 20;

extern const int N_SCAN = 32;
extern const int Horizon_SCAN = 220;
extern const float ang_res_x = 360.0/float(Horizon_SCAN);
extern const float ang_res_y = 41.33/float(N_SCAN-1);
extern const float ang_bottom = 30.67;
extern const int groundScanInd = 20;


// VLS-128
// extern const int N_SCAN = 128;
// extern const int Horizon_SCAN = 1800;
Expand Down
5 changes: 4 additions & 1 deletion LeGO-LOAM/launch/run.launch
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,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" />
<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 -->
<!--- LeGO-LOAM -->
<remap from="velodyne_points" to="velodyne_points2"/>
<!-- <remap from="imu/data" to="imu"/> -->

<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"/>
Expand Down