diff --git a/README.md b/README.md index 5b80a6e..4210141 100644 --- a/README.md +++ b/README.md @@ -61,7 +61,7 @@ This package was developed on Ubuntu 20.04 using ROS Noetic. Other versions shou ``` 4. Build COIN-LIO: ```bash - catkin build coin_lio + catkin build coin_lio --force-cmake ``` ## Alternative Installation: Docker @@ -104,8 +104,11 @@ If you are not using the built-in IMU in the Ouster LiDAR, you need to adapt the ### Run COIN-LIO with your own data Launch with settings for your data: ```bash - roslaunch coin_lio mapping.launch metadata_file:= column_shift:= point_topic:= imu_topic:= + roslaunch coin_lio mapping.launch metadata_file:= column_shift:= point_topic:= imu_topic:= destagger:= ``` + If your data already contains [destaggered point clouds from the ouster driver](https://github.com/ouster-lidar/ouster-ros/blob/55519ed2b8a7dd7d4ae13a968b0ec88e5cada7dd/launch/common.launch#L45), set `destagger:=false`, otherwise use `destagger:=true`. + + Play your data: ```bash rosbag play diff --git a/include/projector.h b/include/projector.h index 6ab19df..a614c0c 100644 --- a/include/projector.h +++ b/include/projector.h @@ -34,6 +34,7 @@ class Projector { std::vector idx_to_v_; std::vector idx_to_u_; M3D K_; + bool destagger_; }; #endif // COIN_LIO_PROJECTOR_H_ \ No newline at end of file diff --git a/launch/mapping.launch b/launch/mapping.launch index 0d21b5c..ed69c27 100644 --- a/launch/mapping.launch +++ b/launch/mapping.launch @@ -1,6 +1,7 @@ + @@ -13,6 +14,7 @@ + diff --git a/src/preprocess.cpp b/src/preprocess.cpp index 2e4d365..182cce5 100644 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -23,7 +23,7 @@ void Preprocess::ouster_handler(const sensor_msgs::PointCloud2::ConstPtr &msg, P pcl::uint64_t max_time = 0; for (size_t i = 0; i < pl_orig.points.size(); i++) { - + if(isnan(pl_orig.points[i].x) || isnan(pl_orig.points[i].y) || isnan(pl_orig.points[i].z)) continue; double range = pl_orig.points[i].getVector3fMap().norm(); if (range < blind) continue; diff --git a/src/projector.cpp b/src/projector.cpp index 607860b..3f4990c 100644 --- a/src/projector.cpp +++ b/src/projector.cpp @@ -90,6 +90,10 @@ void Projector::loadParameters(ros::NodeHandle nh) { return; } u_shift_ = static_cast(u_shift); + + // true: destagger the pointcloud data + // https://static.ouster.dev/sdk-docs/reference/lidar-scan.html#staggering-and-destaggering + nh.param("image/destagger", destagger_, true); } size_t Projector::vectorIndexFromRowCol(const size_t row, const size_t col) const { @@ -150,7 +154,7 @@ void Projector::createImages(LidarFrame& frame) const { size_t Projector::indexFromPixel(const V2D& px) const { const int vv = (int(px(1)) + cols_ - offset_lut_[int(px(0))]) % cols_; - const size_t index = px(0)* cols_ + vv; + const size_t index = px(0)* cols_ + (destagger_ ? vv : int(px(1))); return index; };