Skip to content
Merged
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
7 changes: 7 additions & 0 deletions cpp/bindings/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -267,6 +267,13 @@ inline void make_types(nb::module_& m) {
"List of points in the "
"point cloud. Note, this is always in row major format."
)
.def_static(
"from_vec_positions",
&LidarMeasurement::from_vec_positions,
"stamp"_a,
"positions"_a,
"Construct a LidarMeasurement from a stamp and a (n,3) numpy array."
)
.def(
"to_vec_positions",
&LidarMeasurement::to_vec_positions,
Expand Down
10 changes: 10 additions & 0 deletions cpp/evalio/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -218,6 +218,16 @@ struct LidarMeasurement {
return oss.str();
}

static LidarMeasurement
from_vec_positions(Stamp stamp, const Eigen::MatrixX3d& positions) {
std::vector<Point> pts;
pts.reserve(positions.rows());
for (const auto& p : positions.rowwise()) {
pts.push_back(Point {.x = p.x(), .y = p.y(), .z = p.z()});
}
return LidarMeasurement(stamp, pts);
}

std::vector<Eigen::Vector3d> to_vec_positions() const {
std::vector<Eigen::Vector3d> eigen_points;
eigen_points.reserve(points.size());
Expand Down
9 changes: 9 additions & 0 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,14 @@ build-backend = "scikit_build_core.build"
evalio = "evalio.cli:app"

# -------------- Tools -------------- #
[tool.uv]
cache-keys = [
{ file = "pyproject.toml" },
{ file = "cpp/**/*.{h,c,hpp,cpp}" },
{ file = "python/**/*.{cpp,py}" },
{ file = "CMakeLists.txt" },
]

# building
[tool.scikit-build]
minimum-version = "0.12"
Expand All @@ -49,6 +57,7 @@ sdist.include = ["cpp/bindings/pipelines-src/*"]

[tool.scikit-build.cmake.define]
EVALIO_BUILD_PYTHON = true
CMAKE_BUILD_TYPE = "RelWithDebInfo"
VCPKG_INSTALLED_DIR = "./.vcpkg_installed"
# VCPKG_INSTALL_OPTIONS = "--debug"

Expand Down
4 changes: 3 additions & 1 deletion python/evalio/cli/ls.py
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,9 @@ def ls(
)
else:
# sequences
all_info["Sequences"].append("\n".join(d.sequences()))
all_info["Sequences"].append(
"\n".join([v.seq_name for v in d.sequences()])
)
# downloaded
downloaded = [d(s).is_downloaded() for s in d.sequences()]
downloaded = "\n".join(
Expand Down
4 changes: 3 additions & 1 deletion python/evalio/cli/run.py
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,9 @@ def run(

# save ground truth if we haven't already
if not (gt_file := exp.file.parent / "gt.csv").exists():
exp.sequence.ground_truth().to_file(gt_file)
gt = exp.sequence.ground_truth()
if gt is not None:
gt.to_file(gt_file)

# Figure out the status of the experiment
traj = ty.Trajectory.from_file(exp.file)
Expand Down
19 changes: 8 additions & 11 deletions python/evalio/cli/stats.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,6 @@ def eval_dataset(
elif isinstance(traj.metadata, ty.Experiment):
all_trajs.append(cast(ty.Trajectory[ty.Experiment], traj))

if gt_og is None:
print_warning(f"No ground truth found in {dir}, skipping.")
return None

# Setup visualization
if visualize:
try:
Expand All @@ -67,11 +63,12 @@ def eval_dataset(
spawn=False,
)
rr.connect_grpc()
rr.log(
"gt",
convert(gt_og, color=GT_COLOR),
static=True,
)
if gt_og is not None:
rr.log(
"gt",
convert(gt_og, color=GT_COLOR),
static=True,
)

# generate colors for visualization
colors = distinctipy.get_colors(len(all_trajs) + 1)
Expand All @@ -86,7 +83,7 @@ def eval_dataset(
if traj.metadata.total_elapsed is not None:
hz = len(traj) / traj.metadata.total_elapsed

if len(traj) > 0:
if len(traj) > 0 and gt_og is not None:
# align to ground truth, copying ground truth by hand
gt_aligned = Trajectory(
stamps=[ty.Stamp(s) for s in gt_og.stamps],
Expand Down Expand Up @@ -296,7 +293,7 @@ def evaluate_typer(
else:
from asteval import Interpreter

filter_method = lambda r: Interpreter(user_symbols=r).eval(
filter_method = lambda r: Interpreter(user_symbols=r).eval( # type: ignore
filter_str, raise_errors=True
)

Expand Down
9 changes: 6 additions & 3 deletions python/evalio/datasets/base.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,14 +84,14 @@ def data_iter(self) -> DatasetIterator:
...

# Return the ground truth in the ground truth frame
def ground_truth_raw(self) -> Trajectory:
def ground_truth_raw(self) -> Optional[Trajectory]:
"""
Retrieves the raw ground truth trajectory, as represented in the ground truth frame.

Returns:
The raw ground truth trajectory data.
"""
...
return None

# ------------------------- For loading params ------------------------- #
def imu_T_lidar(self) -> SE3:
Expand Down Expand Up @@ -210,13 +210,16 @@ def is_downloaded(self) -> bool:

return True

def ground_truth(self) -> Trajectory[GroundTruth]:
def ground_truth(self) -> Optional[Trajectory[GroundTruth]]:
"""Get the ground truth trajectory in the **IMU** frame, rather than the ground truth frame as returned in [ground_truth_raw][evalio.datasets.Dataset.ground_truth_raw].

Returns:
The ground truth trajectory in the IMU frame.
"""
gt_traj = self.ground_truth_raw()
if gt_traj is None:
return None

gt_T_imu = self.imu_T_gt().inverse()

# Convert to IMU frame
Expand Down
4 changes: 2 additions & 2 deletions python/evalio/datasets/loaders.py
Original file line number Diff line number Diff line change
Expand Up @@ -368,8 +368,8 @@ def _step(iter: Iterator[T]) -> Optional[T]:
return None

def __iter__(self) -> Iterator[Measurement]:
self.next_imu = next(self.iter_imu)
self.next_lidar = next(self.iter_lidar)
self.next_imu = self._step(self.iter_imu)
self.next_lidar = self._step(self.iter_lidar)
return self

def __next__(self) -> Measurement:
Expand Down
13 changes: 7 additions & 6 deletions python/evalio/rerun.py
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,8 @@ def new_dataset(self, dataset: Dataset):
self.lidar_params = dataset.lidar_params()
self.imu_T_lidar = dataset.imu_T_lidar()

self.rec.log("gt", convert(self.gt, color=GT_COLOR), static=True)
if self.gt is not None:
self.rec.log("gt", convert(self.gt, color=GT_COLOR), static=True)

# reset other variables
self.pn = None
Expand Down Expand Up @@ -165,7 +166,7 @@ def log_scan(self, data: LidarMeasurement):
if self.args is None:
return

if self.lidar_params is None or self.gt is None:
if self.lidar_params is None:
raise ValueError("You needed to add a dataset before stepping!")
if self.pn is None or self.trajectory is None or self.colors is None:
raise ValueError("You needed to add a pipeline before stepping!")
Expand All @@ -192,13 +193,13 @@ def log_pose(self, stamp: Stamp, pose: SE3):
if self.args is None:
return

if self.lidar_params is None or self.gt is None:
if self.lidar_params is None:
raise ValueError("You needed to add a dataset before stepping!")
if self.pn is None or self.trajectory is None or self.colors is None:
raise ValueError("You needed to add a pipeline before stepping!")

# Find transform between ground truth and imu origins
if self.gt_o_T_imu_o is None:
if self.gt_o_T_imu_o is None and self.gt is not None:
# If we haven't hit ground truth data or the pose isn't being updated, wait
if stamp < self.gt.stamps[0] or pose == SE3.identity():
pass
Expand Down Expand Up @@ -231,7 +232,7 @@ def log_map(self, stamp: Stamp, map: dict[str, NDArray[np.float64]]):
if self.args is None:
return

if self.lidar_params is None or self.gt is None:
if self.lidar_params is None:
raise ValueError("You needed to add a pipeline before stepping!")
if self.pn is None or self.trajectory is None or self.colors is None:
raise ValueError("You needed to add a pipeline before stepping!")
Expand All @@ -247,7 +248,7 @@ def log_features(self, stamp: Stamp, features: dict[str, NDArray[np.float64]]):
if self.args is None:
return

if self.lidar_params is None or self.gt is None:
if self.lidar_params is None:
raise ValueError("You needed to add a pipeline before stepping!")
if self.pn is None or self.trajectory is None or self.colors is None:
raise ValueError("You needed to add a pipeline before stepping!")
Expand Down
Loading