Skip to content

Commit

Permalink
add kitti_helper and other changes
Browse files Browse the repository at this point in the history
  • Loading branch information
shaozu committed Mar 7, 2019
1 parent 19d38f9 commit 94ee325
Show file tree
Hide file tree
Showing 11 changed files with 954 additions and 11 deletions.
1 change: 1 addition & 0 deletions .gitignore
@@ -0,0 +1 @@
.vscode/
12 changes: 10 additions & 2 deletions CMakeLists.txt
Expand Up @@ -11,8 +11,12 @@ find_package(catkin REQUIRED COMPONENTS
sensor_msgs
roscpp
rospy
rosbag
std_msgs
tf)
image_transport
cv_bridge
tf
)

#find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)
Expand All @@ -23,7 +27,8 @@ include_directories(
include
${catkin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS})
${CERES_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS})

catkin_package(
CATKIN_DEPENDS geometry_msgs nav_msgs roscpp rospy std_msgs
Expand All @@ -41,6 +46,9 @@ target_link_libraries(laserOdometry ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES
add_executable(laserMapping src/laserMapping.cpp)
target_link_libraries(laserMapping ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES_LIBRARIES})

add_executable(kittiHelper src/kittiHelper.cpp)
target_link_libraries(kittiHelper ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBS})




6 changes: 3 additions & 3 deletions README.md
Expand Up @@ -5,7 +5,7 @@
A-LOAM is an Advanced implenmentation of LOAM (J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), which uses Eigen and Ceres to Solver to simplify code structure. This code is modified from [LOAM_NOTED](https://github.com/cuitaixiang/LOAM_NOTED).


**Authors:** [Tong Qin](http://www.qintonguav.com), [Shaozu Cao](https://github.com/shaozu/LOAM_NOTED), and [Shaojie Shen](http://www.ece.ust.hk/ece.php/profile/facultydetail/eeshaojie) from the [Aerial Robotics Group](http://uav.ust.hk/), [HKUST](https://www.ust.hk/)
**Authors:** [Tong Qin](http://www.qintonguav.com), [Shaozu Cao](https://github.com/shaozu), and [Shaojie Shen](http://www.ece.ust.hk/ece.php/profile/facultydetail/eeshaojie) from the [Aerial Robotics Group](http://uav.ust.hk/), [HKUST](https://www.ust.hk/)


## 1. Prerequisites
Expand Down Expand Up @@ -42,10 +42,10 @@ Download [NSH indoor outdoor](https://drive.google.com/file/d/1s05tBQOLNEDDurlg4


## 4. KITTI Example (Velodyne HDL-64)
Download [KITTI Odometry dataset](http://www.cvlibs.net/datasets/kitti/eval_odometry.php) to YOUR_DATASET_FOLDER, and convert it into ROS bag. We take sequences 00 for example. [00](download link)
Download [KITTI Odometry dataset](http://www.cvlibs.net/datasets/kitti/eval_odometry.php) to YOUR_DATASET_FOLDER and set the `dataset_folder` and `sequence_number` parameters in `kitti_helper.launch` file. Note you also convert KITTI dataset to bag file for easy use by setting proper parameters in `kitti_helper.launch`.

```
roslaunch loam_velodyne loam_velodyne_64.launch
rosbag play YOUR_DATASET_FOLDER/00.bag
roslaunch loam_velodyne kitti_helper.launch
```

11 changes: 11 additions & 0 deletions launch/kitti_helper.launch
@@ -0,0 +1,11 @@
<launch>


<node name="loam_velodyne" pkg="loam_velodyne" type="kittiHelper" output="screen">
<param name="dataset_folder" type="string" value="/data/KITTI/odometry/" />
<param name="sequence_number" type="string" value="00" />
<param name="to_bag" type="bool" value="false" />
<param name="output_bag_file" type="string" value="/tmp/kitti.bag" /> <!-- replace with your output folder -->
<param name="publish_delay" type="int" value="1" />
</node>
</launch>
4 changes: 2 additions & 2 deletions launch/loam_velodyne_16.launch
Expand Up @@ -18,9 +18,9 @@

<node pkg="loam_velodyne" type="laserMapping" name="laserMapping" output="screen" />

<arg name="rviz" default="true" />
<arg name="rviz" default="false" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find loam_velodyne)/rviz_cfg/loam_velodyne.rviz" />
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find loam_velodyne)/rviz_cfg/loam_velodyne_16.rviz" />
</group>

</launch>
4 changes: 2 additions & 2 deletions launch/loam_velodyne_64.launch
Expand Up @@ -18,9 +18,9 @@

<node pkg="loam_velodyne" type="laserMapping" name="laserMapping" output="screen" />

<arg name="rviz" default="true" />
<arg name="rviz" default="false" />
<group if="$(arg rviz)">
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find loam_velodyne)/rviz_cfg/loam_velodyne.rviz" />
<node launch-prefix="nice" pkg="rviz" type="rviz" name="rviz" args="-d $(find loam_velodyne)/rviz_cfg/loam_velodyne_64.rviz" />
</group>

</launch>
6 changes: 5 additions & 1 deletion package.xml
Expand Up @@ -21,17 +21,21 @@
<build_depend>nav_msgs</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>rosbag</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>image_transport</build_depend>

<run_depend>geometry_msgs</run_depend>
<run_depend>nav_msgs</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>rospy</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>rosbag</run_depend>
<run_depend>tf</run_depend>
<run_depend>image_transport</run_depend>

<export>
</export>
Expand Down
File renamed without changes.

0 comments on commit 94ee325

Please sign in to comment.