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
99 changes: 99 additions & 0 deletions .clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
# https://gist.github.com/YodaEmbedding/c2c77dc693d11f3734d78489f9a6eea4
AccessModifierOffset: -2
AlignAfterOpenBracket: BlockIndent # New in v14. For earlier clang-format versions, use AlwaysBreak instead.
AlignConsecutiveMacros: false
AlignConsecutiveAssignments: false
AlignConsecutiveDeclarations: false
AlignEscapedNewlines: DontAlign
AlignOperands: false
AlignTrailingComments: false
AllowAllArgumentsOnNextLine: false
# AllowAllConstructorInitializersOnNextLine: false
AllowAllParametersOfDeclarationOnNextLine: false
AllowShortBlocksOnASingleLine: Empty
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: Empty
AllowShortIfStatementsOnASingleLine: Never
AllowShortLambdasOnASingleLine: All
AllowShortLoopsOnASingleLine: false
AlwaysBreakAfterReturnType: None
AlwaysBreakBeforeMultilineStrings: true
AlwaysBreakTemplateDeclarations: Yes
BinPackArguments: false
BinPackParameters: false
BreakBeforeBinaryOperators: NonAssignment
BreakBeforeBraces: Attach
BreakBeforeTernaryOperators: true
BreakConstructorInitializers: AfterColon
BreakInheritanceList: AfterColon
BreakStringLiterals: false
ColumnLimit: 80
CompactNamespaces: false
# ConstructorInitializerAllOnOneLineOrOnePerLine: true
ConstructorInitializerIndentWidth: 2
ContinuationIndentWidth: 2
Cpp11BracedListStyle: true
DerivePointerAlignment: false
FixNamespaceComments: true
IncludeBlocks: Regroup
IncludeCategories:
- Regex: '^<ext/.*\.h>'
Priority: 2
SortPriority: 0
CaseSensitive: false
- Regex: '^<.*\.h>'
Priority: 1
SortPriority: 0
CaseSensitive: false
- Regex: '^<.*'
Priority: 2
SortPriority: 0
CaseSensitive: false
- Regex: '.*'
Priority: 3
SortPriority: 0
CaseSensitive: false
IncludeIsMainRegex: '([-_](test|unittest))?$'
IndentCaseLabels: true
IndentPPDirectives: BeforeHash
IndentWidth: 2
IndentWrappedFunctionNames: false
KeepEmptyLinesAtTheStartOfBlocks: false
MaxEmptyLinesToKeep: 1
NamespaceIndentation: Inner
PointerAlignment: Left
ReferenceAlignment: Left # New in v13. int &name ==> int& name
ReflowComments: false
SeparateDefinitionBlocks: Always # New in v14.
SortIncludes: true
SortUsingDeclarations: true
SpaceAfterCStyleCast: false
SpaceAfterLogicalNot: false
SpaceAfterTemplateKeyword: false
SpaceBeforeAssignmentOperators: true
SpaceBeforeCpp11BracedList: true
SpaceBeforeCtorInitializerColon: true
SpaceBeforeInheritanceColon: false
SpaceBeforeParens: ControlStatements
SpaceBeforeRangeBasedForLoopColon: true
# SpaceInEmptyParentheses: false
SpacesBeforeTrailingComments: 1
SpacesInAngles: false
SpacesInCStyleCastParentheses: false
SpacesInContainerLiterals: false
SpacesInParentheses: false
SpacesInSquareBrackets: false
Standard: Cpp11
TabWidth: 2
UseTab: Never

# extras
BreakAfterAttributes: Always # v16. [[attribute]] ⏎ void f();
EmptyLineAfterAccessModifier: Never # v13.
EmptyLineBeforeAccessModifier: Always # v12.
InsertBraces: true # v15. if (true) return; ==> if (true) { return; }
InsertNewlineAtEOF: true # v16.
LineEnding: LF # v16.
QualifierAlignment: Left # v14. const int ==> int const
# RemoveParentheses: Return # v17. return(0) ==> return 0
RemoveSemicolon: true # v16.
19 changes: 11 additions & 8 deletions cpp/bindings/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,20 +9,23 @@ namespace nb = nanobind;

NB_MODULE(_cpp, m) {
m.def(
"abi_tag", []() { return nb::detail::abi_tag(); },
"Get the ABI tag of the current module. Useful for debugging when adding "
"external pipelines.");
"abi_tag",
[]() { return nb::detail::abi_tag(); },
"Get the ABI tag of the current module. Useful for debugging when adding "
"external pipelines."
);

