iterative closest points
CEV ICP algorithm library
Loading...
Searching...
No Matches
rosbag_extract.py
Go to the documentation of this file.
1import argparse
2import os
3
4import matplotlib
5import numpy as np
6import pandas as pd
7from bagpy import bagreader
8from matplotlib import pyplot as plt
9
10parser = argparse.ArgumentParser(
11 prog="rosbag_extract",
12 description="Extract LiDAR data from ROS bags to use in ICP testing",
13)
14parser.add_argument(
15 "-i",
16 "--input",
17 type=str,
18 help="Input ROS bag file",
19 required=True,
20)
21parser.add_argument(
22 "-o",
23 "--output_dir",
24 type=str,
25 help="Output directory to save the extracted scans",
26 required=True,
27)
28parser.add_argument(
29 "-t",
30 "--topic",
31 type=str,
32 help="Topic name to extract",
33 required=True,
34)
35args = parser.parse_args()
36
37os.makedirs(args.output_dir, exist_ok=True)
38
39b = bagreader(args.input)
40LASER_MSG = b.message_by_topic(args.topic)
41df = pd.read_csv(LASER_MSG)
42
43current_i = 0
44exported = 0
45
46
47def on_press(event):
48 global current_i
49 if event.key == "l":
50 current_i = min(current_i + 1, len(df) - 1)
51 elif event.key == "h":
52 current_i = max(current_i - 1, 0)
53 elif event.key == "p":
54 current_i = min(current_i + 10, len(df) - 1)
55 elif event.key == "u":
56 current_i = max(current_i - 10, 0)
57 elif event.key == "e":
58 save(current_i)
59 draw(current_i)
60
61
62def get_ranges(row):
63 ranges = []
64 i = 0
65 while True:
66 if f"ranges_{i}" not in row:
67 break
68 ranges.append(row[f"ranges_{i}"])
69 i += 1
70 return np.array(ranges)
71
72
73def draw(index: int):
74 row = df.iloc[index]
75 ranges = get_ranges(row)
76
77 angle_increment = row["angle_increment"]
78 angle_min = row["angle_min"]
79 angle_max = row["angle_max"]
80 angles = np.arange(angle_min, angle_max + angle_increment, angle_increment)
81
82 x = np.cos(angles) * ranges
83 y = np.sin(angles) * ranges
84
85 ax.clear()
86 ax.set_xlabel("x")
87 ax.set_ylabel("y")
88 ax.set_aspect("equal")
89 ax.set_xscale("linear")
90 ax.set_yscale("linear")
91
92 lidar_max = df.iloc[0]["range_max"]
93 ax.set_xlim(-lidar_max, lidar_max)
94 ax.set_ylim(-lidar_max, lidar_max)
95 ax.plot(x, y, "o", linestyle="None")
96
97
98def save(index: int):
99 global exported
100 row = df.iloc[index]
101 angle_increment = row["angle_increment"]
102 angle_min = row["angle_min"]
103 angle_max = row["angle_max"]
104 range_min = row["range_min"]
105 range_max = row["range_max"]
106 ranges = get_ranges(row)
107 length = len(ranges)
108 with open(f"{args.output_dir}/scan_{exported}.conf", "w") as f:
109 f.write(f"angle_max = {angle_max}\n")
110 f.write(f"angle_min = {angle_min}\n")
111 f.write(f"angle_increment = {angle_increment}\n")
112 f.write(f"length = {length}\n")
113 f.write(f"range_max = {range_max}\n")
114 f.write(f"range_min = {range_min}\n")
115 for i, r in enumerate(ranges):
116 f.write(f"{i} = {r}\n")
117 print(f"Exported scan {exported}")
118 exported += 1
119
120
121matplotlib.use("qt5agg")
122fig, ax = plt.subplots()
123plt.ion()
124fig.canvas.mpl_connect("key_press_event", on_press)
125draw(current_i)
126plt.show(block=True)
draw(int index)
save(int index)