Skip to content

Enhancement changes #293

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 7 commits into
base: master
Choose a base branch
from
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++17 -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 COMPONENTS timer thread serialization 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})
11 changes: 6 additions & 5 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 <pcl/kdtree/kdtree_flann.h>
#include <opencv2/opencv.hpp>

#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
Expand Down Expand Up @@ -50,14 +51,14 @@ using namespace std;

typedef pcl::PointXYZI PointType;

extern const string pointCloudTopic = "/velodyne_points";
extern const string imuTopic = "/imu/data";
extern const string pointCloudTopic = "/mid/points";
extern const string imuTopic = "/imu/imu_and_mag";

// Save pcd
extern const string fileDirectory = "/tmp/";

// Using velodyne cloud "ring" channel for image projection (other lidar may have different name for this channel, change "PointXYZIR" below)
extern const bool useCloudRing = true; // if true, ang_res_y and ang_bottom are not used
extern const bool useCloudRing = false; // if true, ang_res_y and ang_bottom are not used

// VLP-16
extern const int N_SCAN = 16;
Expand Down Expand Up @@ -101,7 +102,7 @@ extern const int groundScanInd = 7;
// extern const float ang_bottom = 16.6+0.1;
// extern const int groundScanInd = 15;

extern const bool loopClosureEnableFlag = false;
extern const bool loopClosureEnableFlag = true;
extern const double mappingProcessInterval = 0.3;

extern const float scanPeriod = 0.1;
Expand Down
13 changes: 9 additions & 4 deletions LeGO-LOAM/launch/run.launch
Original file line number Diff line number Diff line change
@@ -1,17 +1,22 @@
<launch>

<!--- Sim Time -->
<param name="/use_sim_time" value="true" />
<!-- <param name="/use_sim_time" value="true" /> -->
<arg name="imu_topic" default="/imu/data"/>
<arg name="point_cloud_topic" default="/mid/points"/>

<!--- 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" />
<node pkg="tf" type="static_transform_publisher" name="camera_init_to_odom" args="0 0 0 1.570795 0 1.570795 odom 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="imageProjection" name="imageProjection" output="screen">
<remap from="/mid/points" to="$(arg point_cloud_topic)"/>
<remap from="/imu/data" to="$(arg imu_topic)"/>
</node>
<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"/>
Expand Down
Loading