Skip to content

Commit 21403a0

Browse files
committed
feat(pl)!: Create features and pose estimate buffers (#54)
BREAKING CHANGE: The Pipeline class interface has changed slightly. `add_lidar` now has no return, and `pose` method has been removed. In place of these is a new `save` method for saving poses and features asynchronously with no overhead.
1 parent 9f9859d commit 21403a0

File tree

16 files changed

+466
-254
lines changed

16 files changed

+466
-254
lines changed

.github/workflows/on_main.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,4 +79,4 @@ jobs:
7979
- name: Github Release
8080
env:
8181
GITHUB_TOKEN: ${{ secrets.RELEASE_PLEASE_GITHUB_TOKEN }}
82-
run: gh release upload -R ${{ github.repository }} ${{ needs.release.outputs.tag_name }} ./dist/*
82+
run: gh release upload -R ${{ github.repository }} ${{ needs.release.outputs.tag_name }} ./dist/*

cpp/bindings/pipeline.h

Lines changed: 51 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,6 @@ class PyPipeline: public evalio::Pipeline {
2121
NB_TRAMPOLINE(Pipeline, 9);
2222

2323
// Getters
24-
const evalio::SE3 pose() override {
25-
NB_OVERRIDE_PURE(pose);
26-
}
27-
2824
const std::map<std::string, std::vector<evalio::Point>> map() override {
2925
NB_OVERRIDE_PURE(map);
3026
}
@@ -56,8 +52,7 @@ class PyPipeline: public evalio::Pipeline {
5652
NB_OVERRIDE_PURE(add_imu, mm);
5753
}
5854

59-
std::map<std::string, std::vector<Point>>
60-
add_lidar(evalio::LidarMeasurement mm) override {
55+
void add_lidar(evalio::LidarMeasurement mm) override {
6156
NB_OVERRIDE_PURE(add_lidar, mm);
6257
}
6358
}; // namespace evalio
@@ -81,7 +76,31 @@ inline void makeBasePipeline(nb::module_& m) {
8176
&evalio::Pipeline::version,
8277
"Version of the pipeline."
8378
)
84-
.def("pose", &evalio::Pipeline::pose, "Most recent pose estimate.")
79+
.def(
80+
"saved_estimates",
81+
&evalio::Pipeline::saved_estimates,
82+
"Most recent stamped pose estimates. Will be removed after this method is called."
83+
)
84+
.def(
85+
"saved_features",
86+
&evalio::Pipeline::saved_features,
87+
"Most recent stamped feature scans. Will be removed after this method is called."
88+
)
89+
.def(
90+
"saved_maps",
91+
&evalio::Pipeline::saved_maps,
92+
"Most recent stamped maps. Will be removed after this method is called."
93+
)
94+
.def(
95+
"saved_features_matrix",
96+
&evalio::Pipeline::saved_features_matrix,
97+
"Most recent stamped feature scans as matrices. Will be removed after this method is called."
98+
)
99+
.def(
100+
"saved_maps_matrix",
101+
&evalio::Pipeline::saved_maps_matrix,
102+
"Most recent stamped maps as matrices. Will be removed after this method is called."
103+
)
85104
.def("map", &evalio::Pipeline::map, "Map of the environment.")
86105
.def(
87106
"initialize",
@@ -126,6 +145,31 @@ inline void makeBasePipeline(nb::module_& m) {
126145
"T"_a,
127146
"Set the transformation from IMU to LiDAR frame."
128147
)
148+
.def(
149+
"set_visualizing",
150+
&evalio::Pipeline::set_visualizing,
151+
"visualize"_a.none(),
152+
"Enable or disable visualization."
153+
)
154+
.def(
155+
"save",
156+
nb::overload_cast<const evalio::Stamp&, const evalio::SE3&>(
157+
&evalio::Pipeline::save<const evalio::SE3&>
158+
),
159+
"stamp"_a,
160+
"pose"_a,
161+
"Save the current pose estimate at the given timestamp."
162+
)
163+
// Use a lambda here, as nb::overload_cast has issues finding the non-template methods
164+
.def(
165+
"save",
166+
[](Pipeline& self, const Stamp& stamp, const Map<>& features) {
167+
self.save(stamp, features);
168+
},
169+
"stamp"_a,
170+
"features"_a,
171+
"Save the current feature map at the given timestamp."
172+
)
129173
.doc() =
130174
"Base class for all pipelines. This class defines the interface "
131175
"for interacting with pipelines, and is intended to be "

cpp/bindings/pipelines/ct_icp.h

Lines changed: 10 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -204,14 +204,8 @@ class CTICP: public ev::Pipeline {
204204
// clang-format on
205205

206206
// Getters
207-
const ev::SE3 pose() override {
208-
const auto pose = ct_icp_->Trajectory().back();
209-
return ev::convert<ev::SE3>(pose) * lidar_T_imu_;
210-
}
211-
212207
const std::map<std::string, std::vector<ev::Point>> map() override {
213-
auto map = ct_icp_->GetLocalMap();
214-
return ev::convert_map<decltype(map)>({{"planar", map}});
208+
return ev::make_map("planar", ct_icp_->GetLocalMap());
215209
}
216210

217211
// Setters
@@ -233,8 +227,7 @@ class CTICP: public ev::Pipeline {
233227

234228
void add_imu(ev::ImuMeasurement mm) override {}
235229

236-
std::map<std::string, std::vector<ev::Point>>
237-
add_lidar(ev::LidarMeasurement mm) override {
230+
void add_lidar(ev::LidarMeasurement mm) override {
238231
// Convert
239232
auto pc = ev::convert_iter<std::vector<ct_icp::Point3D>>(mm.points);
240233

@@ -260,11 +253,14 @@ class CTICP: public ev::Pipeline {
260253

261254
// Run through pipeline
262255
const auto summary = ct_icp_->RegisterFrame(pc);
263-
scan_idx_++;
264256

265-
// Return the used points
266-
return ev::convert_map<std::vector<ct_icp::Point3D>>(
267-
{{"planar", summary.keypoints}}
268-
);
257+
// Save the estimate
258+
const auto pose = ct_icp_->Trajectory().back();
259+
this->save(mm.stamp, ev::convert<ev::SE3>(pose) * lidar_T_imu_);
260+
261+
// Save the used points
262+
this->save(mm.stamp, "planar", summary.keypoints);
263+
264+
scan_idx_++;
269265
}
270266
};

cpp/bindings/pipelines/genz_icp.h

Lines changed: 11 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -52,16 +52,8 @@ class GenZICP: public ev::Pipeline {
5252
// clang-format on
5353

5454
// Getters
55-
const ev::SE3 pose() override {
56-
const auto pose =
57-
!genz_icp_->poses().empty() ? genz_icp_->poses().back() : Sophus::SE3d();
58-
return ev::convert<ev::SE3>(pose * lidar_T_imu_);
59-
}
60-
6155
const std::map<std::string, std::vector<ev::Point>> map() override {
62-
return ev::convert_map<std::vector<Eigen::Vector3d>>(
63-
{{"map", genz_icp_->LocalMap()}}
64-
);
56+
return ev::make_map("map", genz_icp_->LocalMap());
6557
}
6658

6759
// Setters
@@ -84,34 +76,35 @@ class GenZICP: public ev::Pipeline {
8476

8577
void add_imu(ev::ImuMeasurement mm) override {}
8678

87-
std::map<std::string, std::vector<ev::Point>>
88-
add_lidar(ev::LidarMeasurement mm) override {
79+
void add_lidar(ev::LidarMeasurement mm) override {
8980
// Set everything up
9081
auto points = ev::convert_iter<std::vector<Eigen::Vector3d>>(mm.points);
9182
auto timestamps = ev::convert_iter<std::vector<double>>(mm.points);
9283

9384
// Run through pipeline
9485
auto [planar, nonplanar] = genz_icp_->RegisterFrame(points, timestamps);
95-
auto lidar_T_world = genz_icp_->poses().back().inverse();
86+
auto world_T_lidar = genz_icp_->poses().back();
87+
auto lidar_T_world = world_T_lidar.inverse();
88+
89+
// Save the estimate
90+
this->save(mm.stamp, world_T_lidar * lidar_T_imu_);
9691

9792
// These are all in the global frame, so we need to convert them
9893
std::transform(
9994
planar.begin(),
10095
planar.end(),
10196
planar.begin(),
102-
[&](auto point) { return lidar_T_imu_ * point; }
97+
[&](auto point) { return lidar_T_world * point; }
10398
);
10499
std::transform(
105100
nonplanar.begin(),
106101
nonplanar.end(),
107102
nonplanar.begin(),
108-
[&](auto point) { return lidar_T_imu_ * point; }
103+
[&](auto point) { return lidar_T_world * point; }
109104
);
110105

111-
// Return the used points
112-
return ev::convert_map<std::vector<Eigen::Vector3d>>(
113-
{{"planar", planar}, {"nonplanar", nonplanar}}
114-
);
106+
// Save the used points
107+
this->save(mm.stamp, "planar", planar, "nonplanar", nonplanar);
115108
}
116109

117110
private:

cpp/bindings/pipelines/kiss_icp.h

Lines changed: 7 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -39,15 +39,8 @@ class KissICP: public ev::Pipeline {
3939
);
4040

4141
// Getters
42-
const ev::SE3 pose() override {
43-
const Sophus::SE3d pose = kiss_icp_->pose() * lidar_T_imu_;
44-
return ev::convert<ev::SE3>(pose);
45-
}
46-
4742
const std::map<std::string, std::vector<ev::Point>> map() override {
48-
return ev::convert_map<std::vector<Eigen::Vector3d>>(
49-
{{"point", kiss_icp_->LocalMap()}}
50-
);
43+
return ev::make_map("point", kiss_icp_->LocalMap());
5144
}
5245

5346
// Setters
@@ -69,19 +62,19 @@ class KissICP: public ev::Pipeline {
6962

7063
void add_imu(ev::ImuMeasurement mm) override {}
7164

72-
std::map<std::string, std::vector<ev::Point>>
73-
add_lidar(ev::LidarMeasurement mm) override {
65+
void add_lidar(ev::LidarMeasurement mm) override {
7466
// Convert inputs
7567
auto points = ev::convert_iter<std::vector<Eigen::Vector3d>>(mm.points);
7668
auto timestamps = ev::convert_iter<std::vector<double>>(mm.points);
7769

7870
// Run through pipeline
7971
const auto& [_, used_points] = kiss_icp_->RegisterFrame(points, timestamps);
8072

81-
// Convert outputs
82-
return ev::convert_map<std::vector<Eigen::Vector3d>>(
83-
{{"point", used_points}}
84-
);
73+
// Save the estimate
74+
this->save(mm.stamp, kiss_icp_->pose() * lidar_T_imu_);
75+
76+
// Save features
77+
this->save(mm.stamp, "point", used_points);
8578
}
8679

8780
private:

cpp/bindings/pipelines/lio_sam.h

Lines changed: 16 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -35,14 +35,14 @@ inline Point convert(const lio_sam::PointType& in) {
3535

3636
template<>
3737
inline lio_sam::PointXYZIRT convert(const ev::Point& in) {
38-
return lio_sam::PointXYZIRT {
39-
.x = static_cast<float>(in.x),
40-
.y = static_cast<float>(in.y),
41-
.z = static_cast<float>(in.z),
42-
.intensity = static_cast<float>(in.intensity),
43-
.ring = static_cast<uint16_t>(in.row),
44-
.time = static_cast<float>(in.t.to_sec()),
45-
};
38+
lio_sam::PointXYZIRT out;
39+
out.x = static_cast<float>(in.x);
40+
out.y = static_cast<float>(in.y);
41+
out.z = static_cast<float>(in.z);
42+
out.intensity = static_cast<float>(in.intensity);
43+
out.ring = static_cast<uint16_t>(in.row);
44+
out.time = static_cast<float>(in.t.to_sec());
45+
return out;
4646
}
4747

4848
// IMU conversions
@@ -117,14 +117,8 @@ class LioSam: public ev::Pipeline {
117117
// clang-format on
118118

119119
// Getters
120-
const ev::SE3 pose() override {
121-
return ev::convert<ev::SE3>(lio_sam_->getPose()) * lidar_T_imu_;
122-
}
123-
124120
const std::map<std::string, std::vector<ev::Point>> map() override {
125-
return ev::convert_map<pcl::PointCloud<lio_sam::PointType>>(
126-
{{"point", *lio_sam_->getMap()}}
127-
);
121+
return ev::make_map("map", *lio_sam_->getMap());
128122
}
129123

130124
// Setters
@@ -158,8 +152,7 @@ class LioSam: public ev::Pipeline {
158152
lio_sam_->addImuMeasurement(ev::convert<lio_sam::Imu>(mm));
159153
}
160154

161-
std::map<std::string, std::vector<ev::Point>>
162-
add_lidar(ev::LidarMeasurement mm) override {
155+
void add_lidar(ev::LidarMeasurement mm) override {
163156
// Set everything up
164157
auto cloud =
165158
ev::convert_iter<pcl::PointCloud<lio_sam::PointXYZIRT>>(mm.points)
@@ -169,10 +162,12 @@ class LioSam: public ev::Pipeline {
169162
// Run through pipeline
170163
lio_sam_->addLidarMeasurement(mm.stamp.to_sec(), cloud);
171164

172-
// Return features
173-
return ev::convert_map<pcl::PointCloud<lio_sam::PointType>>(
174-
{{"point", *lio_sam_->getMostRecentFrame()}}
175-
);
165+
// Save pose
166+
const auto pose = ev::convert<ev::SE3>(lio_sam_->getPose()) * lidar_T_imu_;
167+
this->save(mm.stamp, pose);
168+
169+
// Save features
170+
this->save(mm.stamp, "features", *lio_sam_->getMostRecentFrame());
176171
}
177172

178173
private:

cpp/bindings/pipelines/loam.h

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -63,10 +63,6 @@ class LOAM: public ev::Pipeline {
6363
// clang-format on
6464

6565
// Getters
66-
const ev::SE3 pose() override {
67-
return ev::convert<ev::SE3>(current_estimated_pose) * lidar_T_imu_;
68-
}
69-
7066
const std::map<std::string, std::vector<ev::Point>> map() override {
7167
return features_to_points(
7268
transform_features(map_features(), current_estimated_pose)
@@ -94,8 +90,7 @@ class LOAM: public ev::Pipeline {
9490

9591
void add_imu(ev::ImuMeasurement mm) override {}
9692

97-
std::map<std::string, std::vector<ev::Point>>
98-
add_lidar(ev::LidarMeasurement mm) override {
93+
void add_lidar(ev::LidarMeasurement mm) override {
9994
// Handle Edge case of the first scan
10095
if (past_k_scans_.size() == 0) {
10196
// Extract Features from the first scan
@@ -106,9 +101,9 @@ class LOAM: public ev::Pipeline {
106101
std::make_pair(loam::Pose3d::Identity(), scan_features)
107102
);
108103
// Initialize the odometry frame pose
109-
current_estimated_pose = loam::Pose3d::Identity();
104+
this->save(mm.stamp, evalio::SE3::identity() * lidar_T_imu_);
110105
// Return the initial scan features
111-
return features_to_points(scan_features);
106+
this->save(mm.stamp, features_to_points(scan_features));
112107
}
113108
// Default case for all iterations except the first
114109
else {
@@ -134,8 +129,11 @@ class LOAM: public ev::Pipeline {
134129
}
135130
// Update the Odometry frame pose
136131
current_estimated_pose = current_estimated_pose.compose(map_T_scan);
132+
const auto pose_ev =
133+
ev::convert<ev::SE3>(current_estimated_pose) * lidar_T_imu_;
134+
this->save(mm.stamp, pose_ev);
137135
// Return the points associated with the used features
138-
return features_to_points(scan_features);
136+
this->save(mm.stamp, features_to_points(scan_features));
139137
}
140138
}
141139

0 commit comments

Comments
 (0)