Skip to content

Commit ded06a8

Browse files
authored
fix!: Switch interface to consistent snake_case naming (#65)
BREAKING CHANGE: Some simple nomenclature breaking changes here, fromMat → from_mat toMat → to_mat toEigen → to_eigen
1 parent 21403a0 commit ded06a8

File tree

16 files changed

+66
-66
lines changed

16 files changed

+66
-66
lines changed

cpp/bindings/main.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -21,13 +21,13 @@ NB_MODULE(_cpp, m) {
2121
"types",
2222
"Common types used for conversion between datasets and pipelines."
2323
);
24-
evalio::makeTypes(m_types);
24+
evalio::make_types(m_types);
2525

2626
auto m_helpers =
2727
m.def_submodule("helpers", "Helper functions for internal evalio usage.");
28-
evalio::makeConversions(m_helpers);
28+
evalio::make_conversions(m_helpers);
2929

3030
auto m_pipelines = m.def_submodule("pipelines", "Pipelines used in evalio.");
31-
evalio::makeBasePipeline(m_pipelines);
32-
evalio::makePipelines(m_pipelines);
31+
evalio::make_base_pipeline(m_pipelines);
32+
evalio::make_pipelines(m_pipelines);
3333
}

cpp/bindings/pipeline.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ class PyPipeline: public evalio::Pipeline {
5757
}
5858
}; // namespace evalio
5959

