diff --git a/README.md b/README.md
index 066d63b..75a146d 100644
--- a/README.md
+++ b/README.md
@@ -6,7 +6,7 @@
-
+
@@ -24,7 +24,7 @@
Cyrill Stachniss
University of Bonn
-
+
@@ -66,6 +66,9 @@
Visualizer instructions
+
+ Citation
+
Contact
@@ -275,7 +278,7 @@ After playing the ROS bag or launching the sensor you can then visualize the res
rviz -d ./config/pin_slam_ros.rviz
```
-You may use the ROS service `save_results` and `save_mesh` to save the results and mesh in the `output_root` folder.
+You may use the ROS service `save_results` and `save_mesh` to save the results and mesh (at a default resolution) in the `output_root` folder.
```
rosservice call /pin_slam/save_results
@@ -352,6 +355,25 @@ We provide a PIN-SLAM visualizer based on [lidar-visualizer](https://github.com/
+## Citation
+
+If you use PIN-SLAM for any academic work, please cite our original [paper](https://www.ipb.uni-bonn.de/wp-content/papercite-data/pdf/pan2024tro.pdf).
+
+```
+@article{pan2024tro,
+author = {Y. Pan and X. Zhong and L. Wiesmann and T. Posewsky and J. Behley and C. Stachniss},
+title = {{PIN-SLAM: LiDAR SLAM Using a Point-Based Implicit Neural Representation for Achieving Global Map Consistency}},
+journal = IEEE Transactions on Robotics (TRO),
+year = {2024},
+volume = {},
+number = {},
+pages = {},
+codeurl = {https://github.com/PRBonn/PIN_SLAM},
+}
+```
+
+
+
## Contact
If you have any questions, please contact:
diff --git a/scripts/rosbag2ply.py b/scripts/rosbag2ply.py
index dc8ab0e..f99dd1f 100644
--- a/scripts/rosbag2ply.py
+++ b/scripts/rosbag2ply.py
@@ -4,12 +4,18 @@
import os
import argparse
import numpy as np
+import open3d as o3d
from module import ply
def rosbag2ply(args):
os.makedirs(args.output_folder, 0o755, exist_ok=True)
+
+ if args.output_pcd:
+ output_folder_pcd = args.output_folder+"_pcd"
+ os.makedirs(output_folder_pcd, 0o755, exist_ok=True)
+
begin_flag = False
@@ -48,6 +54,12 @@ def rosbag2ply(args):
else:
print('ply.write_ply() failed')
+ if args.output_pcd:
+ pcd = o3d.geometry.PointCloud()
+ pcd.points = o3d.utility.Vector3dVector(array[:, :3])
+ pcd_file_path = os.path.join(output_folder_pcd, str(t)+".pcd")
+ o3d.io.write_point_cloud(pcd_file_path, pcd)
+
if __name__ == "__main__":
@@ -55,6 +67,7 @@ def rosbag2ply(args):
parser.add_argument('-i','--input_bag', help="path to the input rosbag")
parser.add_argument('-o','--output_folder', help="path for output foler")
parser.add_argument('-t','--topic', help="name of the point cloud topic used in the rosbag", default="/hesai/pandar_points")
+ parser.add_argument('-p','--output_pcd', action='store_true', help='Also output the pcd file')
args = parser.parse_args()
print("usage: python3 rosbag2ply.py -i [path to input rosbag] -o [path to point cloud output folder] -t [name of point cloud rostopic]")