auto m_types = m.def_submodule(
"types",
"Common types used for conversion between datasets and pipelines.");
"types",
"Common types used for conversion between datasets and pipelines."
);
evalio::makeTypes(m_types);

auto m_helpers = m.def_submodule(
"_helpers", "Helper functions for internal evalio usage.");
auto m_helpers =
m.def_submodule("_helpers", "Helper functions for internal evalio usage.");
evalio::makeConversions(m_helpers);

auto m_pipelines = m.def_submodule("pipelines", "Pipelines used in evalio.");
evalio::makeBasePipeline(m_pipelines);
evalio::makePipelines(m_pipelines);
}
}
119 changes: 84 additions & 35 deletions cpp/bindings/pipeline.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,69 +16,118 @@ using namespace nb::literals;

namespace evalio {

class PyPipeline : public evalio::Pipeline {
class PyPipeline: public evalio::Pipeline {
public:
NB_TRAMPOLINE(Pipeline, 9);

// Getters
const evalio::SE3 pose() override { NB_OVERRIDE_PURE(pose); }
const std::vector<evalio::Point> map() override { NB_OVERRIDE_PURE(map); }
evalio::SE3 const pose() override {
NB_OVERRIDE_PURE(pose);
}

const std::vector<evalio::Point> map() override {
NB_OVERRIDE_PURE(map);
}

// Setters
void set_imu_params(evalio::ImuParams params) override {
NB_OVERRIDE_PURE(set_imu_params, params);
}

void set_lidar_params(evalio::LidarParams params) override {
NB_OVERRIDE_PURE(set_lidar_params, params);
}

void set_imu_T_lidar(evalio::SE3 T) override {
NB_OVERRIDE_PURE(set_imu_T_lidar, T);
}

void set_params(std::map<std::string, Param> params) override {
NB_OVERRIDE_PURE(set_params, params);
}

// Doers
void initialize() override { NB_OVERRIDE_PURE(initialize); }
void initialize() override {
NB_OVERRIDE_PURE(initialize);
}

void add_imu(evalio::ImuMeasurement mm) override {
NB_OVERRIDE_PURE(add_imu, mm);
}

std::vector<Point> add_lidar(evalio::LidarMeasurement mm) override {
NB_OVERRIDE_PURE(add_lidar, mm);
}
};

inline void makeBasePipeline(nb::module_ &m) {
inline void makeBasePipeline(nb::module_& m) {
nb::class_<evalio::Pipeline, PyPipeline>(m, "Pipeline")
.def(nb::init<>(), "Construct a new pipeline.")
.def_static("name", &evalio::Pipeline::name, "Name of the pipeline.")
.def_static("default_params", &evalio::Pipeline::default_params,
"Default parameters for the pipeline.")
.def_static("url", &evalio::Pipeline::url,
"URL for more information about the pipeline.")
.def_static("version", &evalio::Pipeline::version,
"Version of the pipeline.")
.def("pose", &evalio::Pipeline::pose, "Most recent pose estimate.")
.def("map", &evalio::Pipeline::map, "Map of the environment.")
.def("initialize", &evalio::Pipeline::initialize,
"Initialize the pipeline. Must be called after constructing the "
"object and before setting parameters.")
.def("add_imu", &evalio::Pipeline::add_imu, "mm"_a,
"Register an IMU measurement.")
.def("add_lidar", &evalio::Pipeline::add_lidar, "mm"_a,
"Register a LiDAR measurement.")
.def("set_params", &evalio::Pipeline::set_params, "params"_a,
"Set parameters for the pipeline. This will override any default "
"parameters.")
.def("set_imu_params", &evalio::Pipeline::set_imu_params, "params"_a,
"Set IMU parameters for the pipeline.")
.def("set_lidar_params", &evalio::Pipeline::set_lidar_params, "params"_a,
"Set LiDAR parameters for the pipeline.")
.def("set_imu_T_lidar", &evalio::Pipeline::set_imu_T_lidar, "T"_a,
"Set the transformation from IMU to LiDAR frame.")
.doc() = "Base class for all pipelines. This class defines the interface "
"for interacting with pipelines, and is intended to be "
"subclassed by specific implementations.";
.def(nb::init<>(), "Construct a new pipeline.")
.def_static("name", &evalio::Pipeline::name, "Name of the pipeline.")
.def_static(
"default_params",
&evalio::Pipeline::default_params,
"Default parameters for the pipeline."
)
.def_static(
"url",
&evalio::Pipeline::url,
"URL for more information about the pipeline."
)
.def_static(
"version",
&evalio::Pipeline::version,
"Version of the pipeline."
)
.def("pose", &evalio::Pipeline::pose, "Most recent pose estimate.")
.def("map", &evalio::Pipeline::map, "Map of the environment.")
.def(
"initialize",
&evalio::Pipeline::initialize,
"Initialize the pipeline. Must be called after constructing the "
"object and before setting parameters."
)
.def(
"add_imu",
&evalio::Pipeline::add_imu,
"mm"_a,
"Register an IMU measurement."
)
.def(
"add_lidar",
&evalio::Pipeline::add_lidar,
"mm"_a,
"Register a LiDAR measurement."
)
.def(
"set_params",
&evalio::Pipeline::set_params,
"params"_a,
"Set parameters for the pipeline. This will override any default "
"parameters."
)
.def(
"set_imu_params",
&evalio::Pipeline::set_imu_params,
"params"_a,
"Set IMU parameters for the pipeline."
)
.def(
"set_lidar_params",
&evalio::Pipeline::set_lidar_params,
"params"_a,
"Set LiDAR parameters for the pipeline."
)
.def(
"set_imu_T_lidar",
&evalio::Pipeline::set_imu_T_lidar,
"T"_a,
"Set the transformation from IMU to LiDAR frame."
)
.doc() =
"Base class for all pipelines. This class defines the interface "
"for interacting with pipelines, and is intended to be "
"subclassed by specific implementations.";
}

} // namespace evalio
} // namespace evalio
44 changes: 22 additions & 22 deletions cpp/bindings/pipelines/bindings.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,40 +8,40 @@ namespace nb = nanobind;
using namespace nb::literals;

#ifdef EVALIO_KISS_ICP
#include "bindings/pipelines/kiss_icp.h"
#include "bindings/pipelines/kiss_icp.h"
#endif

#ifdef EVALIO_LIO_SAM
#include "bindings/pipelines/lio_sam.h"
#include "bindings/pipelines/lio_sam.h"
#endif

namespace evalio {
inline void makePipelines(nb::module_ &m) {
inline void makePipelines(nb::module_& m) {
// List all the pipelines here
#ifdef EVALIO_KISS_ICP
nb::class_<KissICP, evalio::Pipeline>(m, "KissICP")
.def(nb::init<>())
.def_static("name", &KissICP::name)
.def_static("default_params", &KissICP::default_params)
.def_static("url", &KissICP::url)
.def_static("version", &KissICP::version)
.doc() =
"KissICP LiDAR-only pipeline for point cloud registration. KissICP is "
"designed to be simple and easy to use, while still providing good "
"performance with minimal parameter tuning required across datasets.";
.def(nb::init<>())
.def_static("name", &KissICP::name)
.def_static("default_params", &KissICP::default_params)
.def_static("url", &KissICP::url)
.def_static("version", &KissICP::version)
.doc() =
"KissICP LiDAR-only pipeline for point cloud registration. KissICP is "
"designed to be simple and easy to use, while still providing good "
"performance with minimal parameter tuning required across datasets.";
#endif

#ifdef EVALIO_LIO_SAM
nb::class_<LioSam, evalio::Pipeline>(m, "LioSAM")
.def(nb::init<>())
.def_static("name", &LioSam::name)
.def_static("default_params", &LioSam::default_params)
.def_static("url", &LioSam::url)
.def_static("version", &LioSam::version)
.doc() =
"Lidar-Inertial Smoothing and Mapping (LioSAM) pipeline. LioSAM is an "
"extension of LOAM (=> uses planar and edge features) that additionally "
"utilizes an IMU for initializing ICP steps and for dewarping points";
.def(nb::init<>())
.def_static("name", &LioSam::name)
.def_static("default_params", &LioSam::default_params)
.def_static("url", &LioSam::url)
.def_static("version", &LioSam::version)
.doc() =
"Lidar-Inertial Smoothing and Mapping (LioSAM) pipeline. LioSAM is an "
"extension of LOAM (=> uses planar and edge features) that additionally "
"utilizes an IMU for initializing ICP steps and for dewarping points";
#endif
}
} // namespace evalio
} // namespace evalio
Loading
Loading