60-
inline void makeBasePipeline(nb::module_& m) {
60+
inline void make_base_pipeline(nb::module_& m) {
6161
nb::class_<evalio::Pipeline, PyPipeline>(m, "Pipeline")
6262
.def(nb::init<>(), "Construct a new pipeline.")
6363
.def_static("name", &evalio::Pipeline::name, "Name of the pipeline.")

cpp/bindings/pipelines/bindings.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ using namespace nb::literals;
3232
#endif
3333

3434
namespace evalio {
35-
inline void makePipelines(nb::module_& m) {
35+
inline void make_pipelines(nb::module_& m) {
3636
// List all the pipelines here
3737
#ifdef EVALIO_KISS_ICP
3838
nb::class_<KissICP, evalio::Pipeline>(m, "KissICP")

cpp/bindings/pipelines/ct_icp.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ inline ct_icp::Point3D convert(const evalio::Point& from) {
3939

4040
template<>
4141
inline evalio::SE3 convert(const ct_icp::TrajectoryFrame& in) {
42-
return ev::SE3(ev::SO3::fromMat(in.begin_R), in.begin_t);
42+
return ev::SE3(ev::SO3::from_mat(in.begin_R), in.begin_t);
4343
}
4444
} // namespace evalio
4545

cpp/bindings/pipelines/lio_sam.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,7 @@ class LioSam: public ev::Pipeline {
140140
void set_imu_T_lidar(ev::SE3 T) override {
141141
lidar_T_imu_ = T.inverse();
142142
config_.lidar_P_imu = lidar_T_imu_.trans;
143-
config_.lidar_R_imu = lidar_T_imu_.rot.toEigen();
143+
config_.lidar_R_imu = lidar_T_imu_.rot.to_eigen();
144144
}
145145

146146
// Doers

cpp/bindings/pipelines/loam.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ namespace ev = evalio;
1313
namespace evalio {
1414
template<>
1515
inline ev::SE3 convert(const loam::Pose3d& from) {
16-
return ev::SE3(ev::SO3::fromEigen(from.rotation), from.translation);
16+
return ev::SE3(ev::SO3::from_eigen(from.rotation), from.translation);
1717
}
1818
} // namespace evalio
1919

cpp/bindings/ros_pc2.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -468,7 +468,7 @@ inline bool closest(const Stamp& idx, const Stamp& a, const Stamp& b) {
468468
}
469469

470470
// ---------------------- Create python bindings ---------------------- //
471-
inline void makeConversions(nb::module_& m) {
471+
inline void make_conversions(nb::module_& m) {
472472
nb::enum_<DataType>(m, "DataType")
473473
.value("UINT8", DataType::UINT8)
474474
.value("INT8", DataType::INT8)

cpp/bindings/types.h

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ namespace evalio {
2020

2121
// TODO: Check if copy/deepcopy works or not
2222

23-
inline void makeTypes(nb::module_& m) {
23+
inline void make_types(nb::module_& m) {
2424
nb::enum_<VisOption>(m, "VisOption", nb::is_flag())
2525
.value("MAP", VisOption::MAP, "Visualize the map.")
2626
.value("FEATURES", VisOption::FEATURES, "Visualize the features.")
@@ -58,7 +58,7 @@ inline void makeTypes(nb::module_& m) {
5858
)
5959
.def(nb::self - nb::self, "Compute the difference between two Durations")
6060
.def(nb::self + nb::self, "Add two Durations")
61-
.def("__repr__", &Duration::toString)
61+
.def("__repr__", &Duration::to_string)
6262
.def("__copy__", [](const Duration& self) { return Duration(self); })
6363
.def(
6464
"__deepcopy__",
@@ -124,7 +124,7 @@ inline void makeTypes(nb::module_& m) {
124124
)
125125
.def(nb::self + Duration(), "Add a Duration to a Stamp")
126126
.def(nb::self - Duration(), "Subtract a Duration from a Stamp")
127-
.def("__repr__", &Stamp::toString)
127+
.def("__repr__", &Stamp::to_string)
128128
.def("__copy__", [](const Stamp& self) { return Stamp(self); })
129129
.def(
130130
"__deepcopy__",
@@ -200,7 +200,7 @@ inline void makeTypes(nb::module_& m) {
200200
"Check for inequality",
201201
nb::sig("def __ne__(self, arg: object, /) -> bool")
202202
)
203-
.def("__repr__", &Point::toString)
203+
.def("__repr__", &Point::to_string)
204204
.def(
205205
"__getstate__",
206206
[](const Point& p) {
@@ -280,7 +280,7 @@ inline void makeTypes(nb::module_& m) {
280280
"Check for inequality",
281281
nb::sig("def __ne__(self, arg: object, /) -> bool")
282282
)
283-
.def("__repr__", &LidarMeasurement::toString)
283+
.def("__repr__", &LidarMeasurement::to_string)
284284
.def(
285285
"__getstate__",
286286
[](const LidarMeasurement& p) {
@@ -342,7 +342,7 @@ inline void makeTypes(nb::module_& m) {
342342
"Get the time between two consecutive scans as a Duration. Inverse "
343343
"of the rate."
344344
)
345-
.def("__repr__", &LidarParams::toString)
345+
.def("__repr__", &LidarParams::to_string)
346346
.doc() =
347347
"LidarParams is a structure for storing the parameters of a "
348348
"lidar sensor.";
@@ -380,7 +380,7 @@ inline void makeTypes(nb::module_& m) {
380380
"Check for inequality",
381381
nb::sig("def __ne__(self, arg: object, /) -> bool")
382382
)
383-
.def("__repr__", &ImuMeasurement::toString)
383+
.def("__repr__", &ImuMeasurement::to_string)
384384
.def(
385385
"__getstate__",
386386
[](const ImuMeasurement& p) {
@@ -473,7 +473,7 @@ inline void makeTypes(nb::module_& m) {
473473
.def_ro("rate", &ImuParams::rate, "Rate of the IMU sensor, in Hz.")
474474
.def_ro("brand", &ImuParams::brand, "Brand of the IMU sensor.")
475475
.def_ro("model", &ImuParams::model, "Model of the IMU sensor.")
476-
.def("__repr__", &ImuParams::toString)
476+
.def("__repr__", &ImuParams::to_string)
477477
.doc() = "ImuParams is a structure for storing the parameters of an IMU";
478478

479479
nb::class_<SO3>(m, "SO3")
@@ -491,15 +491,15 @@ inline void makeTypes(nb::module_& m) {
491491
.def_ro("qw", &SO3::qw, "Scalar component of the quaternion.")
492492
.def_static("identity", &SO3::identity, "Create an identity rotation.")
493493
.def_static(
494-
"fromMat",
495-
&SO3::fromMat,
494+
"from_mat",
495+
&SO3::from_mat,
496496
"mat"_a,
497497
"Create a rotation from a 3x3 rotation matrix."
498498
)
499499
.def_static("exp", &SO3::exp, "v"_a, "Create a rotation from a 3D vector.")
500500
.def("inverse", &SO3::inverse, "Compute the inverse of the rotation.")
501501
.def("log", &SO3::log, "Compute the logarithm of the rotation.")
502-
.def("toMat", &SO3::toMat, "Convert the rotation to a 3x3 matrix.")
502+
.def("to_mat", &SO3::to_mat, "Convert the rotation to a 3x3 matrix.")
503503
.def("rotate", &SO3::rotate, "v"_a, "Rotate a 3D vector by the rotation.")
504504
.def(nb::self * nb::self, "Compose two rotations.")
505505
.def(
@@ -512,7 +512,7 @@ inline void makeTypes(nb::module_& m) {
512512
"Check for inequality",
513513
nb::sig("def __ne__(self, arg: object, /) -> bool")
514514
)
515-
.def("__repr__", &SO3::toString)
515+
.def("__repr__", &SO3::to_string)
516516
.def("__copy__", [](const SO3& self) { return SO3(self); })
517517
.def(
518518
"__deepcopy__",
@@ -551,14 +551,14 @@ inline void makeTypes(nb::module_& m) {
551551
.def(nb::init<SE3>(), "other"_a, "Copy constructor for SE3.")
552552
.def_static("identity", &SE3::identity, "Create an identity SE3.")
553553
.def_static(
554-
"fromMat",
555-
&SE3::fromMat,
554+
"from_mat",
555+
&SE3::from_mat,
556556
"mat"_a,
557557
"Create a SE3 from a 4x4 transformation matrix."
558558
)
559559
.def_ro("rot", &SE3::rot, "Rotation as a SO3 object.")
560560
.def_ro("trans", &SE3::trans, "Translation as a 3D vector.")
561-
.def("toMat", &SE3::toMat, "Convert to a 4x4 matrix.")
561+
.def("to_mat", &SE3::to_mat, "Convert to a 4x4 matrix.")
562562
.def("inverse", &SE3::inverse, "Compute the inverse.")
563563
.def_static(
564564
"error",
@@ -588,7 +588,7 @@ inline void makeTypes(nb::module_& m) {
588588
"Check for inequality",
589589
nb::sig("def __ne__(self, arg: object, /) -> bool")
590590
)
591-
.def("__repr__", &SE3::toString)
591+
.def("__repr__", &SE3::to_string)
592592
.def("__copy__", [](const SE3& self) { return SE3(self); })
593593
.def(
594594
"__deepcopy__",

cpp/evalio/convert/sophus.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ inline SE3 convert(const Sophus::SE3d& in) {
1818

1919
template<>
2020
inline Sophus::SE3d convert(const SE3& in) {
21-
return Sophus::SE3d(Sophus::SO3d(in.rot.toEigen()), in.trans);
21+
return Sophus::SE3d(Sophus::SO3d(in.rot.to_eigen()), in.trans);
2222
}
2323

2424
} // namespace evalio

cpp/evalio/types.h

Lines changed: 31 additions & 31 deletions
Original file line numberDiff line numberDiff line change
@@ -36,11 +36,11 @@ struct Duration {
3636
return nsec;
3737
}
3838

39-
std::string toString() const {
40-
return "Duration(" + toStringBrief() + ")";
39+
std::string to_string() const {
40+
return "Duration(" + to_string_brief() + ")";
4141
}
4242

43-
std::string toStringBrief() const {
43+
std::string to_string_brief() const {
4444
return std::to_string(to_sec());
4545
}
4646

@@ -95,11 +95,11 @@ struct Stamp {
9595
return double(sec) + double(nsec) * 1e-9;
9696
}
9797

98-
std::string toString() const {
99-
return "Stamp(" + toStringBrief() + ")";
98+
std::string to_string() const {
99+
return "Stamp(" + to_string_brief() + ")";
100100
}
101101

102-
std::string toStringBrief() const {
102+
std::string to_string_brief() const {
103103
size_t n_zeros = 9;
104104
auto nsec_str = std::to_string(nsec);
105105
auto nsec_str_leading =
@@ -146,7 +146,7 @@ struct Point {
146146
uint8_t row = 0;
147147
uint16_t col = 0;
148148

149-
std::string toString() const {
149+
std::string to_string() const {
150150
return "Point(x: " + std::to_string(x) + ", y: " + std::to_string(y)
151151
+ ", z: " + std::to_string(z) + ", intensity: "
152152
+ std::to_string(intensity) + ", t: " + std::to_string(t.to_sec())
@@ -173,9 +173,9 @@ struct LidarMeasurement {
173173
LidarMeasurement(Stamp stamp, std::vector<Point> points) :
174174
stamp(stamp), points(points) {}
175175

176-
std::string toString() const {
176+
std::string to_string() const {
177177
std::ostringstream oss;
178-
oss << "LidarMeasurement(stamp: " << stamp.toStringBrief()
178+
oss << "LidarMeasurement(stamp: " << stamp.to_string_brief()
179179
<< ", num_points: " << points.size() << ")";
180180
return oss.str();
181181
}
@@ -227,7 +227,7 @@ struct LidarParams {
227227
std::string brand = "-";
228228
std::string model = "-";
229229

230-
std::string toString() const {
230+
std::string to_string() const {
231231
return "LidarParams(rows: " + std::to_string(num_rows)
232232
+ ", cols: " + std::to_string(num_columns) + ", min_range: "
233233
+ std::to_string(min_range) + ", max_range: " + std::to_string(max_range)
@@ -244,9 +244,9 @@ struct ImuMeasurement {
244244
Eigen::Vector3d gyro;
245245
Eigen::Vector3d accel;
246246

247-
std::string toString() const {
247+
std::string to_string() const {
248248
std::ostringstream oss;
249-
oss << "ImuMeasurement(stamp: " << stamp.toStringBrief() << ", gyro: ["
249+
oss << "ImuMeasurement(stamp: " << stamp.to_string_brief() << ", gyro: ["
250250
<< gyro.transpose() << "]"
251251
<< ", accel: [" << accel.transpose() << "])";
252252
return oss.str();
@@ -285,7 +285,7 @@ struct ImuParams {
285285
return imu_params;
286286
}
287287

288-
std::string toString() const {
288+
std::string to_string() const {
289289
std::ostringstream oss;
290290
oss << "ImuParams(gyro: " << gyro << ", accel: " << accel
291291
<< ", gyro_bias: " << gyro_bias << ", accel_bias: " << accel_bias
@@ -302,32 +302,32 @@ struct SO3 {
302302
double qz;
303303
double qw;
304304

305-
Eigen::Quaterniond toEigen() const {
305+
Eigen::Quaterniond to_eigen() const {
306306
return Eigen::Quaterniond(qw, qx, qy, qz);
307307
}
308308

309-
static SO3 fromEigen(const Eigen::Quaterniond& q) {
309+
static SO3 from_eigen(const Eigen::Quaterniond& q) {
310310
return SO3 {.qx = q.x(), .qy = q.y(), .qz = q.z(), .qw = q.w()};
311311
}
312312

313313
static SO3 identity() {
314314
return SO3 {.qx = 0, .qy = 0, .qz = 0, .qw = 1};
315315
}
316316

317-
static SO3 fromMat(const Eigen::Matrix3d& R) {
318-
return fromEigen(Eigen::Quaterniond(R));
317+
static SO3 from_mat(const Eigen::Matrix3d& R) {
318+
return from_eigen(Eigen::Quaterniond(R));
319319
}
320320

321321
SO3 inverse() const {
322322
return SO3 {.qx = -qx, .qy = -qy, .qz = -qz, .qw = qw};
323323
}
324324

325325
SO3 operator*(const SO3& other) const {
326-
return fromEigen(toEigen() * other.toEigen());
326+
return from_eigen(to_eigen() * other.to_eigen());
327327
}
328328

329329
Eigen::Vector3d rotate(const Eigen::Vector3d& v) const {
330-
return toEigen() * v;
330+
return to_eigen() * v;
331331
}
332332

333333
static Eigen::Matrix3d hat(const Eigen::Vector3d& xi) {
@@ -339,25 +339,25 @@ struct SO3 {
339339
static SO3 exp(const Eigen::Vector3d& v) {
340340
Eigen::AngleAxisd axis(v.norm(), v.normalized());
341341
Eigen::Quaterniond q(axis);
342-
return fromEigen(q);
342+
return from_eigen(q);
343343
}
344344

345345
Eigen::Vector3d log() const {
346-
Eigen::Quaterniond q = toEigen();
346+
Eigen::Quaterniond q = to_eigen();
347347
auto axis = Eigen::AngleAxisd(q);
348348
return axis.angle() * axis.axis();
349349
}
350350

351-
Eigen::Matrix3d toMat() const {
352-
return toEigen().toRotationMatrix();
351+
Eigen::Matrix3d to_mat() const {
352+
return to_eigen().toRotationMatrix();
353353
}
354354

355-
std::string toString() const {
355+
std::string to_string() const {
356356
return "SO3(x: " + std::to_string(qx) + ", y: " + std::to_string(qy)
357357
+ ", z: " + std::to_string(qz) + ", w: " + std::to_string(qw) + ")";
358358
}
359359

360-
std::string toStringBrief() const {
360+
std::string to_string_brief() const {
361361
return "x: " + std::to_string(qx) + ", y: " + std::to_string(qy)
362362
+ ", z: " + std::to_string(qz) + ", w: " + std::to_string(qw);
363363
}
@@ -381,13 +381,13 @@ struct SE3 {
381381
return SE3(SO3::identity(), Eigen::Vector3d::Zero());
382382
}
383383

384-
static SE3 fromMat(const Eigen::Matrix4d& T) {
385-
return SE3(SO3::fromMat(T.block<3, 3>(0, 0)), T.block<3, 1>(0, 3));
384+
static SE3 from_mat(const Eigen::Matrix4d& T) {
385+
return SE3(SO3::from_mat(T.block<3, 3>(0, 0)), T.block<3, 1>(0, 3));
386386
}
387387

388-
Eigen::Matrix4d toMat() const {
388+
Eigen::Matrix4d to_mat() const {
389389
Eigen::Matrix4d T = Eigen::Matrix4d::Identity();
390-
T.block<3, 3>(0, 0) = rot.toMat();
390+
T.block<3, 3>(0, 0) = rot.to_mat();
391391
T.block<3, 1>(0, 3) = trans;
392392
return T;
393393
}
@@ -451,9 +451,9 @@ struct SE3 {
451451
return SE3(rot * other.rot, rot.rotate(other.trans) + trans);
452452
}
453453

454-
std::string toString() const {
454+
std::string to_string() const {
455455
std::ostringstream oss;
456-
oss << "SE3(rot: [" << rot.toStringBrief() << "], "
456+
oss << "SE3(rot: [" << rot.to_string_brief() << "], "
457457
<< "t: [" << trans.transpose() << "])";
458458
return oss.str();
459459
}

0 commit comments

Comments
 (0)