From 2b5d2f1c40ea0fba7c6c64095a71eb9fd1b7a842 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Wed, 29 Oct 2025 19:33:20 -0400 Subject: [PATCH 1/6] Add in conversion module --- cpp/bindings/pipelines/kiss_icp.h | 41 ++++++------------------------- cpp/evalio/CMakeLists.txt | 1 + cpp/evalio/convert/base.h | 7 ++++++ cpp/evalio/convert/eigen.h | 28 +++++++++++++++++++++ cpp/evalio/convert/sophus.h | 24 ++++++++++++++++++ 5 files changed, 67 insertions(+), 34 deletions(-) create mode 100644 cpp/evalio/convert/base.h create mode 100644 cpp/evalio/convert/eigen.h create mode 100644 cpp/evalio/convert/sophus.h diff --git a/cpp/bindings/pipelines/kiss_icp.h b/cpp/bindings/pipelines/kiss_icp.h index 681d4675..3475b919 100644 --- a/cpp/bindings/pipelines/kiss_icp.h +++ b/cpp/bindings/pipelines/kiss_icp.h @@ -1,40 +1,13 @@ #pragma once #include -#include +#include "evalio/convert/eigen.h" +#include "evalio/convert/sophus.h" #include "evalio/pipeline.h" #include "evalio/types.h" #include "kiss_icp/pipeline/KissICP.hpp" -inline evalio::Point to_evalio_point(Eigen::Vector3d point) { - return { - .x = point[0], - .y = point[1], - .z = point[2], - .intensity = 0.0, - .t = evalio::Duration::from_sec(0), - .row = 0, - .col = 0 - }; -} - -inline Eigen::Vector3d to_eigen_point(evalio::Point point) { - return {point.x, point.y, point.z}; -} - -inline evalio::SE3 to_evalio_se3(Sophus::SE3d pose) { - const auto t = pose.translation(); - const auto q = pose.unit_quaternion(); - const auto rot = - evalio::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; - return evalio::SE3(rot, t); -} - -inline Sophus::SE3d to_sophus_se3(evalio::SE3 pose) { - return Sophus::SE3d(Sophus::SO3d(pose.rot.toEigen()), pose.trans); -} - class KissICP: public evalio::Pipeline { public: KissICP() : config_() {} @@ -66,7 +39,7 @@ class KissICP: public evalio::Pipeline { // Getters const evalio::SE3 pose() override { const Sophus::SE3d pose = kiss_icp_->pose() * lidar_T_imu_; - return to_evalio_se3(pose); + return evalio::convert(pose); } const std::map> map() override { @@ -74,7 +47,7 @@ class KissICP: public evalio::Pipeline { std::vector evalio_map; evalio_map.reserve(map.size()); for (auto point : map) { - evalio_map.push_back(to_evalio_point(point)); + evalio_map.push_back(evalio::convert(point)); } return {{"point", evalio_map}}; } @@ -88,7 +61,7 @@ class KissICP: public evalio::Pipeline { } void set_imu_T_lidar(evalio::SE3 T) override { - lidar_T_imu_ = to_sophus_se3(T).inverse(); + lidar_T_imu_ = evalio::convert(T).inverse(); } // Doers @@ -108,7 +81,7 @@ class KissICP: public evalio::Pipeline { // Copy for (auto point : mm.points) { - points.push_back(to_eigen_point(point)); + points.push_back(evalio::convert(point)); timestamps.push_back(point.t.to_sec()); } @@ -117,7 +90,7 @@ class KissICP: public evalio::Pipeline { std::vector result; result.reserve(used_points.size()); for (auto point : used_points) { - result.push_back(to_evalio_point(point)); + result.push_back(evalio::convert(point)); } return {{"point", result}}; } diff --git a/cpp/evalio/CMakeLists.txt b/cpp/evalio/CMakeLists.txt index 4bd522f0..030ab4eb 100644 --- a/cpp/evalio/CMakeLists.txt +++ b/cpp/evalio/CMakeLists.txt @@ -17,6 +17,7 @@ install(TARGETS evalio EXPORT evalioConfig) install(EXPORT evalioConfig DESTINATION "${CMAKE_INSTALL_DATADIR}/cmake/evalio") # headers +# TODO: Verify this is handling nested conversion files correctly install( DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR} diff --git a/cpp/evalio/convert/base.h b/cpp/evalio/convert/base.h new file mode 100644 index 00000000..37a2d910 --- /dev/null +++ b/cpp/evalio/convert/base.h @@ -0,0 +1,7 @@ +// Helper module for converting between the various library types. +#pragma once + +namespace evalio { +template +inline Out convert(const In& in) = delete; +} diff --git a/cpp/evalio/convert/eigen.h b/cpp/evalio/convert/eigen.h new file mode 100644 index 00000000..e9a9c91a --- /dev/null +++ b/cpp/evalio/convert/eigen.h @@ -0,0 +1,28 @@ +// Handle eigen conversions here. +#pragma once + +#include + +#include "evalio/convert/base.h" +#include "evalio/types.h" + +namespace evalio { +template<> +inline Point convert(const Eigen::Vector3d& in) { + return { + .x = in[0], + .y = in[1], + .z = in[2], + .intensity = 0.0, + .t = Duration::from_sec(0), + .row = 0, + .col = 0 + }; +} + +template<> +inline Eigen::Vector3d convert(const Point& in) { + return {in.x, in.y, in.z}; +} + +} // namespace evalio diff --git a/cpp/evalio/convert/sophus.h b/cpp/evalio/convert/sophus.h new file mode 100644 index 00000000..a57d6a28 --- /dev/null +++ b/cpp/evalio/convert/sophus.h @@ -0,0 +1,24 @@ +// Handle sophus conversions +#pragma once + +#include + +#include "evalio/convert/base.h" +#include "evalio/types.h" + +namespace evalio { +template<> +inline SE3 convert(const Sophus::SE3d& in) { + const auto t = in.translation(); + const auto q = in.unit_quaternion(); + const auto rot = + evalio::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; + return evalio::SE3(rot, t); +} + +template<> +inline Sophus::SE3d convert(const SE3& in) { + return Sophus::SE3d(Sophus::SO3d(in.rot.toEigen()), in.trans); +} + +} // namespace evalio From 5bc4663a5c3e46875ec9245a0f6ce23f58e54d7f Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Wed, 29 Oct 2025 20:32:20 -0400 Subject: [PATCH 2/6] Got vector conversions working as well! --- cpp/bindings/pipelines/kiss_icp.h | 24 +++++++----------------- cpp/evalio/convert/base.h | 26 ++++++++++++++++++++++++++ 2 files changed, 33 insertions(+), 17 deletions(-) diff --git a/cpp/bindings/pipelines/kiss_icp.h b/cpp/bindings/pipelines/kiss_icp.h index 3475b919..e5d043b0 100644 --- a/cpp/bindings/pipelines/kiss_icp.h +++ b/cpp/bindings/pipelines/kiss_icp.h @@ -73,26 +73,16 @@ class KissICP: public evalio::Pipeline { std::map> add_lidar(evalio::LidarMeasurement mm) override { - // Set everything up - std::vector points; - points.reserve(mm.points.size()); - std::vector timestamps; - timestamps.reserve(mm.points.size()); - - // Copy - for (auto point : mm.points) { - points.push_back(evalio::convert(point)); - timestamps.push_back(point.t.to_sec()); - } + // Convert inputs + std::vector points = + evalio::convert(mm.points); + std::vector timestamps = evalio::convert(mm.points); // Run through pipeline const auto& [_, used_points] = kiss_icp_->RegisterFrame(points, timestamps); - std::vector result; - result.reserve(used_points.size()); - for (auto point : used_points) { - result.push_back(evalio::convert(point)); - } - return {{"point", result}}; + + // Convert outputs + return {{"point", evalio::convert(used_points)}}; } private: diff --git a/cpp/evalio/convert/base.h b/cpp/evalio/convert/base.h index 37a2d910..0390cc74 100644 --- a/cpp/evalio/convert/base.h +++ b/cpp/evalio/convert/base.h @@ -1,7 +1,33 @@ // Helper module for converting between the various library types. #pragma once +#include + +#include "evalio/types.h" + namespace evalio { + +/// @brief Generic conversion function between types. +/// +/// Specializations may be imported from other files or defined by the user. template inline Out convert(const In& in) = delete; + +/// @brief Convert a vector of In to a vector of Out using convert(In). +template +inline std::vector convert(const std::vector& in) { + std::vector out; + out.reserve(in.size()); + for (const auto& item : in) { + out.push_back(convert(item)); + } + return out; +} + +/// @brief Convert evalio::Point to timestamps as doubles. +template<> +inline double convert(const evalio::Point& in) { + return in.t.to_sec(); } + +} // namespace evalio From 99b0a67be1e53c218f032c2e510b58965d09dfce Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Wed, 29 Oct 2025 20:41:27 -0400 Subject: [PATCH 3/6] Do it to genz as well --- cpp/bindings/pipelines/genz_icp.h | 84 ++++++++++--------------------- 1 file changed, 27 insertions(+), 57 deletions(-) diff --git a/cpp/bindings/pipelines/genz_icp.h b/cpp/bindings/pipelines/genz_icp.h index 7f879673..873e906e 100644 --- a/cpp/bindings/pipelines/genz_icp.h +++ b/cpp/bindings/pipelines/genz_icp.h @@ -1,7 +1,10 @@ #pragma once +#include #include +#include "evalio/convert/eigen.h" +#include "evalio/convert/sophus.h" #include "evalio/pipeline.h" #include "evalio/types.h" #include "genz_icp/pipeline/GenZICP.hpp" @@ -49,7 +52,7 @@ class GenZICP: public evalio::Pipeline { const evalio::SE3 pose() override { const auto pose = !genz_icp_->poses().empty() ? genz_icp_->poses().back() : Sophus::SE3d(); - return to_evalio_se3(pose * lidar_T_imu_); + return evalio::convert(pose * lidar_T_imu_); } const std::map> map() override { @@ -57,7 +60,7 @@ class GenZICP: public evalio::Pipeline { std::vector evalio_map; evalio_map.reserve(map.size()); for (auto point : map) { - evalio_map.push_back(to_evalio_point(point)); + evalio_map.push_back(evalio::convert(point)); } return {{"point", evalio_map}}; } @@ -72,7 +75,7 @@ class GenZICP: public evalio::Pipeline { } void set_imu_T_lidar(evalio::SE3 T) override { - lidar_T_imu_ = to_sophus_se3(T).inverse(); + lidar_T_imu_ = evalio::convert(T).inverse(); } // Doers @@ -85,70 +88,37 @@ class GenZICP: public evalio::Pipeline { std::map> add_lidar(evalio::LidarMeasurement mm) override { // Set everything up - std::vector points; - points.reserve(mm.points.size()); - std::vector timestamps; - timestamps.reserve(mm.points.size()); - - // Copy - for (auto point : mm.points) { - points.push_back(to_eigen_point(point)); - timestamps.push_back(point.t.to_sec()); - } + auto points = evalio::convert(mm.points); + auto timestamps = evalio::convert(mm.points); // Run through pipeline - const auto& [planar_points, nonplanar_points] = + auto [planar_points, nonplanar_points] = genz_icp_->RegisterFrame(points, timestamps); - const auto lidar_T_world = genz_icp_->poses().back().inverse(); + auto lidar_T_world = genz_icp_->poses().back().inverse(); - // Return the used points // These are all in the global frame, so we need to convert them - std::vector ev_planar_points; - ev_planar_points.reserve(planar_points.size()); - for (auto point : planar_points) { - ev_planar_points.push_back(to_evalio_point(lidar_T_world * point)); - } - - std::vector ev_nonplanar_points; - ev_nonplanar_points.reserve(nonplanar_points.size()); - for (auto point : nonplanar_points) { - ev_nonplanar_points.push_back(to_evalio_point(lidar_T_world * point)); - } + std::transform( + planar_points.begin(), + planar_points.end(), + planar_points.begin(), + [&](auto point) { return lidar_T_imu_ * point; } + ); + std::transform( + nonplanar_points.begin(), + nonplanar_points.end(), + nonplanar_points.begin(), + [&](auto point) { return lidar_T_imu_ * point; } + ); - return {{"nonplanar", ev_nonplanar_points}, {"planar", ev_planar_points}}; + // Return the used points + return { + {"nonplanar", evalio::convert(nonplanar_points)}, + {"planar", evalio::convert(planar_points)} + }; } private: std::unique_ptr genz_icp_; genz_icp::pipeline::GenZConfig config_; Sophus::SE3d lidar_T_imu_; - - // Misc helpers - inline evalio::Point to_evalio_point(Eigen::Vector3d point) { - return { - .x = point[0], - .y = point[1], - .z = point[2], - .intensity = 0.0, - .t = evalio::Duration::from_sec(0), - .row = 0, - .col = 0 - }; - } - - inline Eigen::Vector3d to_eigen_point(evalio::Point point) { - return {point.x, point.y, point.z}; - } - - inline evalio::SE3 to_evalio_se3(Sophus::SE3d pose) { - const auto t = pose.translation(); - const auto q = pose.unit_quaternion(); - const auto rot = - evalio::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; - return evalio::SE3(rot, t); - } - - inline Sophus::SE3d to_sophus_se3(evalio::SE3 pose) { - return Sophus::SE3d(Sophus::SO3d(pose.rot.toEigen()), pose.trans); - } }; From 2eadb0bec67f5b022dd351f236daae2ac2ca5309 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Thu, 30 Oct 2025 10:47:07 -0400 Subject: [PATCH 4/6] Clean up a few more pipelines with new conversions --- cpp/bindings/pipelines/genz_icp.h | 55 +++++++--------- cpp/bindings/pipelines/kiss_icp.h | 35 +++++----- cpp/bindings/pipelines/lio_sam.h | 106 ++++++++++++++++-------------- cpp/evalio/convert/base.h | 18 ++--- 4 files changed, 108 insertions(+), 106 deletions(-) diff --git a/cpp/bindings/pipelines/genz_icp.h b/cpp/bindings/pipelines/genz_icp.h index 873e906e..6923e3c4 100644 --- a/cpp/bindings/pipelines/genz_icp.h +++ b/cpp/bindings/pipelines/genz_icp.h @@ -3,13 +3,14 @@ #include #include -#include "evalio/convert/eigen.h" #include "evalio/convert/sophus.h" #include "evalio/pipeline.h" #include "evalio/types.h" #include "genz_icp/pipeline/GenZICP.hpp" -class GenZICP: public evalio::Pipeline { +namespace ev = evalio; + +class GenZICP: public ev::Pipeline { public: GenZICP() : config_() {} @@ -49,33 +50,28 @@ class GenZICP: public evalio::Pipeline { // clang-format on // Getters - const evalio::SE3 pose() override { + const ev::SE3 pose() override { const auto pose = !genz_icp_->poses().empty() ? genz_icp_->poses().back() : Sophus::SE3d(); - return evalio::convert(pose * lidar_T_imu_); + return ev::convert(pose * lidar_T_imu_); } - const std::map> map() override { + const std::map> map() override { std::vector map = genz_icp_->LocalMap(); - std::vector evalio_map; - evalio_map.reserve(map.size()); - for (auto point : map) { - evalio_map.push_back(evalio::convert(point)); - } - return {{"point", evalio_map}}; + return {{"point", ev::convert(map)}}; } // Setters - void set_imu_params(evalio::ImuParams params) override {} + void set_imu_params(ev::ImuParams params) override {} - void set_lidar_params(evalio::LidarParams params) override { + void set_lidar_params(ev::LidarParams params) override { config_.min_range = params.min_range; config_.max_range = params.max_range; config_.map_cleanup_radius = params.max_range; } - void set_imu_T_lidar(evalio::SE3 T) override { - lidar_T_imu_ = evalio::convert(T).inverse(); + void set_imu_T_lidar(ev::SE3 T) override { + lidar_T_imu_ = ev::convert(T).inverse(); } // Doers @@ -83,37 +79,36 @@ class GenZICP: public evalio::Pipeline { genz_icp_ = std::make_unique(config_); } - void add_imu(evalio::ImuMeasurement mm) override {} + void add_imu(ev::ImuMeasurement mm) override {} - std::map> - add_lidar(evalio::LidarMeasurement mm) override { + std::map> + add_lidar(ev::LidarMeasurement mm) override { // Set everything up - auto points = evalio::convert(mm.points); - auto timestamps = evalio::convert(mm.points); + auto points = ev::convert(mm.points); + auto timestamps = ev::convert(mm.points); // Run through pipeline - auto [planar_points, nonplanar_points] = - genz_icp_->RegisterFrame(points, timestamps); + auto [planar, nonplanar] = genz_icp_->RegisterFrame(points, timestamps); auto lidar_T_world = genz_icp_->poses().back().inverse(); // These are all in the global frame, so we need to convert them std::transform( - planar_points.begin(), - planar_points.end(), - planar_points.begin(), + planar.begin(), + planar.end(), + planar.begin(), [&](auto point) { return lidar_T_imu_ * point; } ); std::transform( - nonplanar_points.begin(), - nonplanar_points.end(), - nonplanar_points.begin(), + nonplanar.begin(), + nonplanar.end(), + nonplanar.begin(), [&](auto point) { return lidar_T_imu_ * point; } ); // Return the used points return { - {"nonplanar", evalio::convert(nonplanar_points)}, - {"planar", evalio::convert(planar_points)} + {"nonplanar", ev::convert(nonplanar)}, + {"planar", ev::convert(planar)} }; } diff --git a/cpp/bindings/pipelines/kiss_icp.h b/cpp/bindings/pipelines/kiss_icp.h index e5d043b0..7206cc01 100644 --- a/cpp/bindings/pipelines/kiss_icp.h +++ b/cpp/bindings/pipelines/kiss_icp.h @@ -8,7 +8,9 @@ #include "evalio/types.h" #include "kiss_icp/pipeline/KissICP.hpp" -class KissICP: public evalio::Pipeline { +namespace ev = evalio; + +class KissICP: public ev::Pipeline { public: KissICP() : config_() {} @@ -37,31 +39,31 @@ class KissICP: public evalio::Pipeline { ); // Getters - const evalio::SE3 pose() override { + const ev::SE3 pose() override { const Sophus::SE3d pose = kiss_icp_->pose() * lidar_T_imu_; - return evalio::convert(pose); + return ev::convert(pose); } - const std::map> map() override { + const std::map> map() override { std::vector map = kiss_icp_->LocalMap(); - std::vector evalio_map; + std::vector evalio_map; evalio_map.reserve(map.size()); for (auto point : map) { - evalio_map.push_back(evalio::convert(point)); + evalio_map.push_back(ev::convert(point)); } return {{"point", evalio_map}}; } // Setters - void set_imu_params(evalio::ImuParams params) override {} + void set_imu_params(ev::ImuParams params) override {} - void set_lidar_params(evalio::LidarParams params) override { + void set_lidar_params(ev::LidarParams params) override { config_.max_range = params.max_range; config_.min_range = params.min_range; } - void set_imu_T_lidar(evalio::SE3 T) override { - lidar_T_imu_ = evalio::convert(T).inverse(); + void set_imu_T_lidar(ev::SE3 T) override { + lidar_T_imu_ = ev::convert(T).inverse(); } // Doers @@ -69,20 +71,19 @@ class KissICP: public evalio::Pipeline { kiss_icp_ = std::make_unique(config_); } - void add_imu(evalio::ImuMeasurement mm) override {} + void add_imu(ev::ImuMeasurement mm) override {} - std::map> - add_lidar(evalio::LidarMeasurement mm) override { + std::map> + add_lidar(ev::LidarMeasurement mm) override { // Convert inputs - std::vector points = - evalio::convert(mm.points); - std::vector timestamps = evalio::convert(mm.points); + auto points = ev::convert(mm.points); + auto timestamps = ev::convert(mm.points); // Run through pipeline const auto& [_, used_points] = kiss_icp_->RegisterFrame(points, timestamps); // Convert outputs - return {{"point", evalio::convert(used_points)}}; + return {{"point", ev::convert(used_points)}}; } private: diff --git a/cpp/bindings/pipelines/lio_sam.h b/cpp/bindings/pipelines/lio_sam.h index 8be5b441..42ea5fdb 100644 --- a/cpp/bindings/pipelines/lio_sam.h +++ b/cpp/bindings/pipelines/lio_sam.h @@ -3,50 +3,68 @@ #include #include -#include #include #include "LIO-SAM/lio-sam.h" #include "LIO-SAM/types.h" +#include "evalio/convert/base.h" #include "evalio/pipeline.h" #include "evalio/types.h" -inline void -to_evalio_point(evalio::Point& ev_point, const lio_sam::PointXYZIRT& ls_point) { - ev_point.x = ls_point.x; - ev_point.y = ls_point.y; - ev_point.z = ls_point.z; - ev_point.intensity = ls_point.intensity; - ev_point.t = evalio::Duration::from_sec(ls_point.time); - ev_point.row = ls_point.ring; +// ------------------------- Fill out some converters for custom types ------------------------- // +namespace evalio { +// Point conversions +template<> +inline Point convert(const lio_sam::PointXYZIRT& in) { + return Point { + .x = in.x, + .y = in.y, + .z = in.z, + .intensity = in.intensity, + .t = evalio::Duration::from_sec(in.time), + .row = static_cast(in.ring) + }; } -inline void -to_evalio_point(evalio::Point& ev_point, const lio_sam::PointType& ls_point) { - ev_point.x = ls_point.x; - ev_point.y = ls_point.y; - ev_point.z = ls_point.z; - ev_point.intensity = ls_point.intensity; +template<> +inline Point convert(const lio_sam::PointType& in) { + return Point {.x = in.x, .y = in.y, .z = in.z, .intensity = in.intensity}; } -inline void -to_pcl_point(lio_sam::PointXYZIRT& ls_point, const evalio::Point& ev_point) { - ls_point.x = ev_point.x; - ls_point.y = ev_point.y; - ls_point.z = ev_point.z; - ls_point.intensity = ev_point.intensity; - ls_point.time = ev_point.t.to_sec(); - ls_point.ring = ev_point.row; +template<> +inline lio_sam::PointXYZIRT convert(const evalio::Point& in) { + return lio_sam::PointXYZIRT { + .x = static_cast(in.x), + .y = static_cast(in.y), + .z = static_cast(in.z), + .intensity = static_cast(in.intensity), + .ring = static_cast(in.row), + .time = static_cast(in.t.to_sec()), + }; } -inline evalio::SE3 to_evalio_se3(lio_sam::Odometry pose) { - const auto t = pose.position; - const auto q = pose.orientation; +// IMU conversions +template<> +inline lio_sam::Imu convert(const evalio::ImuMeasurement& in) { + return lio_sam::Imu { + .stamp = in.stamp.to_sec(), + .gyro = in.gyro, + .acc = in.accel + }; +} + +// SE3 conversions +template<> +inline evalio::SE3 convert(const lio_sam::Odometry& in) { + const auto t = in.position; + const auto q = in.orientation; const auto rot = evalio::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; return evalio::SE3(rot, t); } +} // namespace evalio +// ------------------------- The pipeline impl ------------------------- // class LioSam: public evalio::Pipeline { public: LioSam() : config_(), lidar_T_imu_(evalio::SE3::identity()) {} @@ -99,16 +117,14 @@ class LioSam: public evalio::Pipeline { // Getters const evalio::SE3 pose() override { - return to_evalio_se3(lio_sam_->getPose()) * lidar_T_imu_; + return evalio::convert(lio_sam_->getPose()) * lidar_T_imu_; } const std::map> map() override { - auto map = lio_sam_->getMap(); - std::vector evalio_map(map->size()); - for (std::size_t i = 0; i < map->size(); ++i) { - to_evalio_point(evalio_map[i], map->at(i)); - } - return {{"point", evalio_map}}; + return { + {"point", + evalio::convert(*lio_sam_->getMap())} + }; } // Setters @@ -139,35 +155,23 @@ class LioSam: public evalio::Pipeline { } void add_imu(evalio::ImuMeasurement mm) override { - lio_sam::Imu imuMsg { - .stamp = mm.stamp.to_sec(), - .gyro = mm.gyro, - .acc = mm.accel - }; - lio_sam_->addImuMeasurement(imuMsg); + lio_sam_->addImuMeasurement(evalio::convert(mm)); } std::map> add_lidar(evalio::LidarMeasurement mm) override { // Set everything up - pcl::PointCloud::Ptr cloud; - cloud.reset(new pcl::PointCloud); - cloud->points.resize(mm.points.size()); - - // Convert to pcl - for (size_t i = 0; i < mm.points.size(); ++i) { - to_pcl_point(cloud->points[i], mm.points[i]); - } + auto cloud = + evalio::convert(mm.points) + // NOTE: This likely causes a copy, see if we can avoid that later + .makeShared(); // Run through pipeline lio_sam_->addLidarMeasurement(mm.stamp.to_sec(), cloud); // Return features auto used_points = lio_sam_->getMostRecentFrame(); - std::vector result(used_points->points.size()); - for (size_t i = 0; i < used_points->points.size(); ++i) { - to_evalio_point(result[i], used_points->points[i]); - } + auto result = evalio::convert(*used_points); return {{"point", result}}; } diff --git a/cpp/evalio/convert/base.h b/cpp/evalio/convert/base.h index 0390cc74..f3498e9a 100644 --- a/cpp/evalio/convert/base.h +++ b/cpp/evalio/convert/base.h @@ -1,25 +1,27 @@ // Helper module for converting between the various library types. #pragma once -#include - #include "evalio/types.h" namespace evalio { /// @brief Generic conversion function between types. /// -/// Specializations may be imported from other files or defined by the user. +/// Overloads and specializations may be imported from other files or defined by the user. template inline Out convert(const In& in) = delete; -/// @brief Convert a vector of In to a vector of Out using convert(In). -template -inline std::vector convert(const std::vector& in) { - std::vector out; +/// @brief Convert a container of In to a container of Out using convert(in). +template< + template class OutCont, + class Out, + template class InCont, + class In> +inline OutCont convert(const InCont& in) { + OutCont out; out.reserve(in.size()); for (const auto& item : in) { - out.push_back(convert(item)); + out.push_back(convert(item)); } return out; } From 2979d15b45f7a2827366d4d2b23d91b1b0b1ae46 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Thu, 30 Oct 2025 11:40:43 -0400 Subject: [PATCH 5/6] Move all of binding conversion over to new convert function --- cpp/bindings/pipelines/ct_icp.h | 142 +++++++++++++++--------------- cpp/bindings/pipelines/genz_icp.h | 8 +- cpp/bindings/pipelines/kiss_icp.h | 12 +-- cpp/bindings/pipelines/lio_sam.h | 56 ++++++------ cpp/bindings/pipelines/loam.h | 65 +++++++------- cpp/bindings/pipelines/mad_icp.h | 82 +++++------------ cpp/evalio/convert/base.h | 17 ++++ cpp/evalio/convert/eigen.h | 15 ++++ 8 files changed, 192 insertions(+), 205 deletions(-) diff --git a/cpp/bindings/pipelines/ct_icp.h b/cpp/bindings/pipelines/ct_icp.h index 76d3513d..5af2f854 100644 --- a/cpp/bindings/pipelines/ct_icp.h +++ b/cpp/bindings/pipelines/ct_icp.h @@ -5,9 +5,44 @@ #include "ct_icp/odometry.hpp" #include "ct_icp/types.hpp" +#include "evalio/convert/eigen.h" #include "evalio/pipeline.h" #include "evalio/types.h" +namespace ev = evalio; + +// ------------------------- Handle all conversions ------------------------- // +namespace evalio { +template<> +inline evalio::Point convert(const ct_icp::Point3D& from) { + return ev::Point { + .x = from.raw_pt.x(), + .y = from.raw_pt.y(), + .z = from.raw_pt.z(), + .intensity = 0.0, + .t = ev::Duration::from_nsec(0), + .row = 0, + .col = 0, + }; +} + +template<> +inline ct_icp::Point3D convert(const evalio::Point& from) { + ct_icp::Point3D to; + to.raw_pt = Eigen::Vector3d(from.x, from.y, from.z); + to.pt = to.raw_pt; + to.alpha_timestamp = from.t.to_sec(); + to.index_frame = 0; + return to; +} + +template<> +inline evalio::SE3 convert(const ct_icp::TrajectoryFrame& in) { + return ev::SE3(ev::SO3::fromMat(in.begin_R), in.begin_t); +} +} // namespace evalio + +// ------------------------- Actual Wrapper ------------------------- // // Simple enum wrapper to parse all strings -> enum options struct CTICPEnumParams { std::string motion_compensation; @@ -91,44 +126,16 @@ struct CTICPEnumParams { } }; -class CTICP: public evalio::Pipeline { +class CTICP: public ev::Pipeline { private: std::unique_ptr ct_icp_; ct_icp::OdometryOptions config_ = ct_icp::OdometryOptions::DefaultDrivingProfile(); CTICPEnumParams enum_params_; - evalio::SE3 lidar_T_imu_ = evalio::SE3::identity(); + ev::SE3 lidar_T_imu_ = ev::SE3::identity(); size_t scan_idx_ = 0; - inline evalio::SE3 to_evalio_pose(const ct_icp::TrajectoryFrame& pose) const { - return evalio::SE3(evalio::SO3::fromMat(pose.begin_R), pose.begin_t); - } - - inline evalio::Point to_evalio_point(const ct_icp::Point3D& point) const { - return evalio::Point { - .x = point.raw_pt.x(), - .y = point.raw_pt.y(), - .z = point.raw_pt.z(), - .intensity = 0.0, - .t = evalio::Duration::from_nsec(0), - .row = 0, - .col = 0, - }; - } - - inline evalio::Point to_evalio_point(const Eigen::Vector3d& point) const { - return evalio::Point { - .x = point.x(), - .y = point.y(), - .z = point.z(), - .intensity = 0.0, - .t = evalio::Duration::from_nsec(0), - .row = 0, - .col = 0, - }; - } - public: CTICP() { config_.debug_print = false; @@ -196,29 +203,26 @@ class CTICP: public evalio::Pipeline { // clang-format on // Getters - const evalio::SE3 pose() override { + const ev::SE3 pose() override { const auto pose = ct_icp_->Trajectory().back(); - return to_evalio_pose(pose) * lidar_T_imu_; + return ev::convert(pose) * lidar_T_imu_; } - const std::map> map() override { - const auto map = ct_icp_->GetLocalMap(); - std::vector ev_points; - ev_points.reserve(map.size()); - for (const auto& point : map) { - ev_points.push_back(to_evalio_point(point)); - } - return {{"planar", std::move(ev_points)}}; + const std::map> map() override { + // TODO: Need to be able to handle custom allocators here + return ev::convert( + {} // {{"planar", ct_icp_->GetLocalMap()}} + ); } // Setters - void set_imu_params(evalio::ImuParams params) override {} + void set_imu_params(ev::ImuParams params) override {} - void set_lidar_params(evalio::LidarParams params) override { + void set_lidar_params(ev::LidarParams params) override { config_.max_distance = params.max_range; } - void set_imu_T_lidar(evalio::SE3 T) override { + void set_imu_T_lidar(ev::SE3 T) override { lidar_T_imu_ = T.inverse(); } @@ -228,49 +232,41 @@ class CTICP: public evalio::Pipeline { ct_icp_ = std::make_unique(config_); } - void add_imu(evalio::ImuMeasurement mm) override {} + void add_imu(ev::ImuMeasurement mm) override {} - std::map> - add_lidar(evalio::LidarMeasurement mm) override { - // Set everything up - std::vector pc; - pc.reserve(mm.points.size()); + std::map> + add_lidar(ev::LidarMeasurement mm) override { + // Convert + std::vector pc = + ev::convert(mm.points); - // Figure out min/max timesteps + // Normalize timestamps to [0, 1] const auto& [min, max] = std::minmax_element( - mm.points.cbegin(), - mm.points.cend(), - [](const evalio::Point& a, const evalio::Point& b) { return a.t < b.t; } + pc.cbegin(), + pc.cend(), + [](const ct_icp::Point3D& a, const ct_icp::Point3D& b) { + return a.alpha_timestamp < b.alpha_timestamp; + } ); - const auto min_t = min->t.to_sec(); - const auto max_t = max->t.to_sec(); - const auto normalize = [min_t, max_t](evalio::Duration t) { - return (t.to_sec() - min_t) / (max_t - min_t); + const auto min_t = min->alpha_timestamp; + const auto max_t = max->alpha_timestamp; + const auto normalize = [min_t, max_t](double t) { + return (t - min_t) / (max_t - min_t); }; // Copy - for (const auto& point : mm.points) { - ct_icp::Point3D p; - p.raw_pt = Eigen::Vector3d(point.x, point.y, point.z); - p.pt = p.raw_pt; - p.alpha_timestamp = normalize(point.t); - p.index_frame = scan_idx_; - pc.push_back(p); + for (auto& p : pc) { + p.alpha_timestamp = normalize(p.alpha_timestamp); } // Run through pipeline const auto summary = ct_icp_->RegisterFrame(pc); - - // Return the used points - std::vector ev_planar_points; - ev_planar_points.reserve(summary.keypoints.size()); - for (const auto& point : summary.keypoints) { - ev_planar_points.push_back(to_evalio_point(point)); - } - scan_idx_++; - return {{"planar", ev_planar_points}}; + // Return the used points + return ev::convert( + {{"planar", summary.keypoints}} + ); } }; diff --git a/cpp/bindings/pipelines/genz_icp.h b/cpp/bindings/pipelines/genz_icp.h index 6923e3c4..15ea18c8 100644 --- a/cpp/bindings/pipelines/genz_icp.h +++ b/cpp/bindings/pipelines/genz_icp.h @@ -3,6 +3,7 @@ #include #include +#include "evalio/convert/eigen.h" #include "evalio/convert/sophus.h" #include "evalio/pipeline.h" #include "evalio/types.h" @@ -106,10 +107,9 @@ class GenZICP: public ev::Pipeline { ); // Return the used points - return { - {"nonplanar", ev::convert(nonplanar)}, - {"planar", ev::convert(planar)} - }; + return ev::convert( + {{"planar", planar}, {"nonplanar", nonplanar}} + ); } private: diff --git a/cpp/bindings/pipelines/kiss_icp.h b/cpp/bindings/pipelines/kiss_icp.h index 7206cc01..29af62fc 100644 --- a/cpp/bindings/pipelines/kiss_icp.h +++ b/cpp/bindings/pipelines/kiss_icp.h @@ -45,13 +45,9 @@ class KissICP: public ev::Pipeline { } const std::map> map() override { - std::vector map = kiss_icp_->LocalMap(); - std::vector evalio_map; - evalio_map.reserve(map.size()); - for (auto point : map) { - evalio_map.push_back(ev::convert(point)); - } - return {{"point", evalio_map}}; + return ev::convert( + {{"point", kiss_icp_->LocalMap()}} + ); } // Setters @@ -83,7 +79,7 @@ class KissICP: public ev::Pipeline { const auto& [_, used_points] = kiss_icp_->RegisterFrame(points, timestamps); // Convert outputs - return {{"point", ev::convert(used_points)}}; + return ev::convert({{"point", used_points}}); } private: diff --git a/cpp/bindings/pipelines/lio_sam.h b/cpp/bindings/pipelines/lio_sam.h index 42ea5fdb..a4ab930d 100644 --- a/cpp/bindings/pipelines/lio_sam.h +++ b/cpp/bindings/pipelines/lio_sam.h @@ -11,6 +11,8 @@ #include "evalio/pipeline.h" #include "evalio/types.h" +namespace ev = evalio; + // ------------------------- Fill out some converters for custom types ------------------------- // namespace evalio { // Point conversions @@ -21,7 +23,7 @@ inline Point convert(const lio_sam::PointXYZIRT& in) { .y = in.y, .z = in.z, .intensity = in.intensity, - .t = evalio::Duration::from_sec(in.time), + .t = ev::Duration::from_sec(in.time), .row = static_cast(in.ring) }; } @@ -32,7 +34,7 @@ inline Point convert(const lio_sam::PointType& in) { } template<> -inline lio_sam::PointXYZIRT convert(const evalio::Point& in) { +inline lio_sam::PointXYZIRT convert(const ev::Point& in) { return lio_sam::PointXYZIRT { .x = static_cast(in.x), .y = static_cast(in.y), @@ -45,7 +47,7 @@ inline lio_sam::PointXYZIRT convert(const evalio::Point& in) { // IMU conversions template<> -inline lio_sam::Imu convert(const evalio::ImuMeasurement& in) { +inline lio_sam::Imu convert(const ev::ImuMeasurement& in) { return lio_sam::Imu { .stamp = in.stamp.to_sec(), .gyro = in.gyro, @@ -55,19 +57,18 @@ inline lio_sam::Imu convert(const evalio::ImuMeasurement& in) { // SE3 conversions template<> -inline evalio::SE3 convert(const lio_sam::Odometry& in) { +inline ev::SE3 convert(const lio_sam::Odometry& in) { const auto t = in.position; const auto q = in.orientation; - const auto rot = - evalio::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; - return evalio::SE3(rot, t); + const auto rot = ev::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; + return ev::SE3(rot, t); } } // namespace evalio // ------------------------- The pipeline impl ------------------------- // -class LioSam: public evalio::Pipeline { +class LioSam: public ev::Pipeline { public: - LioSam() : config_(), lidar_T_imu_(evalio::SE3::identity()) {} + LioSam() : config_(), lidar_T_imu_(ev::SE3::identity()) {} // Info static std::string version() { @@ -116,19 +117,18 @@ class LioSam: public evalio::Pipeline { // clang-format on // Getters - const evalio::SE3 pose() override { - return evalio::convert(lio_sam_->getPose()) * lidar_T_imu_; + const ev::SE3 pose() override { + return ev::convert(lio_sam_->getPose()) * lidar_T_imu_; } - const std::map> map() override { - return { - {"point", - evalio::convert(*lio_sam_->getMap())} - }; + const std::map> map() override { + return ev::convert( + {{"point", *lio_sam_->getMap()}} + ); } // Setters - void set_imu_params(evalio::ImuParams params) override { + void set_imu_params(ev::ImuParams params) override { config_.imuAccNoise = params.accel; config_.imuAccBiasN = params.accel_bias; config_.imuGyrNoise = params.gyro; @@ -136,14 +136,14 @@ class LioSam: public evalio::Pipeline { config_.imuGravity = params.gravity[2]; } - void set_lidar_params(evalio::LidarParams params) override { + void set_lidar_params(ev::LidarParams params) override { config_.N_SCAN = params.num_rows; config_.Horizon_SCAN = params.num_columns; config_.lidarMaxRange = params.max_range; config_.lidarMinRange = params.min_range; } - void set_imu_T_lidar(evalio::SE3 T) override { + void set_imu_T_lidar(ev::SE3 T) override { lidar_T_imu_ = T.inverse(); config_.lidar_P_imu = lidar_T_imu_.trans; config_.lidar_R_imu = lidar_T_imu_.rot.toEigen(); @@ -154,15 +154,15 @@ class LioSam: public evalio::Pipeline { lio_sam_ = std::make_unique(config_); } - void add_imu(evalio::ImuMeasurement mm) override { - lio_sam_->addImuMeasurement(evalio::convert(mm)); + void add_imu(ev::ImuMeasurement mm) override { + lio_sam_->addImuMeasurement(ev::convert(mm)); } - std::map> - add_lidar(evalio::LidarMeasurement mm) override { + std::map> + add_lidar(ev::LidarMeasurement mm) override { // Set everything up auto cloud = - evalio::convert(mm.points) + ev::convert(mm.points) // NOTE: This likely causes a copy, see if we can avoid that later .makeShared(); @@ -170,13 +170,13 @@ class LioSam: public evalio::Pipeline { lio_sam_->addLidarMeasurement(mm.stamp.to_sec(), cloud); // Return features - auto used_points = lio_sam_->getMostRecentFrame(); - auto result = evalio::convert(*used_points); - return {{"point", result}}; + return ev::convert( + {{"point", *lio_sam_->getMostRecentFrame()}} + ); } private: std::unique_ptr lio_sam_; lio_sam::LioSamParams config_; - evalio::SE3 lidar_T_imu_; + ev::SE3 lidar_T_imu_; }; diff --git a/cpp/bindings/pipelines/loam.h b/cpp/bindings/pipelines/loam.h index c913e962..0088afdc 100644 --- a/cpp/bindings/pipelines/loam.h +++ b/cpp/bindings/pipelines/loam.h @@ -2,13 +2,22 @@ #include #include -#include +#include "evalio/convert/eigen.h" #include "evalio/pipeline.h" #include "evalio/types.h" #include "loam/loam.h" -class LOAM: public evalio::Pipeline { +namespace ev = evalio; + +namespace evalio { +template<> +inline ev::SE3 convert(const loam::Pose3d& from) { + return ev::SE3(ev::SO3::fromEigen(from.rotation), from.translation); +} +} // namespace evalio + +class LOAM: public ev::Pipeline { public: LOAM() {} @@ -54,20 +63,20 @@ class LOAM: public evalio::Pipeline { // clang-format on // Getters - const evalio::SE3 pose() override { - return to_se3(current_estimated_pose) * lidar_T_imu_; + const ev::SE3 pose() override { + return ev::convert(current_estimated_pose) * lidar_T_imu_; } - const std::map> map() override { + const std::map> map() override { return features_to_points( transform_features(map_features(), current_estimated_pose) ); } // Setters - void set_imu_params(evalio::ImuParams params) override {} + void set_imu_params(ev::ImuParams params) override {} - void set_lidar_params(evalio::LidarParams params) override { + void set_lidar_params(ev::LidarParams params) override { loam_lidar_params_ = std::make_unique( params.num_rows, params.num_columns, @@ -76,17 +85,17 @@ class LOAM: public evalio::Pipeline { ); } - void set_imu_T_lidar(evalio::SE3 T) override { + void set_imu_T_lidar(ev::SE3 T) override { lidar_T_imu_ = T.inverse(); } // Doers void initialize() override {} - void add_imu(evalio::ImuMeasurement mm) override {} + void add_imu(ev::ImuMeasurement mm) override {} - std::map> - add_lidar(evalio::LidarMeasurement mm) override { + std::map> + add_lidar(ev::LidarMeasurement mm) override { // Handle Edge case of the first scan if (past_k_scans_.size() == 0) { // Extract Features from the first scan @@ -142,28 +151,18 @@ class LOAM: public evalio::Pipeline { /// @brief The last k scans (features points only) and their respective /// odometry measurements - std::deque>> + std::deque>> past_k_scans_; /// @brief The current pose estimate in the odometry frame {odom_T_lidar} loam::Pose3d current_estimated_pose {loam::Pose3d::Identity()}; /// @brief The transform from lidar to IMU - evalio::SE3 lidar_T_imu_ {evalio::SE3::identity()}; + ev::SE3 lidar_T_imu_ {ev::SE3::identity()}; private: - /// @brief Converts a loam SE(3) pose type to a evalio SE(3) pose type - inline evalio::SE3 to_se3(loam::Pose3d pose) { - return evalio::SE3(evalio::SO3::fromEigen(pose.rotation), pose.translation); - } - - /// @brief Converts evalio point to eigen - inline Eigen::Vector3d to_eigen_point(evalio::Point point) { - return {point.x, point.y, point.z}; - } - /// @brief Transforms a evalio point from its source frame to a target frame - inline evalio::Point - transform_point(evalio::Point src_pt, loam::Pose3d target_T_source) { - auto tgt_pt = target_T_source.act(to_eigen_point(src_pt)); + inline ev::Point + transform_point(ev::Point src_pt, loam::Pose3d target_T_source) { + auto tgt_pt = target_T_source.act(ev::convert(src_pt)); return { tgt_pt(0), tgt_pt(1), @@ -178,17 +177,17 @@ class LOAM: public evalio::Pipeline { /// @brief Helper to aggregate all features (edge + planar) into a single /// container - std::map> - features_to_points(const loam::LoamFeatures features) { + std::map> + features_to_points(const loam::LoamFeatures features) { return {{"planar", features.planar_points}, {"edge", features.edge_points}}; } /// @brief Aggregate the history of k most recent scans into a local map in /// the frame of the most recent registered - loam::LoamFeatures map_features() { + loam::LoamFeatures map_features() { // Setup accumulators auto current_T_map = loam::Pose3d::Identity(); - auto map_features = loam::LoamFeatures(); + auto map_features = loam::LoamFeatures(); // Iterate from the most recent scan to the oldest in the stored history for (auto it = past_k_scans_.rbegin(); it != past_k_scans_.rend(); ++it) { @@ -215,11 +214,11 @@ class LOAM: public evalio::Pipeline { } /// @brief Transforms all features into a new frame - loam::LoamFeatures transform_features( - loam::LoamFeatures features, + loam::LoamFeatures transform_features( + loam::LoamFeatures features, loam::Pose3d target_T_source ) { - loam::LoamFeatures transformed_features; + loam::LoamFeatures transformed_features; for (const auto& planar_pt : features.planar_points) { transformed_features.planar_points.push_back( transform_point(planar_pt, target_T_source) diff --git a/cpp/bindings/pipelines/mad_icp.h b/cpp/bindings/pipelines/mad_icp.h index 3fe2d345..1808842b 100644 --- a/cpp/bindings/pipelines/mad_icp.h +++ b/cpp/bindings/pipelines/mad_icp.h @@ -2,15 +2,17 @@ #include #include -#include #include +#include "evalio/convert/eigen.h" #include "evalio/pipeline.h" #include "evalio/types.h" // mad-icp stuff #include "odometry/pipeline.h" +namespace ev = evalio; + // From here // https://github.com/rvp-group/mad-icp/blob/main/mad_icp/configurations/mad_params.py#L31 struct MadICPConfig { @@ -29,7 +31,7 @@ struct MadICPConfig { double sensor_hz = 10.0; }; -class MadICP: public evalio::Pipeline { +class MadICP: public ev::Pipeline { public: MadICP() {} @@ -59,31 +61,26 @@ class MadICP: public evalio::Pipeline { ); // Getters - const evalio::SE3 pose() override { - return to_evalio_se3(mad_icp_->currentPose()) * lidar_T_imu_; + const ev::SE3 pose() override { + return ev::convert(mad_icp_->currentPose()) * lidar_T_imu_; } - const std::map> map() override { - auto leaves = mad_icp_->modelLeaves(); - std::vector output_points; - output_points.reserve(leaves.size()); - for (auto point : leaves) { - output_points.push_back(to_evalio_point(point)); - } - - return {{"planar", output_points}}; + const std::map> map() override { + return ev::convert( + {{"planar", mad_icp_->modelLeaves()}} + ); } // Setters - void set_imu_params(evalio::ImuParams params) override {} + void set_imu_params(ev::ImuParams params) override {} - void set_lidar_params(evalio::LidarParams params) override { + void set_lidar_params(ev::LidarParams params) override { config_.max_range = params.max_range; config_.min_range = params.min_range; config_.sensor_hz = params.rate; } - void set_imu_T_lidar(evalio::SE3 T) override { + void set_imu_T_lidar(ev::SE3 T) override { lidar_T_imu_ = T.inverse(); } @@ -110,17 +107,17 @@ class MadICP: public evalio::Pipeline { ); } - void add_imu(evalio::ImuMeasurement mm) override {} + void add_imu(ev::ImuMeasurement mm) override {} - std::map> - add_lidar(evalio::LidarMeasurement mm) override { + std::map> + add_lidar(ev::LidarMeasurement mm) override { // filter out points that are out of range mm.points.erase( // remove_if puts the elements to be removed at the end of the vector std::remove_if( mm.points.begin(), mm.points.end(), - [this](const evalio::Point& point) { + [this](const ev::Point& point) { double range = std::sqrt( point.x * point.x + point.y * point.y + point.z * point.z ); @@ -131,52 +128,19 @@ class MadICP: public evalio::Pipeline { ); // Copy - std::vector points; - points.reserve(mm.points.size()); - for (auto point : mm.points) { - points.push_back(to_eigen_point(point)); - } + auto points = ev::convert(mm.points); // Run through pipeline mad_icp_->compute(mm.stamp.to_sec(), points); - auto leaves = mad_icp_->currentLeaves(); - std::vector output_points; - output_points.reserve(leaves.size()); - for (const auto& point : leaves) { - output_points.push_back(to_evalio_point(point)); - } - - return {{"planar", output_points}}; + // Return current leaves + return ev::convert( + {{"planar", mad_icp_->currentLeaves()}} + ); } private: std::unique_ptr mad_icp_; MadICPConfig config_; - evalio::SE3 lidar_T_imu_ = evalio::SE3::identity(); - - inline evalio::Point to_evalio_point(Eigen::Vector3d point) { - return { - .x = point[0], - .y = point[1], - .z = point[2], - .intensity = 0.0, - .t = evalio::Duration::from_sec(0), - .row = 0, - .col = 0 - }; - } - - inline Eigen::Vector3d to_eigen_point(evalio::Point point) { - return {point.x, point.y, point.z}; - } - - inline evalio::SE3 to_evalio_se3(Eigen::Matrix4d pose) { - const auto iso = Eigen::Isometry3d(pose); - const auto t = iso.translation(); - const auto q = Eigen::Quaterniond(iso.linear()); - const auto rot = - evalio::SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; - return evalio::SE3(rot, t); - } + ev::SE3 lidar_T_imu_ = ev::SE3::identity(); }; diff --git a/cpp/evalio/convert/base.h b/cpp/evalio/convert/base.h index f3498e9a..1e509e53 100644 --- a/cpp/evalio/convert/base.h +++ b/cpp/evalio/convert/base.h @@ -1,6 +1,8 @@ // Helper module for converting between the various library types. #pragma once +#include + #include "evalio/types.h" namespace evalio { @@ -26,6 +28,21 @@ inline OutCont convert(const InCont& in) { return out; } +/// @brief Convert a map of arbitrary containers to a map of std::vector. +/// +/// Useful for converting to final evalio map types. +/// NOTE: Dict> = std::map +// TODO: This is a bit confusing... for other versions of convert, we have to specify output when calling, for this one we specify the input type... +template class InCont, class In> +inline std::map> +convert(const std::map>& in) { + std::map> out; + for (const auto& [key, val] : in) { + out[key] = convert(val); + } + return out; +} + /// @brief Convert evalio::Point to timestamps as doubles. template<> inline double convert(const evalio::Point& in) { diff --git a/cpp/evalio/convert/eigen.h b/cpp/evalio/convert/eigen.h index e9a9c91a..a2e1695b 100644 --- a/cpp/evalio/convert/eigen.h +++ b/cpp/evalio/convert/eigen.h @@ -7,6 +7,7 @@ #include "evalio/types.h" namespace evalio { +// ------------------------- Points ------------------------- // template<> inline Point convert(const Eigen::Vector3d& in) { return { @@ -25,4 +26,18 @@ inline Eigen::Vector3d convert(const Point& in) { return {in.x, in.y, in.z}; } +// ------------------------- Poses ------------------------- // +template<> +inline SE3 convert(const Eigen::Isometry3d& in) { + const auto t = in.translation(); + const auto q = Eigen::Quaterniond(in.linear()); + const auto rot = SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()}; + return SE3(rot, t); +} + +template<> +inline SE3 convert(const Eigen::Matrix4d& in) { + const auto iso = Eigen::Isometry3d(in); + return convert(iso); +} } // namespace evalio From 3869e8340a396aa141bf12a82e21cb95663fe00e Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Thu, 30 Oct 2025 13:46:30 -0400 Subject: [PATCH 6/6] Move conversions of iters and maps to separate methods --- cpp/bindings/pipelines/ct_icp.h | 12 +++----- cpp/bindings/pipelines/genz_icp.h | 12 +++++--- cpp/bindings/pipelines/kiss_icp.h | 10 +++--- cpp/bindings/pipelines/lio_sam.h | 6 ++-- cpp/bindings/pipelines/mad_icp.h | 6 ++-- cpp/evalio/convert/base.h | 51 +++++++++++++++++++------------ 6 files changed, 55 insertions(+), 42 deletions(-) diff --git a/cpp/bindings/pipelines/ct_icp.h b/cpp/bindings/pipelines/ct_icp.h index 5af2f854..48d952e2 100644 --- a/cpp/bindings/pipelines/ct_icp.h +++ b/cpp/bindings/pipelines/ct_icp.h @@ -5,6 +5,7 @@ #include "ct_icp/odometry.hpp" #include "ct_icp/types.hpp" +#include "evalio/convert/base.h" #include "evalio/convert/eigen.h" #include "evalio/pipeline.h" #include "evalio/types.h" @@ -209,10 +210,8 @@ class CTICP: public ev::Pipeline { } const std::map> map() override { - // TODO: Need to be able to handle custom allocators here - return ev::convert( - {} // {{"planar", ct_icp_->GetLocalMap()}} - ); + auto map = ct_icp_->GetLocalMap(); + return ev::convert_map({{"planar", map}}); } // Setters @@ -237,8 +236,7 @@ class CTICP: public ev::Pipeline { std::map> add_lidar(ev::LidarMeasurement mm) override { // Convert - std::vector pc = - ev::convert(mm.points); + auto pc = ev::convert_iter>(mm.points); // Normalize timestamps to [0, 1] const auto& [min, max] = std::minmax_element( @@ -265,7 +263,7 @@ class CTICP: public ev::Pipeline { scan_idx_++; // Return the used points - return ev::convert( + return ev::convert_map>( {{"planar", summary.keypoints}} ); } diff --git a/cpp/bindings/pipelines/genz_icp.h b/cpp/bindings/pipelines/genz_icp.h index 15ea18c8..90d0fb50 100644 --- a/cpp/bindings/pipelines/genz_icp.h +++ b/cpp/bindings/pipelines/genz_icp.h @@ -3,6 +3,7 @@ #include #include +#include "evalio/convert/base.h" #include "evalio/convert/eigen.h" #include "evalio/convert/sophus.h" #include "evalio/pipeline.h" @@ -58,8 +59,9 @@ class GenZICP: public ev::Pipeline { } const std::map> map() override { - std::vector map = genz_icp_->LocalMap(); - return {{"point", ev::convert(map)}}; + return ev::convert_map>( + {{"map", genz_icp_->LocalMap()}} + ); } // Setters @@ -85,8 +87,8 @@ class GenZICP: public ev::Pipeline { std::map> add_lidar(ev::LidarMeasurement mm) override { // Set everything up - auto points = ev::convert(mm.points); - auto timestamps = ev::convert(mm.points); + auto points = ev::convert_iter>(mm.points); + auto timestamps = ev::convert_iter>(mm.points); // Run through pipeline auto [planar, nonplanar] = genz_icp_->RegisterFrame(points, timestamps); @@ -107,7 +109,7 @@ class GenZICP: public ev::Pipeline { ); // Return the used points - return ev::convert( + return ev::convert_map>( {{"planar", planar}, {"nonplanar", nonplanar}} ); } diff --git a/cpp/bindings/pipelines/kiss_icp.h b/cpp/bindings/pipelines/kiss_icp.h index 29af62fc..a9f30d38 100644 --- a/cpp/bindings/pipelines/kiss_icp.h +++ b/cpp/bindings/pipelines/kiss_icp.h @@ -45,7 +45,7 @@ class KissICP: public ev::Pipeline { } const std::map> map() override { - return ev::convert( + return ev::convert_map>( {{"point", kiss_icp_->LocalMap()}} ); } @@ -72,14 +72,16 @@ class KissICP: public ev::Pipeline { std::map> add_lidar(ev::LidarMeasurement mm) override { // Convert inputs - auto points = ev::convert(mm.points); - auto timestamps = ev::convert(mm.points); + auto points = ev::convert_iter>(mm.points); + auto timestamps = ev::convert_iter>(mm.points); // Run through pipeline const auto& [_, used_points] = kiss_icp_->RegisterFrame(points, timestamps); // Convert outputs - return ev::convert({{"point", used_points}}); + return ev::convert_map>( + {{"point", used_points}} + ); } private: diff --git a/cpp/bindings/pipelines/lio_sam.h b/cpp/bindings/pipelines/lio_sam.h index a4ab930d..c2d21c89 100644 --- a/cpp/bindings/pipelines/lio_sam.h +++ b/cpp/bindings/pipelines/lio_sam.h @@ -122,7 +122,7 @@ class LioSam: public ev::Pipeline { } const std::map> map() override { - return ev::convert( + return ev::convert_map>( {{"point", *lio_sam_->getMap()}} ); } @@ -162,7 +162,7 @@ class LioSam: public ev::Pipeline { add_lidar(ev::LidarMeasurement mm) override { // Set everything up auto cloud = - ev::convert(mm.points) + ev::convert_iter>(mm.points) // NOTE: This likely causes a copy, see if we can avoid that later .makeShared(); @@ -170,7 +170,7 @@ class LioSam: public ev::Pipeline { lio_sam_->addLidarMeasurement(mm.stamp.to_sec(), cloud); // Return features - return ev::convert( + return ev::convert_map>( {{"point", *lio_sam_->getMostRecentFrame()}} ); } diff --git a/cpp/bindings/pipelines/mad_icp.h b/cpp/bindings/pipelines/mad_icp.h index 1808842b..fae11a4c 100644 --- a/cpp/bindings/pipelines/mad_icp.h +++ b/cpp/bindings/pipelines/mad_icp.h @@ -66,7 +66,7 @@ class MadICP: public ev::Pipeline { } const std::map> map() override { - return ev::convert( + return ev::convert_map>( {{"planar", mad_icp_->modelLeaves()}} ); } @@ -128,13 +128,13 @@ class MadICP: public ev::Pipeline { ); // Copy - auto points = ev::convert(mm.points); + auto points = ev::convert_iter>(mm.points); // Run through pipeline mad_icp_->compute(mm.stamp.to_sec(), points); // Return current leaves - return ev::convert( + return ev::convert_map>( {{"planar", mad_icp_->currentLeaves()}} ); } diff --git a/cpp/evalio/convert/base.h b/cpp/evalio/convert/base.h index 1e509e53..501518e6 100644 --- a/cpp/evalio/convert/base.h +++ b/cpp/evalio/convert/base.h @@ -13,40 +13,51 @@ namespace evalio { template inline Out convert(const In& in) = delete; +/// @brief Convert evalio::Point to timestamps as doubles. +template<> +inline double convert(const evalio::Point& in) { + return in.t.to_sec(); +} + /// @brief Convert a container of In to a container of Out using convert(in). -template< - template class OutCont, - class Out, - template class InCont, - class In> -inline OutCont convert(const InCont& in) { - OutCont out; +/// +/// Assumes the following are defined: +/// - In::size(). +/// - In is iterable with range-based for loops. +/// - Out is default-constructible. +/// - Out::value_type. +/// - Out::reserve(size_t). +/// - Out::push_back(Out::value_type). +/// - convert(In::value_type). + +template +inline Out convert_iter(const In& in) { + Out out; out.reserve(in.size()); for (const auto& item : in) { - out.push_back(convert(item)); + out.push_back( + convert(item) + ); } return out; } /// @brief Convert a map of arbitrary containers to a map of std::vector. /// -/// Useful for converting to final evalio map types. -/// NOTE: Dict> = std::map -// TODO: This is a bit confusing... for other versions of convert, we have to specify output when calling, for this one we specify the input type... -template class InCont, class In> +/// Useful for converting to final evalio map types. Unlike other convert functions, +/// this one only requires the input type to be specified. +/// Assumes the following are defined: +/// - In::size(). +/// - In is iterable with range-based for loops. +/// - convert(In::value_type). +template inline std::map> -convert(const std::map>& in) { +convert_map(const std::map& in) { std::map> out; for (const auto& [key, val] : in) { - out[key] = convert(val); + out[key] = convert_iter>(val); } return out; } -/// @brief Convert evalio::Point to timestamps as doubles. -template<> -inline double convert(const evalio::Point& in) { - return in.t.to_sec(); -} - } // namespace evalio