From f9b911e1a73ff41b39c500b82020d48a200c84ff Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sun, 18 Jun 2023 02:39:19 +0200 Subject: [PATCH] pymrpt: more wrapped functions --- doc/source/doxygen-docs/changelog.md | 2 + python/all_wrapped_mrpt_headers.hpp | 1 + .../mrpt/maps/OccupancyGridCellType.cpp | 23 + .../mrpt/math/CMatrixD.cpp | 112 +++ .../mrpt/math/CSplineInterpolator1D.cpp | 149 +++ .../mrpt/math/TPose3D.cpp | 48 + .../mrpt/math/distributions.cpp | 113 +++ .../mrpt/math/slerp.cpp | 37 + .../mrpt/obs/CObservationOdometry.cpp | 891 ++++++++++++++++++ .../mrpt/obs/CRawlog.cpp | 179 ++++ .../mrpt/opengl/CEllipsoidRangeBearing2D.cpp | 667 +++++++++++++ .../mrpt/opengl/CGridPlaneXZ.cpp | 582 ++++++++++++ .../mrpt/opengl/CRenderizable.cpp | 36 + .../mrpt/opengl/CSetOfLines.cpp | 564 +++++++++++ .../mrpt/opengl/CSphere.cpp | 610 ++++++++++++ .../mrpt/opengl/CText3D.cpp | 299 ++++++ .../mrpt/serialization/CArchive.cpp | 75 ++ .../mrpt/serialization/CArchive_1.cpp | 154 ++- .../mrpt/serialization/CArchive_2.cpp | 96 ++ .../mrpt/serialization/CArchive_3.cpp | 27 + .../mrpt/system/crc.cpp | 150 +++ .../mrpt/system/scheduler.cpp | 34 + .../mrpt/vision/utils.cpp | 301 ++++++ python/generated-sources-pybind/pymrpt.cpp | 10 +- .../generated-sources-pybind/pymrpt.sources | 5 +- .../unknown/unknown.cpp | 384 +------- .../unknown/unknown_1.cpp | 384 +++++++- .../unknown/unknown_2.cpp | 54 +- .../unknown/unknown_3.cpp | 55 +- .../unknown/unknown_4.cpp | 35 +- .../unknown/unknown_5.cpp | 428 +-------- .../unknown/unknown_6.cpp | 385 ++++---- .../unknown/unknown_7.cpp | 348 +++---- .../unknown/unknown_8.cpp | 387 ++++++++ python/serialization-python-instances.h | 37 + 35 files changed, 6443 insertions(+), 1219 deletions(-) create mode 100644 python/generated-sources-pybind/mrpt/maps/OccupancyGridCellType.cpp create mode 100644 python/generated-sources-pybind/mrpt/math/CMatrixD.cpp create mode 100644 python/generated-sources-pybind/mrpt/math/CSplineInterpolator1D.cpp create mode 100644 python/generated-sources-pybind/mrpt/math/TPose3D.cpp create mode 100644 python/generated-sources-pybind/mrpt/math/distributions.cpp create mode 100644 python/generated-sources-pybind/mrpt/math/slerp.cpp create mode 100644 python/generated-sources-pybind/mrpt/obs/CObservationOdometry.cpp create mode 100644 python/generated-sources-pybind/mrpt/obs/CRawlog.cpp create mode 100644 python/generated-sources-pybind/mrpt/opengl/CEllipsoidRangeBearing2D.cpp create mode 100644 python/generated-sources-pybind/mrpt/opengl/CGridPlaneXZ.cpp create mode 100644 python/generated-sources-pybind/mrpt/opengl/CRenderizable.cpp create mode 100644 python/generated-sources-pybind/mrpt/opengl/CSetOfLines.cpp create mode 100644 python/generated-sources-pybind/mrpt/opengl/CSphere.cpp create mode 100644 python/generated-sources-pybind/mrpt/opengl/CText3D.cpp create mode 100644 python/generated-sources-pybind/mrpt/serialization/CArchive_2.cpp create mode 100644 python/generated-sources-pybind/mrpt/serialization/CArchive_3.cpp create mode 100644 python/generated-sources-pybind/mrpt/system/crc.cpp create mode 100644 python/generated-sources-pybind/mrpt/system/scheduler.cpp create mode 100644 python/generated-sources-pybind/mrpt/vision/utils.cpp create mode 100644 python/generated-sources-pybind/unknown/unknown_8.cpp create mode 100644 python/serialization-python-instances.h diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 7b7be39b21..55f1eee20b 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -7,6 +7,8 @@ - \ref mrpt_comms_grp - mrpt::comms::CInterfaceFTDI Fix usage of deprecated API in libftdi - Python: + - New wrapped functions: + - `mrpt.serialization.archiveFrom()` - Fix python install directory: - ROS 1: `[...]/lib/python3/site-packages/` - ROS 2 or pure Debian: `[...]/lib/python3.X/site-packages/` diff --git a/python/all_wrapped_mrpt_headers.hpp b/python/all_wrapped_mrpt_headers.hpp index 4c14a2975b..ed53215b05 100644 --- a/python/all_wrapped_mrpt_headers.hpp +++ b/python/all_wrapped_mrpt_headers.hpp @@ -35,6 +35,7 @@ // serialization #include #include +#include "./serialization-python-instances.h" // rtti #include diff --git a/python/generated-sources-pybind/mrpt/maps/OccupancyGridCellType.cpp b/python/generated-sources-pybind/mrpt/maps/OccupancyGridCellType.cpp new file mode 100644 index 0000000000..90f7999d87 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/maps/OccupancyGridCellType.cpp @@ -0,0 +1,23 @@ +#include +#include // __str__ + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_maps_OccupancyGridCellType(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::maps::OccGridCellTraits file:mrpt/maps/OccupancyGridCellType.h line:32 + pybind11::class_> cl(M("mrpt::maps"), "OccGridCellTraits", ""); + cl.def( pybind11::init( [](){ return new mrpt::maps::OccGridCellTraits(); } ) ); + } +} diff --git a/python/generated-sources-pybind/mrpt/math/CMatrixD.cpp b/python/generated-sources-pybind/mrpt/math/CMatrixD.cpp new file mode 100644 index 0000000000..09c6542ff7 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/math/CMatrixD.cpp @@ -0,0 +1,112 @@ +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::math::CMatrixD file:mrpt/math/CMatrixD.h line:23 +struct PyCallBack_mrpt_math_CMatrixD : public mrpt::math::CMatrixD { + using mrpt::math::CMatrixD::CMatrixD; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMatrixD::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMatrixD::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMatrixD::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMatrixD::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMatrixD::serializeFrom(a0, a1); + } +}; + +void bind_mrpt_math_CMatrixD(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::math::CMatrixD file:mrpt/math/CMatrixD.h line:23 + pybind11::class_, PyCallBack_mrpt_math_CMatrixD, mrpt::serialization::CSerializable> cl(M("mrpt::math"), "CMatrixD", "This class is a \"CSerializable\" wrapper for\n \"CMatrixDynamic\".\n \n\n For a complete introduction to Matrices and vectors in MRPT, see:\n https://www.mrpt.org/Matrices_vectors_arrays_and_Linear_Algebra_MRPT_and_Eigen_classes\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixD(); }, [](){ return new PyCallBack_mrpt_math_CMatrixD(); } ) ); + cl.def( pybind11::init(), pybind11::arg("row"), pybind11::arg("col") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_math_CMatrixD const &o){ return new PyCallBack_mrpt_math_CMatrixD(o); } ) ); + cl.def( pybind11::init( [](mrpt::math::CMatrixD const &o){ return new mrpt::math::CMatrixD(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::math::CMatrixD::getClassName, "C++: mrpt::math::CMatrixD::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::math::CMatrixD::GetRuntimeClassIdStatic, "C++: mrpt::math::CMatrixD::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::math::CMatrixD::*)() const) &mrpt::math::CMatrixD::GetRuntimeClass, "C++: mrpt::math::CMatrixD::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::math::CMatrixD::*)() const) &mrpt::math::CMatrixD::clone, "C++: mrpt::math::CMatrixD::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::math::CMatrixD::CreateObject, "C++: mrpt::math::CMatrixD::CreateObject() --> class std::shared_ptr"); + cl.def("assign", (class mrpt::math::CMatrixD & (mrpt::math::CMatrixD::*)(const class mrpt::math::CMatrixD &)) &mrpt::math::CMatrixD::operator=, "C++: mrpt::math::CMatrixD::operator=(const class mrpt::math::CMatrixD &) --> class mrpt::math::CMatrixD &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/math/CSplineInterpolator1D.cpp b/python/generated-sources-pybind/mrpt/math/CSplineInterpolator1D.cpp new file mode 100644 index 0000000000..61e67e06d6 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/math/CSplineInterpolator1D.cpp @@ -0,0 +1,149 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::math::CSplineInterpolator1D file:mrpt/math/CSplineInterpolator1D.h line:25 +struct PyCallBack_mrpt_math_CSplineInterpolator1D : public mrpt::math::CSplineInterpolator1D { + using mrpt::math::CSplineInterpolator1D::CSplineInterpolator1D; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSplineInterpolator1D::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSplineInterpolator1D::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSplineInterpolator1D::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSplineInterpolator1D::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSplineInterpolator1D::serializeFrom(a0, a1); + } +}; + +void bind_mrpt_math_CSplineInterpolator1D(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::math::CSplineInterpolator1D file:mrpt/math/CSplineInterpolator1D.h line:25 + pybind11::class_, PyCallBack_mrpt_math_CSplineInterpolator1D, mrpt::serialization::CSerializable> cl(M("mrpt::math"), "CSplineInterpolator1D", "A (persistent) sequence of (x,y) coordinates, allowing queries of\n intermediate points through spline interpolation, where possible.\n This class internally relies on mrpt::math::spline. Optionally the y\n coordinate can be set as wrapped in ]-pi,pi].\n For querying interpolated points, see\n \\ sa mrpt::math::spline, mrpt::poses::CPose3DInterpolator\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::math::CSplineInterpolator1D(); }, [](){ return new PyCallBack_mrpt_math_CSplineInterpolator1D(); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("wrap2pi") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_math_CSplineInterpolator1D const &o){ return new PyCallBack_mrpt_math_CSplineInterpolator1D(o); } ) ); + cl.def( pybind11::init( [](mrpt::math::CSplineInterpolator1D const &o){ return new mrpt::math::CSplineInterpolator1D(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::math::CSplineInterpolator1D::getClassName, "C++: mrpt::math::CSplineInterpolator1D::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::math::CSplineInterpolator1D::GetRuntimeClassIdStatic, "C++: mrpt::math::CSplineInterpolator1D::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::math::CSplineInterpolator1D::*)() const) &mrpt::math::CSplineInterpolator1D::GetRuntimeClass, "C++: mrpt::math::CSplineInterpolator1D::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::math::CSplineInterpolator1D::*)() const) &mrpt::math::CSplineInterpolator1D::clone, "C++: mrpt::math::CSplineInterpolator1D::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::math::CSplineInterpolator1D::CreateObject, "C++: mrpt::math::CSplineInterpolator1D::CreateObject() --> class std::shared_ptr"); + cl.def("setWrap2pi", (void (mrpt::math::CSplineInterpolator1D::*)(bool)) &mrpt::math::CSplineInterpolator1D::setWrap2pi, "If set to true, the interpolated data will be wrapped to ]-pi,pi] \n\nC++: mrpt::math::CSplineInterpolator1D::setWrap2pi(bool) --> void", pybind11::arg("wrap")); + cl.def("getWrap2pi", (bool (mrpt::math::CSplineInterpolator1D::*)()) &mrpt::math::CSplineInterpolator1D::getWrap2pi, "Return the wrap property \n\nC++: mrpt::math::CSplineInterpolator1D::getWrap2pi() --> bool"); + cl.def("appendXY", (void (mrpt::math::CSplineInterpolator1D::*)(double, double)) &mrpt::math::CSplineInterpolator1D::appendXY, "Append a new point: \n\nC++: mrpt::math::CSplineInterpolator1D::appendXY(double, double) --> void", pybind11::arg("x"), pybind11::arg("y")); + cl.def("clear", (void (mrpt::math::CSplineInterpolator1D::*)()) &mrpt::math::CSplineInterpolator1D::clear, "Clears all stored points \n\nC++: mrpt::math::CSplineInterpolator1D::clear() --> void"); + cl.def("query", (double & (mrpt::math::CSplineInterpolator1D::*)(double, double &, bool &) const) &mrpt::math::CSplineInterpolator1D::query, "Query an interpolation of the curve at some \"x\".\n The result is stored in \"y\". If the \"x\" point is out of range,\n \"valid_out\" is set to false.\n \n\n A reference to \"y\"\n \n\n queryVector\n\nC++: mrpt::math::CSplineInterpolator1D::query(double, double &, bool &) const --> double &", pybind11::return_value_policy::automatic, pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("out_valid")); + cl.def("assign", (class mrpt::math::CSplineInterpolator1D & (mrpt::math::CSplineInterpolator1D::*)(const class mrpt::math::CSplineInterpolator1D &)) &mrpt::math::CSplineInterpolator1D::operator=, "C++: mrpt::math::CSplineInterpolator1D::operator=(const class mrpt::math::CSplineInterpolator1D &) --> class mrpt::math::CSplineInterpolator1D &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::math::TObject2D file:mrpt/math/TObject2D.h line:29 + pybind11::class_> cl(M("mrpt::math"), "TObject2D", "A variant type for any lightweight 2D type: point, segment, line, polygon.\n Use provided helper method, or directly access the variant `data`.\n\n \n TPoint2D,TSegment2D,TLine2D,TPolygon2D"); + cl.def( pybind11::init( [](){ return new mrpt::math::TObject2D(); } ) ); + cl.def( pybind11::init( [](mrpt::math::TObject2D const &o){ return new mrpt::math::TObject2D(o); } ) ); + cl.def("isPoint", (bool (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::isPoint, "Checks whether content is a point. \n\nC++: mrpt::math::TObject2D::isPoint() const --> bool"); + cl.def("isSegment", (bool (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::isSegment, "Checks whether content is a segment. \n\nC++: mrpt::math::TObject2D::isSegment() const --> bool"); + cl.def("isLine", (bool (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::isLine, "Checks whether content is a line.\n\nC++: mrpt::math::TObject2D::isLine() const --> bool"); + cl.def("isPolygon", (bool (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::isPolygon, "Checks whether content is a polygon.\n\nC++: mrpt::math::TObject2D::isPolygon() const --> bool"); + cl.def("empty", (bool (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::empty, "C++: mrpt::math::TObject2D::empty() const --> bool"); + cl.def("getSegment", (bool (mrpt::math::TObject2D::*)(struct mrpt::math::TSegment2D &) const) &mrpt::math::TObject2D::getSegment, "returns true if the objects is a segment, and retrieves its value in\n `out`. Prefer getAs(). This method was left in mrpt 2.3.0 for backwards\n compatibility.\n\nC++: mrpt::math::TObject2D::getSegment(struct mrpt::math::TSegment2D &) const --> bool", pybind11::arg("out")); + cl.def("getLine", (bool (mrpt::math::TObject2D::*)(struct mrpt::math::TLine2D &) const) &mrpt::math::TObject2D::getLine, "returns true if the objects is a line, and retrieves its value in\n `out`. Prefer getAs(). This method was left in mrpt 2.3.0 for backwards\n compatibility.\n\nC++: mrpt::math::TObject2D::getLine(struct mrpt::math::TLine2D &) const --> bool", pybind11::arg("out")); + cl.def("getPolygon", (bool (mrpt::math::TObject2D::*)(class mrpt::math::TPolygon2D &) const) &mrpt::math::TObject2D::getPolygon, "returns true if the objects is a TPolygon2D, and retrieves its value in\n `out`. Prefer getAs(). This method was left in mrpt 2.3.0 for backwards\n compatibility.\n\nC++: mrpt::math::TObject2D::getPolygon(class mrpt::math::TPolygon2D &) const --> bool", pybind11::arg("out")); + cl.def("asString", (std::string (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::asString, "Gets a string with the type and the parameters of the object. `empty` if\n not defined. \n\n New in MRPT 2.3.0 \n\nC++: mrpt::math::TObject2D::asString() const --> std::string"); + cl.def("generate3DObject", (struct mrpt::math::TObject3D (mrpt::math::TObject2D::*)() const) &mrpt::math::TObject2D::generate3DObject, "Cast into 3D space. \n\nC++: mrpt::math::TObject2D::generate3DObject() const --> struct mrpt::math::TObject3D"); + + cl.def("__str__", [](mrpt::math::TObject2D const &o) -> std::string { std::ostringstream s; using namespace mrpt::math; s << o; return s.str(); } ); + } +} diff --git a/python/generated-sources-pybind/mrpt/math/TPose3D.cpp b/python/generated-sources-pybind/mrpt/math/TPose3D.cpp new file mode 100644 index 0000000000..f6f2464f33 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/math/TPose3D.cpp @@ -0,0 +1,48 @@ +#include +#include +#include +#include +#include // __str__ +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_math_TPose3D(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::math::TPose3D file:mrpt/math/TPose3D.h line:26 + pybind11::class_, mrpt::math::TPoseOrPoint> cl(M("mrpt::math"), "TPose3D", "Lightweight 3D pose (three spatial coordinates, plus three angular\n coordinates). Allows coordinate access using [] operator.\n \n\n mrpt::poses::CPose3D\n \n\n\n "); + cl.def( pybind11::init(), pybind11::arg("p") ); + + cl.def( pybind11::init(), pybind11::arg("_x"), pybind11::arg("_y"), pybind11::arg("_z"), pybind11::arg("_yaw"), pybind11::arg("_pitch"), pybind11::arg("_roll") ); + + cl.def( pybind11::init( [](){ return new mrpt::math::TPose3D(); } ) ); + cl.def( pybind11::init( [](mrpt::math::TPose3D const &o){ return new mrpt::math::TPose3D(o); } ) ); + cl.def_readwrite("x", &mrpt::math::TPose3D::x); + cl.def_readwrite("y", &mrpt::math::TPose3D::y); + cl.def_readwrite("z", &mrpt::math::TPose3D::z); + cl.def_readwrite("yaw", &mrpt::math::TPose3D::yaw); + cl.def_readwrite("pitch", &mrpt::math::TPose3D::pitch); + cl.def_readwrite("roll", &mrpt::math::TPose3D::roll); + cl.def_static("Identity", (struct mrpt::math::TPose3D (*)()) &mrpt::math::TPose3D::Identity, "Returns the identity transformation, T=eye(4) \n\nC++: mrpt::math::TPose3D::Identity() --> struct mrpt::math::TPose3D"); + cl.def_static("FromString", (struct mrpt::math::TPose3D (*)(const std::string &)) &mrpt::math::TPose3D::FromString, "See fromString() for a description of the expected string format. \n\nC++: mrpt::math::TPose3D::FromString(const std::string &) --> struct mrpt::math::TPose3D", pybind11::arg("s")); + cl.def("__getitem__", (double & (mrpt::math::TPose3D::*)(size_t)) &mrpt::math::TPose3D::operator[], "Coordinate access using operator[]. Order: x,y,z,yaw,pitch,roll \n\nC++: mrpt::math::TPose3D::operator[](size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); + cl.def("norm", (double (mrpt::math::TPose3D::*)() const) &mrpt::math::TPose3D::norm, "Pose's spatial coordinates norm.\n\nC++: mrpt::math::TPose3D::norm() const --> double"); + cl.def("asString", (void (mrpt::math::TPose3D::*)(std::string &) const) &mrpt::math::TPose3D::asString, "Returns a human-readable textual representation of the object (eg: \"[x y\n z yaw pitch roll]\", angles in degrees.)\n \n\n fromString\n\nC++: mrpt::math::TPose3D::asString(std::string &) const --> void", pybind11::arg("s")); + cl.def("asString", (std::string (mrpt::math::TPose3D::*)() const) &mrpt::math::TPose3D::asString, "C++: mrpt::math::TPose3D::asString() const --> std::string"); + cl.def("composePose", (void (mrpt::math::TPose3D::*)(const struct mrpt::math::TPose3D, struct mrpt::math::TPose3D &) const) &mrpt::math::TPose3D::composePose, "C++: mrpt::math::TPose3D::composePose(const struct mrpt::math::TPose3D, struct mrpt::math::TPose3D &) const --> void", pybind11::arg("other"), pybind11::arg("result")); + cl.def("__add__", (struct mrpt::math::TPose3D (mrpt::math::TPose3D::*)(const struct mrpt::math::TPose3D &) const) &mrpt::math::TPose3D::operator+, "Operator \"oplus\" pose composition: \"ret=this b\" \n CPose3D\n \n\n [Added in MRPT 2.1.5] \n\nC++: mrpt::math::TPose3D::operator+(const struct mrpt::math::TPose3D &) const --> struct mrpt::math::TPose3D", pybind11::arg("b")); + cl.def("fromString", (void (mrpt::math::TPose3D::*)(const std::string &)) &mrpt::math::TPose3D::fromString, "Set the current object value from a string generated by 'asString' (eg:\n \"[x y z yaw pitch roll]\" with the three angles given in degrees. )\n \n\n asString\n \n\n std::exception On invalid format\n\nC++: mrpt::math::TPose3D::fromString(const std::string &) --> void", pybind11::arg("s")); + cl.def("assign", (struct mrpt::math::TPose3D & (mrpt::math::TPose3D::*)(const struct mrpt::math::TPose3D &)) &mrpt::math::TPose3D::operator=, "C++: mrpt::math::TPose3D::operator=(const struct mrpt::math::TPose3D &) --> struct mrpt::math::TPose3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/math/distributions.cpp b/python/generated-sources-pybind/mrpt/math/distributions.cpp new file mode 100644 index 0000000000..191aab6e6c --- /dev/null +++ b/python/generated-sources-pybind/mrpt/math/distributions.cpp @@ -0,0 +1,113 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_math_distributions(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::math::normalPDF(double, double, double) file:mrpt/math/distributions.h line:25 + M("mrpt::math").def("normalPDF", (double (*)(double, double, double)) &mrpt::math::normalPDF, "Evaluates the univariate normal (Gaussian) distribution at a given point\n \"x\".\n\nC++: mrpt::math::normalPDF(double, double, double) --> double", pybind11::arg("x"), pybind11::arg("mu"), pybind11::arg("std")); + + // mrpt::math::normalQuantile(double) file:mrpt/math/distributions.h line:132 + M("mrpt::math").def("normalQuantile", (double (*)(double)) &mrpt::math::normalQuantile, "Evaluates the Gaussian distribution quantile for the probability value\n p=[0,1].\n The employed approximation is that from Peter J. Acklam\n (pjacklam.no),\n freely available in http://home.online.no/~pjacklam.\n\nC++: mrpt::math::normalQuantile(double) --> double", pybind11::arg("p")); + + // mrpt::math::normalCDF(double) file:mrpt/math/distributions.h line:139 + M("mrpt::math").def("normalCDF", (double (*)(double)) &mrpt::math::normalCDF, "Evaluates the Gaussian cumulative density function.\n The employed approximation is that from W. J. Cody\n freely available in http://www.netlib.org/specfun/erf\n \n\n Equivalent to MATLAB normcdf(x,mu,s) with p=(x-mu)/s\n\nC++: mrpt::math::normalCDF(double) --> double", pybind11::arg("p")); + + // mrpt::math::chi2inv(double, unsigned int) file:mrpt/math/distributions.h line:147 + M("mrpt::math").def("chi2inv", [](double const & a0) -> double { return mrpt::math::chi2inv(a0); }, "", pybind11::arg("P")); + M("mrpt::math").def("chi2inv", (double (*)(double, unsigned int)) &mrpt::math::chi2inv, "The \"quantile\" of the Chi-Square distribution, for dimension \"dim\" and\n probability 0 double", pybind11::arg("P"), pybind11::arg("dim")); + + // mrpt::math::noncentralChi2CDF(unsigned int, double, double) file:mrpt/math/distributions.h line:169 + M("mrpt::math").def("noncentralChi2CDF", (double (*)(unsigned int, double, double)) &mrpt::math::noncentralChi2CDF, "Cumulative non-central chi square distribution (approximate).\n\n Computes approximate values of the cumulative density of a chi square\ndistribution with \n and noncentrality parameter at the given argument\n i.e. the probability that a random number drawn from the\ndistribution is below \n It uses the approximate transform into a normal distribution due to Wilson\nand Hilferty\n (see Abramovitz, Stegun: \"Handbook of Mathematical Functions\", formula\n26.3.32).\n The algorithm's running time is independent of the inputs. The accuracy is\nonly\n about 0.1 for few degrees of freedom, but reaches about 0.001 above dof = 5.\n\n \n Function code from the Vigra project\n(http://hci.iwr.uni-heidelberg.de/vigra/); code under \"MIT X11 License\", GNU\nGPL-compatible.\n \n\n noncentralChi2PDF_CDF\n\nC++: mrpt::math::noncentralChi2CDF(unsigned int, double, double) --> double", pybind11::arg("degreesOfFreedom"), pybind11::arg("noncentrality"), pybind11::arg("arg")); + + // mrpt::math::chi2CDF(unsigned int, double) file:mrpt/math/distributions.h line:185 + M("mrpt::math").def("chi2CDF", (double (*)(unsigned int, double)) &mrpt::math::chi2CDF, "Cumulative chi square distribution.\n\n Computes the cumulative density of a chi square distribution with \n and tolerance at the given argument i.e. the probability\n that\n a random number drawn from the distribution is below \n by calling noncentralChi2CDF(degreesOfFreedom, 0.0, arg, accuracy).\n\n \n Function code from the Vigra project\n (http://hci.iwr.uni-heidelberg.de/vigra/); code under \"MIT X11 License\", GNU\n GPL-compatible.\n\nC++: mrpt::math::chi2CDF(unsigned int, double) --> double", pybind11::arg("degreesOfFreedom"), pybind11::arg("arg")); + + // mrpt::math::chi2PDF(unsigned int, double, double) file:mrpt/math/distributions.h line:197 + M("mrpt::math").def("chi2PDF", [](unsigned int const & a0, double const & a1) -> double { return mrpt::math::chi2PDF(a0, a1); }, "", pybind11::arg("degreesOfFreedom"), pybind11::arg("arg")); + M("mrpt::math").def("chi2PDF", (double (*)(unsigned int, double, double)) &mrpt::math::chi2PDF, "Chi square distribution PDF.\n Computes the density of a chi square distribution with \n and tolerance at the given argument \n by calling noncentralChi2(degreesOfFreedom, 0.0, arg, accuracy).\n \n\n Function code from the Vigra project\n(http://hci.iwr.uni-heidelberg.de/vigra/); code under \"MIT X11 License\", GNU\nGPL-compatible.\n\n \n Equivalent to MATLAB's chi2pdf(arg,degreesOfFreedom)\n\nC++: mrpt::math::chi2PDF(unsigned int, double, double) --> double", pybind11::arg("degreesOfFreedom"), pybind11::arg("arg"), pybind11::arg("accuracy")); + + // mrpt::math::noncentralChi2PDF_CDF(unsigned int, double, double, double) file:mrpt/math/distributions.h line:204 + M("mrpt::math").def("noncentralChi2PDF_CDF", [](unsigned int const & a0, double const & a1, double const & a2) -> std::pair { return mrpt::math::noncentralChi2PDF_CDF(a0, a1, a2); }, "", pybind11::arg("degreesOfFreedom"), pybind11::arg("noncentrality"), pybind11::arg("arg")); + M("mrpt::math").def("noncentralChi2PDF_CDF", (struct std::pair (*)(unsigned int, double, double, double)) &mrpt::math::noncentralChi2PDF_CDF, "Returns the 'exact' PDF (first) and CDF (second) of a Non-central\n chi-squared probability distribution, using an iterative method.\n \n\n Equivalent to MATLAB's ncx2cdf(arg,degreesOfFreedom,noncentrality)\n\nC++: mrpt::math::noncentralChi2PDF_CDF(unsigned int, double, double, double) --> struct std::pair", pybind11::arg("degreesOfFreedom"), pybind11::arg("noncentrality"), pybind11::arg("arg"), pybind11::arg("eps")); + + { // mrpt::math::LowPassFilter_IIR1 file:mrpt/math/filters.h line:24 + pybind11::class_> cl(M("mrpt::math"), "LowPassFilter_IIR1", "1-order low-pass IIR filter.\n Discrete time equation: `y[k]=alpha*y[k-1]+(1-alpha)*x[k]`.\n With: x[k] input, y[k] output, alpha a parameter in [0,1]"); + cl.def( pybind11::init( [](){ return new mrpt::math::LowPassFilter_IIR1(); } ), "doc" ); + cl.def( pybind11::init( [](double const & a0){ return new mrpt::math::LowPassFilter_IIR1(a0); } ), "doc" , pybind11::arg("alpha")); + cl.def( pybind11::init(), pybind11::arg("alpha"), pybind11::arg("y_k_minus_1") ); + + cl.def( pybind11::init( [](mrpt::math::LowPassFilter_IIR1 const &o){ return new mrpt::math::LowPassFilter_IIR1(o); } ) ); + cl.def_readwrite("alpha", &mrpt::math::LowPassFilter_IIR1::alpha); + cl.def("filter", (double (mrpt::math::LowPassFilter_IIR1::*)(double)) &mrpt::math::LowPassFilter_IIR1::filter, "Processes one input sample, updates the filter state and return the\n filtered value. \n\nC++: mrpt::math::LowPassFilter_IIR1::filter(double) --> double", pybind11::arg("x")); + cl.def("getLastOutput", (double (mrpt::math::LowPassFilter_IIR1::*)() const) &mrpt::math::LowPassFilter_IIR1::getLastOutput, "C++: mrpt::math::LowPassFilter_IIR1::getLastOutput() const --> double"); + } + // mrpt::math::fresnel_sin_integral(double) file:mrpt/math/fresnel.h line:25 + M("mrpt::math").def("fresnel_sin_integral", (double (*)(double)) &mrpt::math::fresnel_sin_integral, "Evaluates the integral from 0 to x of sqrt(2/pi) sin(t^2) dt. Equivalent to\n MATLAB fresnels()\n \n\n https://en.wikipedia.org/wiki/Fresnel_integral\n \n\n Code based on\n http://www.mymathlib.com/functions/fresnel_sin_cos_integrals.html \n\nC++: mrpt::math::fresnel_sin_integral(double) --> double", pybind11::arg("x")); + + // mrpt::math::fresnel_cos_integral(double) file:mrpt/math/fresnel.h line:32 + M("mrpt::math").def("fresnel_cos_integral", (double (*)(double)) &mrpt::math::fresnel_cos_integral, "Evaluates the integral from 0 to x of sqrt(2/pi) cos(t^2) dt. Equivalent to\nMATLAB fresnelc()\n \n\n https://en.wikipedia.org/wiki/Fresnel_integral\n\n Code based on\nhttp://www.mymathlib.com/functions/fresnel_sin_cos_integrals.html \n\nC++: mrpt::math::fresnel_cos_integral(double) --> double", pybind11::arg("x")); + + // mrpt::math::lfresnel_sin_integral(long double) file:mrpt/math/fresnel.h line:35 + M("mrpt::math").def("lfresnel_sin_integral", (long double (*)(long double)) &mrpt::math::lfresnel_sin_integral, "long double version of fresnel_sin_integral \n\nC++: mrpt::math::lfresnel_sin_integral(long double) --> long double", pybind11::arg("x")); + + // mrpt::math::lfresnel_cos_integral(long double) file:mrpt/math/fresnel.h line:38 + M("mrpt::math").def("lfresnel_cos_integral", (long double (*)(long double)) &mrpt::math::lfresnel_cos_integral, "long double version of fresnel_cos_integral \n\nC++: mrpt::math::lfresnel_cos_integral(long double) --> long double", pybind11::arg("x")); + + // mrpt::math::interpolate2points(const double, const double, const double, const double, const double, bool) file:mrpt/math/interp_fit.h line:36 + M("mrpt::math").def("interpolate2points", [](const double & a0, const double & a1, const double & a2, const double & a3, const double & a4) -> double { return mrpt::math::interpolate2points(a0, a1, a2, a3, a4); }, "", pybind11::arg("x"), pybind11::arg("x0"), pybind11::arg("y0"), pybind11::arg("x1"), pybind11::arg("y1")); + M("mrpt::math").def("interpolate2points", (double (*)(const double, const double, const double, const double, const double, bool)) &mrpt::math::interpolate2points, "Linear interpolation/extrapolation: evaluates at \"x\" the line\n (x0,y0)-(x1,y1).\n If wrap2pi is true, output is wrapped to ]-pi,pi] (It is assumed that input\n \"y\" values already are in the correct range).\n \n\n spline, interpolate, leastSquareLinearFit\n\nC++: mrpt::math::interpolate2points(const double, const double, const double, const double, const double, bool) --> double", pybind11::arg("x"), pybind11::arg("x0"), pybind11::arg("y0"), pybind11::arg("x1"), pybind11::arg("y1"), pybind11::arg("wrap2pi")); + + { // mrpt::math::ModelSearch file:mrpt/math/model_search.h line:65 + pybind11::class_> cl(M("mrpt::math"), "ModelSearch", "Model search implementations: RANSAC and genetic algorithm\n\n The type is a user-supplied struct/class that implements this\n interface:\n - Types:\n - : The numeric type to use (typ: double, float)\n - : The type of the model to be fitted (for example: A matrix, a\n TLine2D, a TPlane3D, ...)\n - Methods:\n - size_t getSampleCount() const : return the number of samples. This\n should not change during a model search.\n - bool fitModel( const std::vector& useIndices, Model& model )\n const :\n This function fits a model to the data selected by the indices. The return\n value indicates the success, hence false means a degenerate case, where no\n model was found.\n - Real testSample( size_t index, const Model& model ) const : return some\n value that indicates how well a sample fits to the model. This way the\n thresholding is moved to the searching procedure and the model just tells how\n good a sample is.\n\n There are two methods provided in this class to fit a model:\n - (RANSAC): Just like mrpt::math::RANSAC_Template\n\n - (Genetic): Provides a mixture of a genetic and\n the ransac algorithm.\n Instead of selecting a set of data in each iteration, it takes more\n (ex. 10) and order these model\n using some fitness function: the average error of the inliers scaled\n by the number of outliers (This\n fitness might require some fine tuning). Than the (ex 10) new kernel\n for the next iteration is created as follows:\n - Take the best kernels (as for the original ransac)\n - Select two kernels ( with a higher probability for the better\n models) and let the new kernel be a subset of the two original kernels (\n additionally to leave the local minimums an additional random seed might\n appear - mutation)\n - Generate some new random samples.\n\n For an example of usage, see \"samples/model_search_test/\"\n \n\n mrpt::math::RANSAC_Template, another RANSAC implementation where models\n can be matrices only.\n\n \n Zoltar Gaal\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::math::ModelSearch(); } ) ); + } + // mrpt::math::solve_poly3(double *, double, double, double) file:mrpt/math/poly_roots.h line:29 + M("mrpt::math").def("solve_poly3", (int (*)(double *, double, double, double)) &mrpt::math::solve_poly3, "Solves cubic equation `x^3 + a*x^2 + b*x + c = 0`. Returns the number of\n real roots `N`<=3.\n The roots are returned in the first entries of `x`, i.e. `x[0]` if N=1,\n `x[0]` and `x[1]` if N=2, etc.\n \n\n array of size 3\n \n\n Based on `poly34.h`, by Khashin S.I.\n http://math.ivanovo.ac.ru/dalgebra/Khashin/index.html - khash2 (at) gmail.com\n\nC++: mrpt::math::solve_poly3(double *, double, double, double) --> int", pybind11::arg("x"), pybind11::arg("a"), pybind11::arg("b"), pybind11::arg("c")); + + // mrpt::math::solve_poly4(double *, double, double, double, double) file:mrpt/math/poly_roots.h line:44 + M("mrpt::math").def("solve_poly4", (int (*)(double *, double, double, double, double)) &mrpt::math::solve_poly4, "Solves quartic equation `x^4 + a*x^3 + b*x^2 + c*x + d = 0` by Dekart-Euler\n method.\n Returns the number of real roots `N`<=4:\n - return 4: 4 real roots x[0], x[1], x[2], x[3], possible multiple roots\n - return 2: 2 real roots x[0], x[1] and complex x[2]+-i*x[3],\n - return 0: two pair of complex roots: x[0]+-i*x[1], x[2]+-i*x[3],\n\n The roots are returned in the first entries of `x`, i.e. `x[0]` if N=1,\n `x[0]` and `x[1]` if N=2, etc.\n \n\n array of size 4\n \n\n Based on `poly34.h`, by Khashin S.I.\n http://math.ivanovo.ac.ru/dalgebra/Khashin/index.html - khash2 (at) gmail.com\n\nC++: mrpt::math::solve_poly4(double *, double, double, double, double) --> int", pybind11::arg("x"), pybind11::arg("a"), pybind11::arg("b"), pybind11::arg("c"), pybind11::arg("d")); + + // mrpt::math::solve_poly5(double *, double, double, double, double, double) file:mrpt/math/poly_roots.h line:54 + M("mrpt::math").def("solve_poly5", (int (*)(double *, double, double, double, double, double)) &mrpt::math::solve_poly5, "Solves equation `x^5 + a*x^4 + b*x^3 + c*x^2 + d*x + e = 0`.\n Returns the number of real roots `N`<=5.\n The roots are returned in the first entries of `x`, i.e. `x[0]` if N=1,\n `x[0]` and `x[1]` if N=2, etc.\n \n\n array of size 5\n \n\n Based on `poly34.h`, by Khashin S.I.\n http://math.ivanovo.ac.ru/dalgebra/Khashin/index.html - khash2 (at) gmail.com\n\nC++: mrpt::math::solve_poly5(double *, double, double, double, double, double) --> int", pybind11::arg("x"), pybind11::arg("a"), pybind11::arg("b"), pybind11::arg("c"), pybind11::arg("d"), pybind11::arg("e")); + + // mrpt::math::solve_poly2(double, double, double, double &, double &) file:mrpt/math/poly_roots.h line:64 + M("mrpt::math").def("solve_poly2", (int (*)(double, double, double, double &, double &)) &mrpt::math::solve_poly2, "Solves equation `a*x^2 + b*x + c = 0`.\n Returns the number of real roots: either 0 or 2; or 1 if a=0 (in this case\n the root is in r1).\n r1, r2 are the roots. (r1<=r2)\n \n\n Based on `poly34.h`, by Khashin S.I.\n http://math.ivanovo.ac.ru/dalgebra/Khashin/index.html - khash2 (at) gmail.com\n\nC++: mrpt::math::solve_poly2(double, double, double, double &, double &) --> int", pybind11::arg("a"), pybind11::arg("b"), pybind11::arg("c"), pybind11::arg("r1"), pybind11::arg("r2")); + + // mrpt::math::TRobustKernelType file:mrpt/math/robust_kernels.h line:23 + pybind11::enum_(M("mrpt::math"), "TRobustKernelType", pybind11::arithmetic(), "The different types of kernels for usage within a robustified least-squares\n estimator.\n \n\n Use these types as arguments of the template RobustKernel<>") + .value("rkLeastSquares", mrpt::math::rkLeastSquares) + .value("rkPseudoHuber", mrpt::math::rkPseudoHuber) + .export_values(); + +; + + // mrpt::math::slerp(const struct mrpt::math::TPose3D &, const struct mrpt::math::TPose3D &, const double, struct mrpt::math::TPose3D &) file:mrpt/math/slerp.h line:87 + M("mrpt::math").def("slerp", (void (*)(const struct mrpt::math::TPose3D &, const struct mrpt::math::TPose3D &, const double, struct mrpt::math::TPose3D &)) &mrpt::math::slerp, "SLERP interpolation between two 6D poses - like mrpt::math::slerp for\n quaternions, but interpolates the [X,Y,Z] coordinates as well.\n \n\n The pose for t=0\n \n\n The pose for t=1\n \n\n A \"time\" parameter, in the range [0,1].\n \n\n The output, interpolated pose.\n \n\n std::exception Only in Debug, if t is not in the valid range.\n\nC++: mrpt::math::slerp(const struct mrpt::math::TPose3D &, const struct mrpt::math::TPose3D &, const double, struct mrpt::math::TPose3D &) --> void", pybind11::arg("q0"), pybind11::arg("q1"), pybind11::arg("t"), pybind11::arg("p")); + +} diff --git a/python/generated-sources-pybind/mrpt/math/slerp.cpp b/python/generated-sources-pybind/mrpt/math/slerp.cpp new file mode 100644 index 0000000000..a4d7509c96 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/math/slerp.cpp @@ -0,0 +1,37 @@ +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_math_slerp(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::math::slerp_ypr(const struct mrpt::math::TPose3D &, const struct mrpt::math::TPose3D &, const double, struct mrpt::math::TPose3D &) file:mrpt/math/slerp.h line:93 + M("mrpt::math").def("slerp_ypr", (void (*)(const struct mrpt::math::TPose3D &, const struct mrpt::math::TPose3D &, const double, struct mrpt::math::TPose3D &)) &mrpt::math::slerp_ypr, "as mrpt::math::TPose3D\n form as yaw,pitch,roll angles. XYZ are ignored.\n\nC++: mrpt::math::slerp_ypr(const struct mrpt::math::TPose3D &, const struct mrpt::math::TPose3D &, const double, struct mrpt::math::TPose3D &) --> void", pybind11::arg("q0"), pybind11::arg("q1"), pybind11::arg("t"), pybind11::arg("p")); + + // mrpt::math::medianFilter(const int &, int &, int, int) file:mrpt/math/utils.h line:72 + M("mrpt::math").def("medianFilter", [](const int & a0, int & a1, int const & a2) -> void { return mrpt::math::medianFilter(a0, a1, a2); }, "", pybind11::arg("inV"), pybind11::arg("outV"), pybind11::arg("winSize")); + M("mrpt::math").def("medianFilter", (void (*)(const int &, int &, int, int)) &mrpt::math::medianFilter, "C++: mrpt::math::medianFilter(const int &, int &, int, int) --> void", pybind11::arg("inV"), pybind11::arg("outV"), pybind11::arg("winSize"), pybind11::arg("numberOfSigmas")); + + // mrpt::math::factorial64(unsigned int) file:mrpt/math/utils.h line:168 + M("mrpt::math").def("factorial64", (uint64_t (*)(unsigned int)) &mrpt::math::factorial64, "Computes the factorial of an integer number and returns it as a 64-bit\n integer number.\n\nC++: mrpt::math::factorial64(unsigned int) --> uint64_t", pybind11::arg("n")); + + // mrpt::math::factorial(unsigned int) file:mrpt/math/utils.h line:173 + M("mrpt::math").def("factorial", (double (*)(unsigned int)) &mrpt::math::factorial, "Computes the factorial of an integer number and returns it as a double value\n (internally it uses logarithms for avoiding overflow).\n\nC++: mrpt::math::factorial(unsigned int) --> double", pybind11::arg("n")); + +} diff --git a/python/generated-sources-pybind/mrpt/obs/CObservationOdometry.cpp b/python/generated-sources-pybind/mrpt/obs/CObservationOdometry.cpp new file mode 100644 index 0000000000..b7b9e9abc4 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/obs/CObservationOdometry.cpp @@ -0,0 +1,891 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::obs::CObservationOdometry file:mrpt/obs/CObservationOdometry.h line:32 +struct PyCallBack_mrpt_obs_CObservationOdometry : public mrpt::obs::CObservationOdometry { + using mrpt::obs::CObservationOdometry::CObservationOdometry; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::serializeFrom(a0, a1); + } + void getSensorPose(class mrpt::poses::CPose3D & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::getSensorPose(a0); + } + void setSensorPose(const class mrpt::poses::CPose3D & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::setSensorPose(a0); + } + bool exportTxtSupported() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::exportTxtSupported(); + } + std::string exportTxtHeader() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::exportTxtHeader(); + } + std::string exportTxtDataRow() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationOdometry::exportTxtDataRow(); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + } + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + } + return CObservation::getOriginalReceivedTimeStamp(); + } + std::string asString() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::asString(); + } + void load() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "load"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::load(); + } + void unload() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::unload(); + } +}; + +// mrpt::obs::CObservationReflectivity file:mrpt/obs/CObservationReflectivity.h line:24 +struct PyCallBack_mrpt_obs_CObservationReflectivity : public mrpt::obs::CObservationReflectivity { + using mrpt::obs::CObservationReflectivity::CObservationReflectivity; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::serializeFrom(a0, a1); + } + void getSensorPose(class mrpt::poses::CPose3D & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::getSensorPose(a0); + } + void setSensorPose(const class mrpt::poses::CPose3D & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::setSensorPose(a0); + } + bool exportTxtSupported() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::exportTxtSupported(); + } + std::string exportTxtHeader() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::exportTxtHeader(); + } + std::string exportTxtDataRow() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationReflectivity::exportTxtDataRow(); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + } + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + } + return CObservation::getOriginalReceivedTimeStamp(); + } + std::string asString() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::asString(); + } + void load() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "load"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::load(); + } + void unload() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::unload(); + } +}; + +// mrpt::obs::CObservationRobotPose file:mrpt/obs/CObservationRobotPose.h line:21 +struct PyCallBack_mrpt_obs_CObservationRobotPose : public mrpt::obs::CObservationRobotPose { + using mrpt::obs::CObservationRobotPose::CObservationRobotPose; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::serializeFrom(a0, a1); + } + void getSensorPose(class mrpt::poses::CPose3D & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::getSensorPose(a0); + } + void setSensorPose(const class mrpt::poses::CPose3D & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::setSensorPose(a0); + } + bool exportTxtSupported() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::exportTxtSupported(); + } + std::string exportTxtHeader() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::exportTxtHeader(); + } + std::string exportTxtDataRow() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationRobotPose::exportTxtDataRow(); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + } + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + } + return CObservation::getOriginalReceivedTimeStamp(); + } + std::string asString() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::asString(); + } + void load() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "load"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::load(); + } + void unload() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::unload(); + } +}; + +// mrpt::obs::CObservationStereoImagesFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:36 +struct PyCallBack_mrpt_obs_CObservationStereoImagesFeatures : public mrpt::obs::CObservationStereoImagesFeatures { + using mrpt::obs::CObservationStereoImagesFeatures::CObservationStereoImagesFeatures; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::serializeFrom(a0, a1); + } + void getSensorPose(class mrpt::poses::CPose3D & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::getSensorPose(a0); + } + void setSensorPose(const class mrpt::poses::CPose3D & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setSensorPose"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservationStereoImagesFeatures::setSensorPose(a0); + } + using _binder_ret_0 = mrpt::Clock::time_point; + _binder_ret_0 getOriginalReceivedTimeStamp() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "getOriginalReceivedTimeStamp"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference<_binder_ret_0>::value) { + static pybind11::detail::override_caster_t<_binder_ret_0> caster; + return pybind11::detail::cast_ref<_binder_ret_0>(std::move(o), caster); + } + else return pybind11::detail::cast_safe<_binder_ret_0>(std::move(o)); + } + return CObservation::getOriginalReceivedTimeStamp(); + } + std::string asString() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "asString"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::asString(); + } + bool exportTxtSupported() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtSupported"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::exportTxtSupported(); + } + std::string exportTxtHeader() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtHeader"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::exportTxtHeader(); + } + std::string exportTxtDataRow() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "exportTxtDataRow"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::exportTxtDataRow(); + } + void load() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "load"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::load(); + } + void unload() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "unload"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CObservation::unload(); + } +}; + +void bind_mrpt_obs_CObservationOdometry(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::obs::CObservationOdometry file:mrpt/obs/CObservationOdometry.h line:32 + pybind11::class_, PyCallBack_mrpt_obs_CObservationOdometry, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationOdometry", "An observation of the current (cumulative) odometry for a wheeled robot.\n This provides the relative pose of the robot with respect to the `odom`\n frame of reference, in \"ROS parlance\".\n\n This kind of observation more naturally fits the \"observation-only\" rawlog\n format, since odometry increments are normally used in \"sensory-frame based\"\n datasets. However, the user is free to use them whenever it is useful. Refer\n to the [rawlog format description](rawlog_format.html).\n\n \n CObservation, CActionRobotMovement2D\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationOdometry(); }, [](){ return new PyCallBack_mrpt_obs_CObservationOdometry(); } ) ); + cl.def_readwrite("odometry", &mrpt::obs::CObservationOdometry::odometry); + cl.def_readwrite("hasEncodersInfo", &mrpt::obs::CObservationOdometry::hasEncodersInfo); + cl.def_readwrite("encoderLeftTicks", &mrpt::obs::CObservationOdometry::encoderLeftTicks); + cl.def_readwrite("encoderRightTicks", &mrpt::obs::CObservationOdometry::encoderRightTicks); + cl.def_readwrite("hasVelocities", &mrpt::obs::CObservationOdometry::hasVelocities); + cl.def_readwrite("velocityLocal", &mrpt::obs::CObservationOdometry::velocityLocal); + cl.def_static("getClassName", (auto (*)()) &mrpt::obs::CObservationOdometry::getClassName, "C++: mrpt::obs::CObservationOdometry::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationOdometry::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationOdometry::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationOdometry::*)() const) &mrpt::obs::CObservationOdometry::GetRuntimeClass, "C++: mrpt::obs::CObservationOdometry::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationOdometry::*)() const) &mrpt::obs::CObservationOdometry::clone, "C++: mrpt::obs::CObservationOdometry::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationOdometry::CreateObject, "C++: mrpt::obs::CObservationOdometry::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservationOdometry::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationOdometry::getSensorPose, "C++: mrpt::obs::CObservationOdometry::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationOdometry::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationOdometry::setSensorPose, "C++: mrpt::obs::CObservationOdometry::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("")); + cl.def("exportTxtSupported", (bool (mrpt::obs::CObservationOdometry::*)() const) &mrpt::obs::CObservationOdometry::exportTxtSupported, "C++: mrpt::obs::CObservationOdometry::exportTxtSupported() const --> bool"); + cl.def("exportTxtHeader", (std::string (mrpt::obs::CObservationOdometry::*)() const) &mrpt::obs::CObservationOdometry::exportTxtHeader, "C++: mrpt::obs::CObservationOdometry::exportTxtHeader() const --> std::string"); + cl.def("exportTxtDataRow", (std::string (mrpt::obs::CObservationOdometry::*)() const) &mrpt::obs::CObservationOdometry::exportTxtDataRow, "C++: mrpt::obs::CObservationOdometry::exportTxtDataRow() const --> std::string"); + cl.def("assign", (class mrpt::obs::CObservationOdometry & (mrpt::obs::CObservationOdometry::*)(const class mrpt::obs::CObservationOdometry &)) &mrpt::obs::CObservationOdometry::operator=, "C++: mrpt::obs::CObservationOdometry::operator=(const class mrpt::obs::CObservationOdometry &) --> class mrpt::obs::CObservationOdometry &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::CObservationReflectivity file:mrpt/obs/CObservationReflectivity.h line:24 + pybind11::class_, PyCallBack_mrpt_obs_CObservationReflectivity, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationReflectivity", "Declares a class derived from \"CObservation\" that encapsules a single\n short-range reflectivity measurement.\n This can be used for example to store readings from IR sensors (Lego\n Mindstorm NXT, etc...).\n\n \n mrpt::obs::CReflectivityGridMap2D, CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationReflectivity(); }, [](){ return new PyCallBack_mrpt_obs_CObservationReflectivity(); } ) ); + cl.def_readwrite("reflectivityLevel", &mrpt::obs::CObservationReflectivity::reflectivityLevel); + cl.def_readwrite("channel", &mrpt::obs::CObservationReflectivity::channel); + cl.def_readwrite("sensorPose", &mrpt::obs::CObservationReflectivity::sensorPose); + cl.def_readwrite("sensorStdNoise", &mrpt::obs::CObservationReflectivity::sensorStdNoise); + cl.def_static("getClassName", (auto (*)()) &mrpt::obs::CObservationReflectivity::getClassName, "C++: mrpt::obs::CObservationReflectivity::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationReflectivity::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationReflectivity::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationReflectivity::*)() const) &mrpt::obs::CObservationReflectivity::GetRuntimeClass, "C++: mrpt::obs::CObservationReflectivity::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationReflectivity::*)() const) &mrpt::obs::CObservationReflectivity::clone, "C++: mrpt::obs::CObservationReflectivity::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationReflectivity::CreateObject, "C++: mrpt::obs::CObservationReflectivity::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservationReflectivity::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationReflectivity::getSensorPose, "C++: mrpt::obs::CObservationReflectivity::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationReflectivity::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationReflectivity::setSensorPose, "C++: mrpt::obs::CObservationReflectivity::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("exportTxtSupported", (bool (mrpt::obs::CObservationReflectivity::*)() const) &mrpt::obs::CObservationReflectivity::exportTxtSupported, "C++: mrpt::obs::CObservationReflectivity::exportTxtSupported() const --> bool"); + cl.def("exportTxtHeader", (std::string (mrpt::obs::CObservationReflectivity::*)() const) &mrpt::obs::CObservationReflectivity::exportTxtHeader, "C++: mrpt::obs::CObservationReflectivity::exportTxtHeader() const --> std::string"); + cl.def("exportTxtDataRow", (std::string (mrpt::obs::CObservationReflectivity::*)() const) &mrpt::obs::CObservationReflectivity::exportTxtDataRow, "C++: mrpt::obs::CObservationReflectivity::exportTxtDataRow() const --> std::string"); + cl.def("assign", (class mrpt::obs::CObservationReflectivity & (mrpt::obs::CObservationReflectivity::*)(const class mrpt::obs::CObservationReflectivity &)) &mrpt::obs::CObservationReflectivity::operator=, "C++: mrpt::obs::CObservationReflectivity::operator=(const class mrpt::obs::CObservationReflectivity &) --> class mrpt::obs::CObservationReflectivity &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::CObservationRobotPose file:mrpt/obs/CObservationRobotPose.h line:21 + pybind11::class_, PyCallBack_mrpt_obs_CObservationRobotPose, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationRobotPose", "An observation providing an alternative robot pose from an external source.\n \n\n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationRobotPose(); }, [](){ return new PyCallBack_mrpt_obs_CObservationRobotPose(); } ) ); + cl.def_readwrite("pose", &mrpt::obs::CObservationRobotPose::pose); + cl.def_readwrite("sensorPose", &mrpt::obs::CObservationRobotPose::sensorPose); + cl.def_static("getClassName", (auto (*)()) &mrpt::obs::CObservationRobotPose::getClassName, "C++: mrpt::obs::CObservationRobotPose::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationRobotPose::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationRobotPose::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::GetRuntimeClass, "C++: mrpt::obs::CObservationRobotPose::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::clone, "C++: mrpt::obs::CObservationRobotPose::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationRobotPose::CreateObject, "C++: mrpt::obs::CObservationRobotPose::CreateObject() --> class std::shared_ptr"); + cl.def("getSensorPose", (void (mrpt::obs::CObservationRobotPose::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationRobotPose::getSensorPose, "C++: mrpt::obs::CObservationRobotPose::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationRobotPose::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationRobotPose::setSensorPose, "C++: mrpt::obs::CObservationRobotPose::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("exportTxtSupported", (bool (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtSupported, "C++: mrpt::obs::CObservationRobotPose::exportTxtSupported() const --> bool"); + cl.def("exportTxtHeader", (std::string (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtHeader, "C++: mrpt::obs::CObservationRobotPose::exportTxtHeader() const --> std::string"); + cl.def("exportTxtDataRow", (std::string (mrpt::obs::CObservationRobotPose::*)() const) &mrpt::obs::CObservationRobotPose::exportTxtDataRow, "C++: mrpt::obs::CObservationRobotPose::exportTxtDataRow() const --> std::string"); + cl.def("assign", (class mrpt::obs::CObservationRobotPose & (mrpt::obs::CObservationRobotPose::*)(const class mrpt::obs::CObservationRobotPose &)) &mrpt::obs::CObservationRobotPose::operator=, "C++: mrpt::obs::CObservationRobotPose::operator=(const class mrpt::obs::CObservationRobotPose &) --> class mrpt::obs::CObservationRobotPose &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::TStereoImageFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:21 + pybind11::class_> cl(M("mrpt::obs"), "TStereoImageFeatures", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::TStereoImageFeatures(); } ) ); + cl.def_readwrite("pixels", &mrpt::obs::TStereoImageFeatures::pixels); + cl.def_readwrite("ID", &mrpt::obs::TStereoImageFeatures::ID); + } + { // mrpt::obs::CObservationStereoImagesFeatures file:mrpt/obs/CObservationStereoImagesFeatures.h line:36 + pybind11::class_, PyCallBack_mrpt_obs_CObservationStereoImagesFeatures, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationStereoImagesFeatures", "Declares a class derived from \"CObservation\" that encapsules a pair of\n cameras and a set of matched image features extracted from them.\n\n NOTE: The image features stored in this class are NOT supposed to be\n UNDISTORTED, but the TCamera members must provide their distortion params.\n A zero-vector of distortion params means a set of UNDISTORTED pixels.\n \n\n CObservation\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationStereoImagesFeatures(); }, [](){ return new PyCallBack_mrpt_obs_CObservationStereoImagesFeatures(); } ) ); + cl.def( pybind11::init(), pybind11::arg("cLeft"), pybind11::arg("cRight"), pybind11::arg("rCPose"), pybind11::arg("cPORobot") ); + + cl.def_readwrite("cameraLeft", &mrpt::obs::CObservationStereoImagesFeatures::cameraLeft); + cl.def_readwrite("cameraRight", &mrpt::obs::CObservationStereoImagesFeatures::cameraRight); + cl.def_readwrite("rightCameraPose", &mrpt::obs::CObservationStereoImagesFeatures::rightCameraPose); + cl.def_readwrite("cameraPoseOnRobot", &mrpt::obs::CObservationStereoImagesFeatures::cameraPoseOnRobot); + cl.def_readwrite("theFeatures", &mrpt::obs::CObservationStereoImagesFeatures::theFeatures); + cl.def_static("getClassName", (auto (*)()) &mrpt::obs::CObservationStereoImagesFeatures::getClassName, "C++: mrpt::obs::CObservationStereoImagesFeatures::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClassIdStatic, "C++: mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CObservationStereoImagesFeatures::*)() const) &mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClass, "C++: mrpt::obs::CObservationStereoImagesFeatures::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CObservationStereoImagesFeatures::*)() const) &mrpt::obs::CObservationStereoImagesFeatures::clone, "C++: mrpt::obs::CObservationStereoImagesFeatures::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationStereoImagesFeatures::CreateObject, "C++: mrpt::obs::CObservationStereoImagesFeatures::CreateObject() --> class std::shared_ptr"); + cl.def("saveFeaturesToTextFile", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const std::string &)) &mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile, "A method for storing the set of observed features in a text file in the\n format: \n ID ul vl ur vr \n being (ul,vl) and (ur,vr) the \"x\" and \"y\" coordinates for the left and\n right feature, respectively.\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::saveFeaturesToTextFile(const std::string &) --> void", pybind11::arg("filename")); + cl.def("getSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationStereoImagesFeatures::getSensorPose, "C++: mrpt::obs::CObservationStereoImagesFeatures::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("getSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(class mrpt::poses::CPose3DQuat &) const) &mrpt::obs::CObservationStereoImagesFeatures::getSensorPose, "C++: mrpt::obs::CObservationStereoImagesFeatures::getSensorPose(class mrpt::poses::CPose3DQuat &) const --> void", pybind11::arg("out_sensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationStereoImagesFeatures::setSensorPose, "A general method to change the sensor pose on the robot in a\n mrpt::poses::CPose3D form.\n Note that most sensors will use the full (6D) CPose3DQuat, but see the\n derived classes for more details or special cases.\n \n\n getSensorPose\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); + cl.def("setSensorPose", (void (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::poses::CPose3DQuat &)) &mrpt::obs::CObservationStereoImagesFeatures::setSensorPose, "A general method to change the sensor pose on the robot in a CPose3DQuat\n form.\n Note that most sensors will use the full (6D) CPose3DQuat, but see the\n derived classes for more details or special cases.\n \n\n getSensorPose\n\nC++: mrpt::obs::CObservationStereoImagesFeatures::setSensorPose(const class mrpt::poses::CPose3DQuat &) --> void", pybind11::arg("newSensorPose")); + cl.def("assign", (class mrpt::obs::CObservationStereoImagesFeatures & (mrpt::obs::CObservationStereoImagesFeatures::*)(const class mrpt::obs::CObservationStereoImagesFeatures &)) &mrpt::obs::CObservationStereoImagesFeatures::operator=, "C++: mrpt::obs::CObservationStereoImagesFeatures::operator=(const class mrpt::obs::CObservationStereoImagesFeatures &) --> class mrpt::obs::CObservationStereoImagesFeatures &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/obs/CRawlog.cpp b/python/generated-sources-pybind/mrpt/obs/CRawlog.cpp new file mode 100644 index 0000000000..dc9601c34c --- /dev/null +++ b/python/generated-sources-pybind/mrpt/obs/CRawlog.cpp @@ -0,0 +1,179 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::obs::CRawlog file:mrpt/obs/CRawlog.h line:60 +struct PyCallBack_mrpt_obs_CRawlog : public mrpt::obs::CRawlog { + using mrpt::obs::CRawlog::CRawlog; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRawlog::serializeFrom(a0, a1); + } +}; + +void bind_mrpt_obs_CRawlog(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::obs::CRawlog file:mrpt/obs/CRawlog.h line:60 + pybind11::class_, PyCallBack_mrpt_obs_CRawlog, mrpt::serialization::CSerializable> cl(M("mrpt::obs"), "CRawlog", "The main class for loading and processing robotics datasets, or \"rawlogs\".\n\n Please, refer to the [rawlog format specification](rawlog_format.html).\n\n In short, this class stores a sequence of objects, in one of two possible\nformats:\n - Format #1: A sequence of actions and observations. There is a sequence\nof objects, where each one can be of one type:\n - An action: Implemented as a CActionCollection object, the\nactuation\nof the robot (i.e. odometry increment).\n - Observations: Implemented as a CSensoryFrame, refering to a set of\nrobot observations from the same pose.\n - Format #2: A sequence of actions and observations. There is a sequence\nof objects, where each one can be of one type:\n\n See also [RawLogViewer](app_RawLogViewer.html) for a GUI application for\n quick inspection and analysis of rawlogs.\n\n There is a field for dataset plain-text comments (human-friendly description,\n blocks of parameters, etc.) accessible through CRawlog::getCommentText() and\n CRawlog::setCommentText().\n\n This container provides a STL container-like interface (see CRawlog::begin,\n CRawlog::iterator, ...).\n\n \n There is a static helper method CRawlog::detectImagesDirectory() to\n identify the directory where external images are stored.\n\n \n CSensoryFrame,\n [Dataset file format](robotics_file_formats.html#datasets).\n\n \n\n "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog(); }, [](){ return new PyCallBack_mrpt_obs_CRawlog(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CRawlog const &o){ return new PyCallBack_mrpt_obs_CRawlog(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::CRawlog const &o){ return new mrpt::obs::CRawlog(o); } ) ); + + pybind11::enum_(cl, "TEntryType", pybind11::arithmetic(), "The type of each entry in a rawlog.\n \n\n CRawlog::getType") + .value("etSensoryFrame", mrpt::obs::CRawlog::etSensoryFrame) + .value("etActionCollection", mrpt::obs::CRawlog::etActionCollection) + .value("etObservation", mrpt::obs::CRawlog::etObservation) + .value("etOther", mrpt::obs::CRawlog::etOther) + .export_values(); + + cl.def_static("getClassName", (auto (*)()) &mrpt::obs::CRawlog::getClassName, "C++: mrpt::obs::CRawlog::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::obs::CRawlog::GetRuntimeClassIdStatic, "C++: mrpt::obs::CRawlog::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::GetRuntimeClass, "C++: mrpt::obs::CRawlog::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::clone, "C++: mrpt::obs::CRawlog::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CRawlog::CreateObject, "C++: mrpt::obs::CRawlog::CreateObject() --> class std::shared_ptr"); + cl.def("getCommentText", (void (mrpt::obs::CRawlog::*)(std::string &) const) &mrpt::obs::CRawlog::getCommentText, "Returns the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::getCommentText(std::string &) const --> void", pybind11::arg("t")); + cl.def("getCommentText", (std::string (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::getCommentText, "Returns the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::getCommentText() const --> std::string"); + cl.def("setCommentText", (void (mrpt::obs::CRawlog::*)(const std::string &)) &mrpt::obs::CRawlog::setCommentText, "Changes the block of comment text for the rawlog \n\nC++: mrpt::obs::CRawlog::setCommentText(const std::string &) --> void", pybind11::arg("t")); + cl.def("getCommentTextAsConfigFile", (void (mrpt::obs::CRawlog::*)(class mrpt::config::CConfigFileMemory &) const) &mrpt::obs::CRawlog::getCommentTextAsConfigFile, "Saves the block of comment text for the rawlog into the passed config\n file object. \n\nC++: mrpt::obs::CRawlog::getCommentTextAsConfigFile(class mrpt::config::CConfigFileMemory &) const --> void", pybind11::arg("memCfg")); + cl.def("clear", (void (mrpt::obs::CRawlog::*)()) &mrpt::obs::CRawlog::clear, "Clear the sequence of actions/observations. Smart pointers to objects\n previously in the rawlog will remain being valid. \n\nC++: mrpt::obs::CRawlog::clear() --> void"); + cl.def("empty", (bool (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::empty, "Returns true if the rawlog is empty \n\nC++: mrpt::obs::CRawlog::empty() const --> bool"); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CAction &)) &mrpt::obs::CRawlog::insert, "Add an action to the sequence: a collection of just one element is\n created.\n The object is duplicated, so the original one can be freed if desired.\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CAction &) --> void", pybind11::arg("action")); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CActionCollection &)) &mrpt::obs::CRawlog::insert, "Add a set of actions to the sequence; the object is duplicated, so the\n original one can be freed if desired.\n \n\n insert, insert\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CActionCollection &) --> void", pybind11::arg("action")); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CSensoryFrame &)) &mrpt::obs::CRawlog::insert, "Add a set of observations to the sequence; the object is duplicated, so\n the original one can be free if desired.\n\nC++: mrpt::obs::CRawlog::insert(class mrpt::obs::CSensoryFrame &) --> void", pybind11::arg("observations")); + cl.def("insert", (void (mrpt::obs::CRawlog::*)(const class std::shared_ptr &)) &mrpt::obs::CRawlog::insert, "Generic add for a smart pointer to a CSerializable object:\n\nC++: mrpt::obs::CRawlog::insert(const class std::shared_ptr &) --> void", pybind11::arg("obj")); + cl.def("loadFromRawLogFile", [](mrpt::obs::CRawlog &o, const std::string & a0) -> bool { return o.loadFromRawLogFile(a0); }, "", pybind11::arg("fileName")); + cl.def("loadFromRawLogFile", (bool (mrpt::obs::CRawlog::*)(const std::string &, bool)) &mrpt::obs::CRawlog::loadFromRawLogFile, "Load the contents from a file containing one of these possibilities:\n - A \"CRawlog\" object.\n - Directly the sequence of objects (pairs\n `CSensoryFrame`/`CActionCollection` or `CObservation*` objects). In this\n case the method stops reading on EOF of an unrecogniced class name.\n - Only if `non_obs_objects_are_legal` is true, any `CSerializable`\n object is allowed in the log file. Otherwise, the read stops on classes\n different from the ones listed in the item above.\n \n\n It returns false upon error reading or accessing the file.\n\nC++: mrpt::obs::CRawlog::loadFromRawLogFile(const std::string &, bool) --> bool", pybind11::arg("fileName"), pybind11::arg("non_obs_objects_are_legal")); + cl.def("saveToRawLogFile", (bool (mrpt::obs::CRawlog::*)(const std::string &) const) &mrpt::obs::CRawlog::saveToRawLogFile, "Saves the contents to a rawlog-file, compatible with RawlogViewer (As\n the sequence of internal objects).\n The file is saved with gz-commpressed if MRPT has gz-streams.\n \n\n It returns false if any error is found while writing/creating\n the target file.\n\nC++: mrpt::obs::CRawlog::saveToRawLogFile(const std::string &) const --> bool", pybind11::arg("fileName")); + cl.def("size", (size_t (mrpt::obs::CRawlog::*)() const) &mrpt::obs::CRawlog::size, "Returns the number of actions / observations object in the sequence. \n\nC++: mrpt::obs::CRawlog::size() const --> size_t"); + cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getType, "Returns the type of a given element.\n \n\n isAction, isObservation\n\nC++: mrpt::obs::CRawlog::getType(size_t) const --> enum mrpt::obs::CRawlog::TEntryType", pybind11::arg("index")); + cl.def("remove", (void (mrpt::obs::CRawlog::*)(size_t)) &mrpt::obs::CRawlog::remove, "Delete the action or observation stored in the given index.\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::remove(size_t) --> void", pybind11::arg("index")); + cl.def("remove", (void (mrpt::obs::CRawlog::*)(size_t, size_t)) &mrpt::obs::CRawlog::remove, "Delete the elements stored in the given range of indices (including both\n the first and last one).\n \n\n std::exception If any index is out of bounds\n\nC++: mrpt::obs::CRawlog::remove(size_t, size_t) --> void", pybind11::arg("first_index"), pybind11::arg("last_index")); + cl.def("getAsAction", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsAction, "Returns the i'th element in the sequence, as being actions, where\n index=0 is the first object.\n If it is not a CActionCollection, it throws an exception. Do neighter\n modify nor delete the returned pointer.\n \n\n size, isAction, getAsObservations, getAsObservation\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsAction(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("getAsObservations", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsObservations, "Returns the i'th element in the sequence, as being an action, where\n index=0 is the first object.\n If it is not an CSensoryFrame, it throws an exception.\n \n\n size, isAction, getAsAction, getAsObservation\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsObservations(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("getAsGeneric", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsGeneric, "Returns the i'th element in the sequence, being its class whatever.\n \n\n size, isAction, getAsAction, getAsObservations\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsGeneric(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("getAsObservation", (class std::shared_ptr (mrpt::obs::CRawlog::*)(size_t) const) &mrpt::obs::CRawlog::getAsObservation, "Returns the i'th element in the sequence, as being an observation, where\n index=0 is the first object.\n If it is not an CObservation, it throws an exception. Do neighter\n modify nor delete the returned pointer.\n This is the proper method to obtain the objects stored in a \"only\n observations\"-rawlog file (named \"format #2\" above.\n \n\n size, isAction, getAsAction\n \n\n std::exception If index is out of bounds\n\nC++: mrpt::obs::CRawlog::getAsObservation(size_t) const --> class std::shared_ptr", pybind11::arg("index")); + cl.def("findObservationsByClassInRange", [](mrpt::obs::CRawlog const &o, mrpt::Clock::time_point const & a0, mrpt::Clock::time_point const & a1, const struct mrpt::rtti::TRuntimeClassId * a2, int & a3) -> void { return o.findObservationsByClassInRange(a0, a1, a2, a3); }, "", pybind11::arg("time_start"), pybind11::arg("time_end"), pybind11::arg("class_type"), pybind11::arg("out_found")); + cl.def("findObservationsByClassInRange", (void (mrpt::obs::CRawlog::*)(mrpt::Clock::time_point, mrpt::Clock::time_point, const struct mrpt::rtti::TRuntimeClassId *, int &, size_t) const) &mrpt::obs::CRawlog::findObservationsByClassInRange, "Returns the sub-set of observations of a given class whose time-stamp t\n fulfills time_start <= t < time_end.\n This method requires the timestamps of the sensors to be in strict\n ascending order (which should be the normal situation).\n Otherwise, the output is undeterminate.\n \n\n findClosestObservationsByClass\n\nC++: mrpt::obs::CRawlog::findObservationsByClassInRange(mrpt::Clock::time_point, mrpt::Clock::time_point, const struct mrpt::rtti::TRuntimeClassId *, int &, size_t) const --> void", pybind11::arg("time_start"), pybind11::arg("time_end"), pybind11::arg("class_type"), pybind11::arg("out_found"), pybind11::arg("guess_start_position")); + cl.def("swap", (void (mrpt::obs::CRawlog::*)(class mrpt::obs::CRawlog &)) &mrpt::obs::CRawlog::swap, "Efficiently swap the contents of two existing objects.\n\nC++: mrpt::obs::CRawlog::swap(class mrpt::obs::CRawlog &) --> void", pybind11::arg("obj")); + cl.def_static("readActionObservationPair", (bool (*)(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &)) &mrpt::obs::CRawlog::readActionObservationPair, "Reads a consecutive pair action / observation from the rawlog opened at\n some input stream.\n Previous contents of action and observations are discarded, and\n upon exit they contain smart pointers to the new objects read from the\n rawlog file.\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n getActionObservationPair, getActionObservationPairOrObservation\n\nC++: mrpt::obs::CRawlog::readActionObservationPair(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &) --> bool", pybind11::arg("inStream"), pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("rawlogEntry")); + cl.def_static("getActionObservationPairOrObservation", (bool (*)(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &)) &mrpt::obs::CRawlog::getActionObservationPairOrObservation, "Reads a consecutive pair action/sensory_frame OR an observation,\n depending of the rawlog format, from the rawlog opened at some input\n stream.\n Previous contents of action and observations are discarded, and\n upon return they contain smart pointers to the new objects read from\n the rawlog file.\n\n Depending on the rawlog file format, at return either:\n - action/observations contain objects, or\n - observation contains an object.\n\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n getActionObservationPair\n\nC++: mrpt::obs::CRawlog::getActionObservationPairOrObservation(class mrpt::serialization::CArchive &, class std::shared_ptr &, class std::shared_ptr &, class std::shared_ptr &, unsigned long &) --> bool", pybind11::arg("inStream"), pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("observation"), pybind11::arg("rawlogEntry")); + cl.def("getActionObservationPair", (bool (mrpt::obs::CRawlog::*)(class std::shared_ptr &, class std::shared_ptr &, unsigned long &) const) &mrpt::obs::CRawlog::getActionObservationPair, "Gets the next consecutive pair action / observation from the rawlog\n loaded into this object.\n Previous contents of action and observations are discarded, and\n upon return they contain smart pointers to the next objects read from\n the rawlog dataset.\n The input/output variable \"rawlogEntry\" is just a counter of the last\n rawlog entry read, for logging or monitoring purposes.\n \n\n false if there was some error, true otherwise.\n \n\n readActionObservationPair\n\nC++: mrpt::obs::CRawlog::getActionObservationPair(class std::shared_ptr &, class std::shared_ptr &, unsigned long &) const --> bool", pybind11::arg("action"), pybind11::arg("observations"), pybind11::arg("rawlogEntry")); + cl.def_static("detectImagesDirectory", (std::string (*)(const std::string &)) &mrpt::obs::CRawlog::detectImagesDirectory, "Tries to auto-detect the external-images directory of the given rawlog\nfile.\n This searches for the existence of the directories:\n - \"/_Images\"\n - \"/_images\"\n - \"/_IMAGES\"\n - \"/Images\" (This one is returned if none of the\nchoices actually exists).\n\n The results from this function should be written into\nmrpt::img::CImage::getImagesPathBase() to enable automatic\n loading of extenrnally-stored images in rawlogs.\n\nC++: mrpt::obs::CRawlog::detectImagesDirectory(const std::string &) --> std::string", pybind11::arg("rawlogFilename")); + cl.def("assign", (class mrpt::obs::CRawlog & (mrpt::obs::CRawlog::*)(const class mrpt::obs::CRawlog &)) &mrpt::obs::CRawlog::operator=, "C++: mrpt::obs::CRawlog::operator=(const class mrpt::obs::CRawlog &) --> class mrpt::obs::CRawlog &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::CRawlog::iterator file:mrpt/obs/CRawlog.h line:230 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "iterator", "A normal iterator, plus the extra method \"getType\" to determine the\n type of each entry in the sequence. "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog::iterator(); } ) ); + cl.def( pybind11::init(), pybind11::arg("it") ); + + cl.def("dereference", (class std::shared_ptr (mrpt::obs::CRawlog::iterator::*)()) &mrpt::obs::CRawlog::iterator::operator*, "C++: mrpt::obs::CRawlog::iterator::operator*() --> class std::shared_ptr"); + cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::iterator::*)() const) &mrpt::obs::CRawlog::iterator::getType, "C++: mrpt::obs::CRawlog::iterator::getType() const --> enum mrpt::obs::CRawlog::TEntryType"); + } + + { // mrpt::obs::CRawlog::const_iterator file:mrpt/obs/CRawlog.h line:286 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "const_iterator", "A normal iterator, plus the extra method \"getType\" to determine the type\n of each entry in the sequence. "); + cl.def( pybind11::init( [](){ return new mrpt::obs::CRawlog::const_iterator(); } ) ); + cl.def( pybind11::init(), pybind11::arg("it") ); + + cl.def("dereference", (const class std::shared_ptr (mrpt::obs::CRawlog::const_iterator::*)() const) &mrpt::obs::CRawlog::const_iterator::operator*, "C++: mrpt::obs::CRawlog::const_iterator::operator*() const --> const class std::shared_ptr"); + cl.def("getType", (enum mrpt::obs::CRawlog::TEntryType (mrpt::obs::CRawlog::const_iterator::*)() const) &mrpt::obs::CRawlog::const_iterator::getType, "C++: mrpt::obs::CRawlog::const_iterator::getType() const --> enum mrpt::obs::CRawlog::TEntryType"); + } + + } +} diff --git a/python/generated-sources-pybind/mrpt/opengl/CEllipsoidRangeBearing2D.cpp b/python/generated-sources-pybind/mrpt/opengl/CEllipsoidRangeBearing2D.cpp new file mode 100644 index 0000000000..181144eb48 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/opengl/CEllipsoidRangeBearing2D.cpp @@ -0,0 +1,667 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::opengl::CEllipsoidRangeBearing2D file:mrpt/opengl/CEllipsoidRangeBearing2D.h line:34 +struct PyCallBack_mrpt_opengl_CEllipsoidRangeBearing2D : public mrpt::opengl::CEllipsoidRangeBearing2D { + using mrpt::opengl::CEllipsoidRangeBearing2D::CEllipsoidRangeBearing2D; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidRangeBearing2D::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidRangeBearing2D::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidRangeBearing2D::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidRangeBearing2D::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidRangeBearing2D::serializeFrom(a0, a1); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + pybind11::pybind11_fail("Tried to call pure virtual function \"CRenderizable::renderUpdateBuffers\""); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::traceRay(a0, a1); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + pybind11::pybind11_fail("Tried to call pure virtual function \"CRenderizable::freeOpenGLResources\""); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +// mrpt::opengl::CPolyhedron file:mrpt/opengl/CPolyhedron.h line:38 +struct PyCallBack_mrpt_opengl_CPolyhedron : public mrpt::opengl::CPolyhedron { + using mrpt::opengl::CPolyhedron::CPolyhedron; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::serializeFrom(a0, a1); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::renderUpdateBuffers(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::freeOpenGLResources(); + } + void onUpdateBuffers_Wireframe() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Wireframe"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::onUpdateBuffers_Wireframe(); + } + void onUpdateBuffers_Triangles() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Triangles"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::onUpdateBuffers_Triangles(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CPolyhedron::traceRay(a0, a1); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +void bind_mrpt_opengl_CEllipsoidRangeBearing2D(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::opengl::CEllipsoidRangeBearing2D file:mrpt/opengl/CEllipsoidRangeBearing2D.h line:34 + pybind11::class_, PyCallBack_mrpt_opengl_CEllipsoidRangeBearing2D, mrpt::opengl::CRenderizable> cl(M("mrpt::opengl"), "CEllipsoidRangeBearing2D", "An especial \"ellipsoid\" in 2D computed as the uncertainty iso-surfaces of a\n (range,bearing) variable.\n The parameter space of this ellipsoid comprises these variables (in this\n order):\n - range: Distance from sensor to feature.\n - bearing: Angle from +X to the line that goes from the sensor towards the\n feature.\n\n This class expects you to provide a mean vector of length 2 and a 2x2\n covariance matrix, set with \n\n Please read the documentation of\n CGeneralizedEllipsoidTemplate::setQuantiles() for learning\n the mathematical details about setting the desired confidence interval.\n\n ![mrpt::opengl::CEllipsoidRangeBearing2D](preview_CEllipsoidRangeBearing2D.png)\n\n \n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CEllipsoidRangeBearing2D(); }, [](){ return new PyCallBack_mrpt_opengl_CEllipsoidRangeBearing2D(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CEllipsoidRangeBearing2D const &o){ return new PyCallBack_mrpt_opengl_CEllipsoidRangeBearing2D(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CEllipsoidRangeBearing2D const &o){ return new mrpt::opengl::CEllipsoidRangeBearing2D(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CEllipsoidRangeBearing2D::getClassName, "C++: mrpt::opengl::CEllipsoidRangeBearing2D::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CEllipsoidRangeBearing2D::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CEllipsoidRangeBearing2D::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CEllipsoidRangeBearing2D::*)() const) &mrpt::opengl::CEllipsoidRangeBearing2D::GetRuntimeClass, "C++: mrpt::opengl::CEllipsoidRangeBearing2D::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CEllipsoidRangeBearing2D::*)() const) &mrpt::opengl::CEllipsoidRangeBearing2D::clone, "C++: mrpt::opengl::CEllipsoidRangeBearing2D::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CEllipsoidRangeBearing2D::CreateObject, "C++: mrpt::opengl::CEllipsoidRangeBearing2D::CreateObject() --> class std::shared_ptr"); + cl.def("assign", (class mrpt::opengl::CEllipsoidRangeBearing2D & (mrpt::opengl::CEllipsoidRangeBearing2D::*)(const class mrpt::opengl::CEllipsoidRangeBearing2D &)) &mrpt::opengl::CEllipsoidRangeBearing2D::operator=, "C++: mrpt::opengl::CEllipsoidRangeBearing2D::operator=(const class mrpt::opengl::CEllipsoidRangeBearing2D &) --> class mrpt::opengl::CEllipsoidRangeBearing2D &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::opengl::CFBORender file:mrpt/opengl/CFBORender.h line:37 + pybind11::class_> cl(M("mrpt::opengl"), "CFBORender", "Render 3D scenes off-screen directly to RGB and/or RGB+D images.\n\n Main methods:\n - render_RGB(): Renders a scene into an RGB image.\n - render_RGBD(): Renders a scene into an RGB and depth images.\n\n To define a background color, define it in your\n `scene.getViewport()->setCustomBackgroundColor()`. You can add overlaid text\n messages, see base class CTextMessageCapable\n\n The SE(3) pose from which the scene is rendered is defined by the scene\n `\"main\"` viewport camera pose.\n See for code examples.\n\n \n , \n \n\n\n "); + cl.def( pybind11::init(), pybind11::arg("p") ); + + cl.def( pybind11::init( [](){ return new mrpt::opengl::CFBORender(); } ), "doc" ); + cl.def( pybind11::init( [](unsigned int const & a0){ return new mrpt::opengl::CFBORender(a0); } ), "doc" , pybind11::arg("width")); + cl.def( pybind11::init(), pybind11::arg("width"), pybind11::arg("height") ); + + cl.def( pybind11::init( [](mrpt::opengl::CFBORender const &o){ return new mrpt::opengl::CFBORender(o); } ) ); + cl.def("setCamera", (void (mrpt::opengl::CFBORender::*)(const class mrpt::opengl::Scene &, const class mrpt::opengl::CCamera &)) &mrpt::opengl::CFBORender::setCamera, "Change the scene camera to be used when rendering the scene through this\n particular instance of CFBORender. \n\nC++: mrpt::opengl::CFBORender::setCamera(const class mrpt::opengl::Scene &, const class mrpt::opengl::CCamera &) --> void", pybind11::arg("scene"), pybind11::arg("camera")); + cl.def("getCamera", (class mrpt::opengl::CCamera & (mrpt::opengl::CFBORender::*)(const class mrpt::opengl::Scene &)) &mrpt::opengl::CFBORender::getCamera, "Get a reference to the scene camera to be used when rendering the scene\n through this particular instance of CFBORender. \n\nC++: mrpt::opengl::CFBORender::getCamera(const class mrpt::opengl::Scene &) --> class mrpt::opengl::CCamera &", pybind11::return_value_policy::automatic, pybind11::arg("scene")); + cl.def("render_RGB", (void (mrpt::opengl::CFBORender::*)(const class mrpt::opengl::Scene &, class mrpt::img::CImage &)) &mrpt::opengl::CFBORender::render_RGB, "Render the scene and get the rendered RGB image. Resizes the image\n buffer if necessary to the configured render resolution.\n\n \n render_RGBD()\n\nC++: mrpt::opengl::CFBORender::render_RGB(const class mrpt::opengl::Scene &, class mrpt::img::CImage &) --> void", pybind11::arg("scene"), pybind11::arg("outRGB")); + cl.def("assign", (class mrpt::opengl::CFBORender & (mrpt::opengl::CFBORender::*)(const class mrpt::opengl::CFBORender &)) &mrpt::opengl::CFBORender::operator=, "C++: mrpt::opengl::CFBORender::operator=(const class mrpt::opengl::CFBORender &) --> class mrpt::opengl::CFBORender &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::opengl::CFBORender::Parameters file:mrpt/opengl/CFBORender.h line:41 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "Parameters", "Parameters for CFBORender constructor "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CFBORender::Parameters(); } ) ); + cl.def( pybind11::init(), pybind11::arg("Width"), pybind11::arg("Height") ); + + cl.def( pybind11::init( [](mrpt::opengl::CFBORender::Parameters const &o){ return new mrpt::opengl::CFBORender::Parameters(o); } ) ); + cl.def_readwrite("width", &mrpt::opengl::CFBORender::Parameters::width); + cl.def_readwrite("height", &mrpt::opengl::CFBORender::Parameters::height); + cl.def_readwrite("raw_depth", &mrpt::opengl::CFBORender::Parameters::raw_depth); + cl.def_readwrite("create_EGL_context", &mrpt::opengl::CFBORender::Parameters::create_EGL_context); + cl.def_readwrite("deviceIndexToUse", &mrpt::opengl::CFBORender::Parameters::deviceIndexToUse); + cl.def_readwrite("blueSize", &mrpt::opengl::CFBORender::Parameters::blueSize); + cl.def_readwrite("redSize", &mrpt::opengl::CFBORender::Parameters::redSize); + cl.def_readwrite("greenSize", &mrpt::opengl::CFBORender::Parameters::greenSize); + cl.def_readwrite("depthSize", &mrpt::opengl::CFBORender::Parameters::depthSize); + cl.def_readwrite("conformantOpenGLES2", &mrpt::opengl::CFBORender::Parameters::conformantOpenGLES2); + cl.def_readwrite("renderableOpenGLES2", &mrpt::opengl::CFBORender::Parameters::renderableOpenGLES2); + cl.def_readwrite("bindOpenGLES_API", &mrpt::opengl::CFBORender::Parameters::bindOpenGLES_API); + cl.def_readwrite("contextMajorVersion", &mrpt::opengl::CFBORender::Parameters::contextMajorVersion); + cl.def_readwrite("contextMinorVersion", &mrpt::opengl::CFBORender::Parameters::contextMinorVersion); + cl.def_readwrite("contextDebug", &mrpt::opengl::CFBORender::Parameters::contextDebug); + } + + } + { // mrpt::opengl::CPolyhedron file:mrpt/opengl/CPolyhedron.h line:38 + pybind11::class_, PyCallBack_mrpt_opengl_CPolyhedron, mrpt::opengl::CRenderizableShaderWireFrame, mrpt::opengl::CRenderizableShaderTriangles> cl(M("mrpt::opengl"), "CPolyhedron", "This class represents arbitrary polyhedra. The class includes a set of\n static methods to create common polyhedrons. The class includes many methods\n to create standard polyhedra, not intended to be fast but to be simple. For\n example, the dodecahedron is not created efficiently: first, an icosahedron\n is created, and a duality operator is applied to it, which yields the\n dodecahedron. This way, code is much smaller, although much slower. This is\n not a big problem, since polyhedron creation does not usually take a\n significant amount of time (they are created once and rendered many times).\n Polyhedra information and models have been gotten from the Wikipedia,\n https://wikipedia.org\n\n ![mrpt::opengl::CPolyhedron](preview_CPolyhedron.png)\n\n \n opengl::Scene\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CPolyhedron(); }, [](){ return new PyCallBack_mrpt_opengl_CPolyhedron(); } ) ); + cl.def( pybind11::init( [](const int & a0, const int & a1){ return new mrpt::opengl::CPolyhedron(a0, a1); }, [](const int & a0, const int & a1){ return new PyCallBack_mrpt_opengl_CPolyhedron(a0, a1); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("vertices"), pybind11::arg("faces"), pybind11::arg("doCheck") ); + + cl.def( pybind11::init(), pybind11::arg("polys") ); + + cl.def( pybind11::init(), pybind11::arg("vertices"), pybind11::arg("faces") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CPolyhedron const &o){ return new PyCallBack_mrpt_opengl_CPolyhedron(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CPolyhedron const &o){ return new mrpt::opengl::CPolyhedron(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CPolyhedron::getClassName, "C++: mrpt::opengl::CPolyhedron::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CPolyhedron::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CPolyhedron::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::GetRuntimeClass, "C++: mrpt::opengl::CPolyhedron::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::clone, "C++: mrpt::opengl::CPolyhedron::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CPolyhedron::CreateObject, "C++: mrpt::opengl::CPolyhedron::CreateObject() --> class std::shared_ptr"); + cl.def("renderUpdateBuffers", (void (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::renderUpdateBuffers, "C++: mrpt::opengl::CPolyhedron::renderUpdateBuffers() const --> void"); + cl.def("freeOpenGLResources", (void (mrpt::opengl::CPolyhedron::*)()) &mrpt::opengl::CPolyhedron::freeOpenGLResources, "C++: mrpt::opengl::CPolyhedron::freeOpenGLResources() --> void"); + cl.def("requiredShaders", (int (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::requiredShaders, "C++: mrpt::opengl::CPolyhedron::requiredShaders() const --> int"); + cl.def("onUpdateBuffers_Wireframe", (void (mrpt::opengl::CPolyhedron::*)()) &mrpt::opengl::CPolyhedron::onUpdateBuffers_Wireframe, "C++: mrpt::opengl::CPolyhedron::onUpdateBuffers_Wireframe() --> void"); + cl.def("onUpdateBuffers_Triangles", (void (mrpt::opengl::CPolyhedron::*)()) &mrpt::opengl::CPolyhedron::onUpdateBuffers_Triangles, "C++: mrpt::opengl::CPolyhedron::onUpdateBuffers_Triangles() --> void"); + cl.def_static("CreateTetrahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTetrahedron, " @{\n\n Creates a regular tetrahedron (see\n http://en.wikipedia.org/wiki/Tetrahedron). The tetrahedron is created as a\n triangular pyramid whose edges and vertices are transitive.\n The tetrahedron is the dual to itself.\n \n \n\n\n CreatePyramid,CreateJohnsonSolidWithConstantBase,CreateTruncatedTetrahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTetrahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateHexahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateHexahedron, "Creates a regular cube, also called hexahedron (see\n http://en.wikipedia.org/wiki/Hexahedron). The hexahedron is created as a\n cubic prism which transitive edges. Another ways to create it include:\n Dual to an octahedron.Parallelepiped with three\n orthogonal, equally-lengthed vectors.Triangular trapezohedron\n with proper height.\n \n \n\n\n CreateOctahedron,getDual,CreateParallelepiped,CreateTrapezohedron,CreateTruncatedHexahedron,CreateTruncatedOctahedron,CreateCuboctahedron,CreateRhombicuboctahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateHexahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateOctahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateOctahedron, "Creates a regular octahedron (see\n http://en.wikipedia.org/wiki/Octahedron). The octahedron is created as a\n square bipyramid whit transitive edges and vertices. Another ways to\n create an octahedron are:\n Dual to an hexahedronTriangular antiprism with transitive\n vertices.Conveniently truncated tetrahedron.\n \n \n\n\n CreateHexahedron,getDual,CreateArchimedeanAntiprism,CreateTetrahedron,truncate,CreateTruncatedOctahedron,CreateTruncatedHexahedron,CreateCuboctahedron,CreateRhombicuboctahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateOctahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateDodecahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateDodecahedron, "Creates a regular dodecahedron (see\n http://en.wikipedia.org/wiki/Dodecahedron). The dodecahedron is created as\n the dual to an icosahedron.\n \n \n\n\n CreateIcosahedron,getDual,CreateTruncatedDodecahedron,CreateTruncatedIcosahedron,CreateIcosidodecahedron,CreateRhombicosidodecahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateDodecahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateIcosahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateIcosahedron, "Creates a regular icosahedron (see\n http://en.wikipedia.org/wiki/Icosahedron). The icosahedron is created as a\n gyroelongated pentagonal bipyramid with transitive edges, and it's the\n dual to a dodecahedron.\n \n \n\n\n CreateJohnsonSolidWithConstantBase,CreateDodecahedron,getDual,CreateTruncatedIcosahedron,CreateTruncatedDodecahedron,CreateIcosidodecahedron,CreateRhombicosidodecahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateIcosahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTruncatedTetrahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTruncatedTetrahedron, " @{\n\n Creates a truncated tetrahedron, consisting of four triangular faces and\n for hexagonal ones (see\n http://en.wikipedia.org/wiki/Truncated_tetrahedron). Its dual is the\n triakis tetrahedron.\n \n \n\n CreateTetrahedron,CreateTriakisTetrahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTruncatedTetrahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateCuboctahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateCuboctahedron, "Creates a cuboctahedron, consisting of six square faces and eight\n triangular ones (see http://en.wikipedia.org/wiki/Cuboctahedron). There\n are several ways to create a cuboctahedron:\n Hexahedron truncated to a certain extent.Octahedron\n truncated to a certain extent.Cantellated\n tetrahedronDual to a rhombic dodecahedron.\n \n \n\n\n CreateHexahedron,CreateOctahedron,truncate,CreateTetrahedron,cantellate,CreateRhombicuboctahedron,CreateRhombicDodecahedron,\n\nC++: mrpt::opengl::CPolyhedron::CreateCuboctahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTruncatedHexahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTruncatedHexahedron, "Creates a truncated hexahedron, with six octogonal faces and eight\n triangular ones (see http://en.wikipedia.org/wiki/Truncated_hexahedron).\n The truncated octahedron is dual to the triakis octahedron.\n \n \n\n CreateHexahedron,CreateTriakisOctahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTruncatedHexahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTruncatedOctahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTruncatedOctahedron, "Creates a truncated octahedron, with eight hexagons and eight squares\n (see http://en.wikipedia.org/wiki/Truncated_octahedron). It's the dual to\n the tetrakis hexahedron.\n \n \n\n CreateOctahedron,CreateTetrakisHexahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTruncatedOctahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateRhombicuboctahedron", [](double const & a0) -> std::shared_ptr { return mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron(a0); }, "", pybind11::arg("radius")); + cl.def_static("CreateRhombicuboctahedron", (class std::shared_ptr (*)(double, bool)) &mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron, "Creates a rhombicuboctahedron, with 18 squares and 8 triangles (see\n http://en.wikipedia.org/wiki/Rhombicuboctahedron), calculated as an\n elongated square bicupola. It can also be calculated as a cantellated\n hexahedron or octahedron, and its dual is the deltoidal icositetrahedron.\n If the second argument is set to false, the lower cupola is rotated, so\n that the objet created is an elongated square gyrobicupola (see\n http://en.wikipedia.org/wiki/Elongated_square_gyrobicupola). This is not\n an archimedean solid, but a Johnson one, since it hasn't got vertex\n transitivity.\n \n \n\n\n CreateJohnsonSolidWithConstantBase,CreateHexahedron,CreateOctahedron,cantellate,CreateCuboctahedron,CreateDeltoidalIcositetrahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateRhombicuboctahedron(double, bool) --> class std::shared_ptr", pybind11::arg("radius"), pybind11::arg("type")); + cl.def_static("CreateIcosidodecahedron", [](double const & a0) -> std::shared_ptr { return mrpt::opengl::CPolyhedron::CreateIcosidodecahedron(a0); }, "", pybind11::arg("radius")); + cl.def_static("CreateIcosidodecahedron", (class std::shared_ptr (*)(double, bool)) &mrpt::opengl::CPolyhedron::CreateIcosidodecahedron, "Creates an icosidodecahedron, with 12 pentagons and 20 triangles (see\n http://en.wikipedia.org/wiki/Icosidodecahedron). Certain truncations of\n either a dodecahedron or an icosahedron yield an icosidodecahedron.\n The dual of the icosidodecahedron is the rhombic triacontahedron.\n If the second argument is set to false, the lower rotunda is rotated. In\n this case, the object created is a pentagonal orthobirotunda (see\n http://en.wikipedia.org/wiki/Pentagonal_orthobirotunda). This object\n presents symmetry against the XY plane and is not vertex transitive, so\n it's a Johnson's solid.\n \n \n\n\n CreateDodecahedron,CreateIcosahedron,truncate,CreateRhombicosidodecahedron,CreateRhombicTriacontahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateIcosidodecahedron(double, bool) --> class std::shared_ptr", pybind11::arg("radius"), pybind11::arg("type")); + cl.def_static("CreateTruncatedDodecahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTruncatedDodecahedron, "Creates a truncated dodecahedron, consisting of 12 dodecagons and 20\n triangles (see http://en.wikipedia.org/wiki/Truncated_dodecahedron). The\n truncated dodecahedron is the dual to the triakis icosahedron.\n \n \n\n CreateDodecahedron,CreateTriakisIcosahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTruncatedDodecahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTruncatedIcosahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTruncatedIcosahedron, "Creates a truncated icosahedron, consisting of 20 hexagons and 12\n pentagons. This object resembles a typical soccer ball (see\n http://en.wikipedia.org/wiki/Truncated_icosahedron). The pentakis\n dodecahedron is the dual to the truncated icosahedron.\n \n \n\n CreateIcosahedron,CreatePentakisDodecahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTruncatedIcosahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateRhombicosidodecahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateRhombicosidodecahedron, "Creates a rhombicosidodecahedron, consisting of 30 squares, 12 pentagons\n and 20 triangles (see\n http://en.wikipedia.org/wiki/Rhombicosidodecahedron). This object can be\n obtained as the cantellation of either a dodecahedron or an icosahedron.\n The dual of the rhombicosidodecahedron is the deltoidal hexecontahedron.\n \n \n\n\n CreateDodecahedron,CreateIcosahedron,CreateIcosidodecahedron,CreateDeltoidalHexecontahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateRhombicosidodecahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreatePentagonalRotunda", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreatePentagonalRotunda, " @{\n\n Creates a pentagonal rotunda (half an icosidodecahedron), consisting of\n six pentagons, ten triangles and a decagon (see\n http://en.wikipedia.org/wiki/Pentagonal_rotunda).\n \n\n CreateIcosidodecahedron,CreateJohnsonSolidWithConstantBase\n\nC++: mrpt::opengl::CPolyhedron::CreatePentagonalRotunda(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTriakisTetrahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTriakisTetrahedron, " @{\n\n Creates a triakis tetrahedron, dual to the truncated tetrahedron. This\n body consists of 12 isosceles triangles (see\n http://en.wikipedia.org/wiki/Triakis_tetrahedron).\n \n \n\n CreateTruncatedTetrahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTriakisTetrahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateRhombicDodecahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateRhombicDodecahedron, "Creates a rhombic dodecahedron, dual to the cuboctahedron. This body\n consists of 12 rhombi (see\n http://en.wikipedia.org/wiki/Rhombic_dodecahedron).\n \n \n\n CreateCuboctahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateRhombicDodecahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTriakisOctahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTriakisOctahedron, "Creates a triakis octahedron, dual to the truncated hexahedron. This\n body consists of 24 isosceles triangles (see\n http://en.wikipedia.org/wiki/Triakis_octahedron).\n \n \n\n CreateTruncatedHexahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTriakisOctahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTetrakisHexahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTetrakisHexahedron, "Creates a tetrakis hexahedron, dual to the truncated octahedron. This\n body consists of 24 isosceles triangles (see\n http://en.wikipedia.org/wiki/Tetrakis_hexahedron).\n \n \n\n CreateTruncatedOctahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTetrakisHexahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateDeltoidalIcositetrahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateDeltoidalIcositetrahedron, "Creates a deltoidal icositetrahedron, dual to the rhombicuboctahedron.\n This body consists of 24 kites (see\n http://en.wikipedia.org/wiki/Deltoidal_icositetrahedron).\n \n \n\n CreateRhombicuboctahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateDeltoidalIcositetrahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateRhombicTriacontahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateRhombicTriacontahedron, "Creates a rhombic triacontahedron, dual to the icosidodecahedron. This\n body consists of 30 rhombi (see\n http://en.wikipedia.org/wiki/Rhombic_triacontahedron).\n \n \n\n CreateIcosidodecahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateRhombicTriacontahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateTriakisIcosahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateTriakisIcosahedron, "Creates a triakis icosahedron, dual to the truncated dodecahedron. This\n body consists of 60 isosceles triangles\n http://en.wikipedia.org/wiki/Triakis_icosahedron).\n \n \n\n CreateTruncatedDodecahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateTriakisIcosahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreatePentakisDodecahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreatePentakisDodecahedron, "Creates a pentakis dodecahedron, dual to the truncated icosahedron. This\n body consists of 60 isosceles triangles (see\n http://en.wikipedia.org/wiki/Pentakis_dodecahedron).\n \n \n\n CreateTruncatedIcosahedron\n\nC++: mrpt::opengl::CPolyhedron::CreatePentakisDodecahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateDeltoidalHexecontahedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateDeltoidalHexecontahedron, "Creates a deltoidal hexecontahedron, dual to the rhombicosidodecahedron.\n This body consists of 60 kites (see\n http://en.wikipedia.org/wiki/Deltoidal_hexecontahedron).\n \n \n\n CreateRhombicosidodecahedron\n\nC++: mrpt::opengl::CPolyhedron::CreateDeltoidalHexecontahedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def_static("CreateCubicPrism", (class std::shared_ptr (*)(double, double, double, double, double, double)) &mrpt::opengl::CPolyhedron::CreateCubicPrism, " @{\n\n Creates a cubic prism, given the coordinates of two opposite vertices.\n Each edge will be parallel to one of the coordinate axes, although the\n orientation may change by assigning a pose to the object.\n \n\n CreateCubicPrism(const mrpt::math::TPoint3D &,const\n mrpt::math::TPoint3D\n &),CreateParallelepiped,CreateCustomPrism,CreateRegularPrism,CreateArchimedeanRegularPrism\n\nC++: mrpt::opengl::CPolyhedron::CreateCubicPrism(double, double, double, double, double, double) --> class std::shared_ptr", pybind11::arg("x1"), pybind11::arg("x2"), pybind11::arg("y1"), pybind11::arg("y2"), pybind11::arg("z1"), pybind11::arg("z2")); + cl.def_static("CreatePyramid", (class std::shared_ptr (*)(const int &, double)) &mrpt::opengl::CPolyhedron::CreatePyramid, "Creates a custom pyramid, using a set of 2D vertices which will lie on\n the XY plane.\n \n\n\n CreateDoublePyramid,CreateFrustum,CreateBifrustum,CreateRegularPyramid\n\nC++: mrpt::opengl::CPolyhedron::CreatePyramid(const int &, double) --> class std::shared_ptr", pybind11::arg("baseVertices"), pybind11::arg("height")); + cl.def_static("CreateDoublePyramid", (class std::shared_ptr (*)(const int &, double, double)) &mrpt::opengl::CPolyhedron::CreateDoublePyramid, "Creates a double pyramid, using a set of 2D vertices which will lie on\n the XY plane. The second height is used with the downwards pointing\n pyramid, so that it will effectively point downwards if it's positive.\n \n\n CreatePyramid,CreateBifrustum,CreateRegularDoublePyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateDoublePyramid(const int &, double, double) --> class std::shared_ptr", pybind11::arg("baseVertices"), pybind11::arg("height1"), pybind11::arg("height2")); + cl.def_static("CreateTruncatedPyramid", (class std::shared_ptr (*)(const int &, double, double)) &mrpt::opengl::CPolyhedron::CreateTruncatedPyramid, "Creates a truncated pyramid, using a set of vertices which will lie on\n the XY plane.\n Do not try to use with a ratio equal to zero; use CreatePyramid instead.\n When using a ratio of 1, it will create a Prism.\n \n\n CreatePyramid,CreateBifrustum\n\nC++: mrpt::opengl::CPolyhedron::CreateTruncatedPyramid(const int &, double, double) --> class std::shared_ptr", pybind11::arg("baseVertices"), pybind11::arg("height"), pybind11::arg("ratio")); + cl.def_static("CreateFrustum", (class std::shared_ptr (*)(const int &, double, double)) &mrpt::opengl::CPolyhedron::CreateFrustum, "This is a synonym for CreateTruncatedPyramid.\n \n\n CreateTruncatedPyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateFrustum(const int &, double, double) --> class std::shared_ptr", pybind11::arg("baseVertices"), pybind11::arg("height"), pybind11::arg("ratio")); + cl.def_static("CreateCustomPrism", (class std::shared_ptr (*)(const int &, double)) &mrpt::opengl::CPolyhedron::CreateCustomPrism, "Creates a custom prism with vertical edges, given any base which will\n lie on the XY plane.\n \n\n\n CreateCubicPrism,CreateCustomAntiprism,CreateRegularPrism,CreateArchimedeanRegularPrism\n\nC++: mrpt::opengl::CPolyhedron::CreateCustomPrism(const int &, double) --> class std::shared_ptr", pybind11::arg("baseVertices"), pybind11::arg("height")); + cl.def_static("CreateCustomAntiprism", (class std::shared_ptr (*)(const int &, const int &, double)) &mrpt::opengl::CPolyhedron::CreateCustomAntiprism, "Creates a custom antiprism, using two custom bases. For better results,\n the top base should be slightly rotated with respect to the bottom one.\n \n\n\n CreateCustomPrism,CreateRegularAntiprism,CreateArchimedeanRegularAntiprism\n\nC++: mrpt::opengl::CPolyhedron::CreateCustomAntiprism(const int &, const int &, double) --> class std::shared_ptr", pybind11::arg("bottomBase"), pybind11::arg("topBase"), pybind11::arg("height")); + cl.def_static("CreateBifrustum", (class std::shared_ptr (*)(const int &, double, double, double, double)) &mrpt::opengl::CPolyhedron::CreateBifrustum, "Creates a bifrustum, or double truncated pyramid, given a base which\n will lie on the XY plane.\n \n\n CreateFrustum,CreateDoublePyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateBifrustum(const int &, double, double, double, double) --> class std::shared_ptr", pybind11::arg("baseVertices"), pybind11::arg("height1"), pybind11::arg("ratio1"), pybind11::arg("height2"), pybind11::arg("ratio2")); + cl.def_static("CreateTrapezohedron", (class std::shared_ptr (*)(uint32_t, double, double)) &mrpt::opengl::CPolyhedron::CreateTrapezohedron, "Creates a trapezohedron, consisting of 2*N kites, where N is the number\n of edges in the base. The base radius controls the polyhedron height,\n whilst the distance between bases affects the height.\n When the number of edges equals 3, the polyhedron is actually a\n parallelepiped, and it can even be a cube.\n\nC++: mrpt::opengl::CPolyhedron::CreateTrapezohedron(uint32_t, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("basesDistance")); + cl.def_static("CreateRegularAntiprism", (class std::shared_ptr (*)(uint32_t, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularAntiprism, "Creates an antiprism whose base is a regular polygon. The upper base is\n rotated \n\n with respect to the lower one, where N is the\n number of vertices in the base, and thus the lateral triangles are\n isosceles.\n \n\n CreateCustomAntiprism,CreateArchimedeanRegularAntiprism\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularAntiprism(uint32_t, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height")); + cl.def_static("CreateRegularPrism", (class std::shared_ptr (*)(uint32_t, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularPrism, "Creates a regular prism whose base is a regular polygon and whose edges\n are either parallel or perpendicular to the XY plane.\n \n\n CreateCubicPrism,CreateCustomPrism,CreateArchimedeanRegularAntiprism\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularPrism(uint32_t, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height")); + cl.def_static("CreateRegularPyramid", (class std::shared_ptr (*)(uint32_t, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularPyramid, "Creates a regular pyramid whose base is a regular polygon.\n \n\n CreatePyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularPyramid(uint32_t, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height")); + cl.def_static("CreateRegularDoublePyramid", (class std::shared_ptr (*)(uint32_t, double, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularDoublePyramid, "Creates a regular double pyramid whose base is a regular polygon.\n \n\n CreateDoublePyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularDoublePyramid(uint32_t, double, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height1"), pybind11::arg("height2")); + cl.def_static("CreateArchimedeanRegularPrism", (class std::shared_ptr (*)(uint32_t, double)) &mrpt::opengl::CPolyhedron::CreateArchimedeanRegularPrism, "Creates a regular prism whose lateral area is comprised of squares, and\n so each face of its is a regular polygon. Due to vertex transitivity, the\n resulting object is always archimedean.\n \n\n CreateRegularPrism,CreateCustomPrism\n\nC++: mrpt::opengl::CPolyhedron::CreateArchimedeanRegularPrism(uint32_t, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius")); + cl.def_static("CreateArchimedeanRegularAntiprism", (class std::shared_ptr (*)(uint32_t, double)) &mrpt::opengl::CPolyhedron::CreateArchimedeanRegularAntiprism, "Creates a regular antiprism whose lateral polygons are equilateral\n triangles, and so each face of its is a regular polygon. Due to vertex\n transitivity, the resulting object is always archimedean.\n \n\n CreateRegularAntiprism,CreateCustomAntiprism\n\nC++: mrpt::opengl::CPolyhedron::CreateArchimedeanRegularAntiprism(uint32_t, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius")); + cl.def_static("CreateRegularTruncatedPyramid", (class std::shared_ptr (*)(uint32_t, double, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularTruncatedPyramid, "Creates a regular truncated pyramid whose base is a regular polygon.\n \n\n CreateTruncatedPyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularTruncatedPyramid(uint32_t, double, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height"), pybind11::arg("ratio")); + cl.def_static("CreateRegularFrustum", (class std::shared_ptr (*)(uint32_t, double, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularFrustum, "This is a synonym for CreateRegularTruncatedPyramid.\n \n\n CreateRegularTruncatedPyramid\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularFrustum(uint32_t, double, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height"), pybind11::arg("ratio")); + cl.def_static("CreateRegularBifrustum", (class std::shared_ptr (*)(uint32_t, double, double, double, double, double)) &mrpt::opengl::CPolyhedron::CreateRegularBifrustum, "Creates a bifrustum (double truncated pyramid) whose base is a regular\n polygon lying in the XY plane.\n \n\n CreateBifrustum\n\nC++: mrpt::opengl::CPolyhedron::CreateRegularBifrustum(uint32_t, double, double, double, double, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("height1"), pybind11::arg("ratio1"), pybind11::arg("height2"), pybind11::arg("ratio2")); + cl.def_static("CreateCupola", (class std::shared_ptr (*)(uint32_t, double)) &mrpt::opengl::CPolyhedron::CreateCupola, "Creates a cupola.\n \n\n std::logic_error if the number of edges is odd or less than four.\n\nC++: mrpt::opengl::CPolyhedron::CreateCupola(uint32_t, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("edgeLength")); + cl.def_static("CreateCatalanTrapezohedron", (class std::shared_ptr (*)(uint32_t, double)) &mrpt::opengl::CPolyhedron::CreateCatalanTrapezohedron, "Creates a trapezohedron whose dual is exactly an archimedean antiprism.\n Creates a cube if numBaseEdges is equal to 3.\n \n\n Actually resulting height is significantly higher than that passed\n to the algorithm.\n \n\n CreateTrapezohedron,CreateArchimedeanRegularAntiprism,getDual\n\nC++: mrpt::opengl::CPolyhedron::CreateCatalanTrapezohedron(uint32_t, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("height")); + cl.def_static("CreateCatalanDoublePyramid", (class std::shared_ptr (*)(uint32_t, double)) &mrpt::opengl::CPolyhedron::CreateCatalanDoublePyramid, "Creates a double pyramid whose dual is exactly an archimedean prism.\n Creates an octahedron if numBaseEdges is equal to 4.\n \n\n Actually resulting height is significantly higher than that passed\n to the algorithm.\n \n\n CreateDoublePyramid,CreateArchimedeanRegularPrism,getDual\n\nC++: mrpt::opengl::CPolyhedron::CreateCatalanDoublePyramid(uint32_t, double) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("height")); + cl.def_static("CreateJohnsonSolidWithConstantBase", [](uint32_t const & a0, double const & a1, const std::string & a2) -> std::shared_ptr { return mrpt::opengl::CPolyhedron::CreateJohnsonSolidWithConstantBase(a0, a1, a2); }, "", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("components")); + cl.def_static("CreateJohnsonSolidWithConstantBase", (class std::shared_ptr (*)(uint32_t, double, const std::string &, size_t)) &mrpt::opengl::CPolyhedron::CreateJohnsonSolidWithConstantBase, "Creates a series of concatenated solids (most of which are prismatoids)\n whose base is a regular polygon with a given number of edges. Every face\n of the resulting body will be a regular polygon, so it is a Johnson solid;\n in special cases, it may be archimedean or even platonic.\n The shape of the body is defined by the string argument, which can\n include one or more of the following:\n
\n StringBodyRestrictions\n P+Upward pointing pyramidMust be the last\n object, vertex number cannot surpass 5\n P-Downward pointing pyramidMust be the first\n object, vertex number cannot surpass 5\n C+Upward pointing cupolaMust be the last object,\n vertex number must be an even number in the range 4-10.\n C-Downward pointing cupolaMust be the first\n object, vertex number must be an even number in the range 4-10.\n GC+Upward pointing cupola, rotatedMust be the\n last object, vertex number must be an even number in the range\n 4-10.\n GC-Downward pointing cupola, rotatedMust be the\n first object, vertex number must be an even number in the range\n 4-10.\n PRArchimedean prismCannot abut other\n prism\n AArchimedean antiprismNone\n R+Upward pointing rotundaMust be the last\n object, vertex number must be exactly 10\n R-Downward pointing rotundaMust be the first\n object, vertex number must be exactly 10\n GR+Upward pointing rotunda, rotatedMust be the\n last object, vertex number must be exactly 10\n GR-Downward pointing rotundaMust be the first\n object, vertex number must be exactly 10\n
\n Some examples of bodies are:\n
\n StringVerticesResulting\n body\n P+3Tetrahedron\n PR4Hexahedron\n P-P+4Octahedron\n A3Octahedron\n C+PRC-\n8Rhombicuboctahedron\n P-AP+5Icosahedron\n R-R+10Icosidodecahedron\n
\n\nC++: mrpt::opengl::CPolyhedron::CreateJohnsonSolidWithConstantBase(uint32_t, double, const std::string &, size_t) --> class std::shared_ptr", pybind11::arg("numBaseEdges"), pybind11::arg("baseRadius"), pybind11::arg("components"), pybind11::arg("shifts")); + cl.def("traceRay", (bool (mrpt::opengl::CPolyhedron::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CPolyhedron::traceRay, "@}\n\nC++: mrpt::opengl::CPolyhedron::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist")); + cl.def("getVertices", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getVertices, "Gets a list with the polyhedron's vertices.\n\nC++: mrpt::opengl::CPolyhedron::getVertices(int &) const --> void", pybind11::arg("vertices")); + cl.def("getEdges", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getEdges, "Gets a list with the polyhedron's edges.\n\nC++: mrpt::opengl::CPolyhedron::getEdges(int &) const --> void", pybind11::arg("edges")); + cl.def("getFaces", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getFaces, "Gets a list with the polyhedron's faces.\n\nC++: mrpt::opengl::CPolyhedron::getFaces(int &) const --> void", pybind11::arg("faces")); + cl.def("getNumberOfVertices", (uint32_t (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::getNumberOfVertices, "Gets the amount of vertices.\n\nC++: mrpt::opengl::CPolyhedron::getNumberOfVertices() const --> uint32_t"); + cl.def("getNumberOfEdges", (uint32_t (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::getNumberOfEdges, "Gets the amount of edges.\n\nC++: mrpt::opengl::CPolyhedron::getNumberOfEdges() const --> uint32_t"); + cl.def("getNumberOfFaces", (uint32_t (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::getNumberOfFaces, "Gets the amount of faces.\n\nC++: mrpt::opengl::CPolyhedron::getNumberOfFaces() const --> uint32_t"); + cl.def("getEdgesLength", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getEdgesLength, "Gets a vector with each edge's length.\n\nC++: mrpt::opengl::CPolyhedron::getEdgesLength(int &) const --> void", pybind11::arg("lengths")); + cl.def("getFacesArea", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getFacesArea, "Gets a vector with each face's area. Won't work properly if the polygons\n are not convex.\n\nC++: mrpt::opengl::CPolyhedron::getFacesArea(int &) const --> void", pybind11::arg("areas")); + cl.def("getVolume", (double (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::getVolume, "Gets the polyhedron volume. Won't work properly if the polyhedron is not\n convex.\n\nC++: mrpt::opengl::CPolyhedron::getVolume() const --> double"); + cl.def("isWireframe", (bool (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::isWireframe, "Returns whether the polyhedron will be rendered as a wireframe object.\n\nC++: mrpt::opengl::CPolyhedron::isWireframe() const --> bool"); + cl.def("setWireframe", [](mrpt::opengl::CPolyhedron &o) -> void { return o.setWireframe(); }, ""); + cl.def("setWireframe", (void (mrpt::opengl::CPolyhedron::*)(bool)) &mrpt::opengl::CPolyhedron::setWireframe, "Sets whether the polyhedron will be rendered as a wireframe object.\n\nC++: mrpt::opengl::CPolyhedron::setWireframe(bool) --> void", pybind11::arg("enabled")); + cl.def("getSetOfPolygons", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getSetOfPolygons, "Gets the polyhedron as a set of polygons.\n \n\n mrpt::math::TPolygon3D\n\nC++: mrpt::opengl::CPolyhedron::getSetOfPolygons(int &) const --> void", pybind11::arg("vec")); + cl.def("getSetOfPolygonsAbsolute", (void (mrpt::opengl::CPolyhedron::*)(int &) const) &mrpt::opengl::CPolyhedron::getSetOfPolygonsAbsolute, "Gets the polyhedron as a set of polygons, with the pose transformation\n already applied.\n \n\n mrpt::math::TPolygon3D,mrpt::poses::CPose3D\n\nC++: mrpt::opengl::CPolyhedron::getSetOfPolygonsAbsolute(int &) const --> void", pybind11::arg("vec")); + cl.def("isClosed", (bool (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::isClosed, "Returns true if the polygon is a completely closed object.\n\nC++: mrpt::opengl::CPolyhedron::isClosed() const --> bool"); + cl.def("makeConvexPolygons", (void (mrpt::opengl::CPolyhedron::*)()) &mrpt::opengl::CPolyhedron::makeConvexPolygons, "Recomputes polygons, if necessary, so that each one is convex.\n\nC++: mrpt::opengl::CPolyhedron::makeConvexPolygons() --> void"); + cl.def_static("CreateRandomPolyhedron", (class std::shared_ptr (*)(double)) &mrpt::opengl::CPolyhedron::CreateRandomPolyhedron, "Creates a random polyhedron from the static methods.\n\nC++: mrpt::opengl::CPolyhedron::CreateRandomPolyhedron(double) --> class std::shared_ptr", pybind11::arg("radius")); + cl.def("getDual", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::getDual, " @{\n\n Given a polyhedron, creates its dual.\n \n\n truncate,cantellate,augment\n \n\n std::logic_error Can't get the dual to this polyhedron.\n\nC++: mrpt::opengl::CPolyhedron::getDual() const --> class std::shared_ptr"); + cl.def("truncate", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(double) const) &mrpt::opengl::CPolyhedron::truncate, "Truncates a polyhedron to a given factor.\n \n\n getDual,cantellate,augment\n \n\n std::logic_error Polyhedron truncation results in skew polygons\n and thus it's impossible to perform.\n\nC++: mrpt::opengl::CPolyhedron::truncate(double) const --> class std::shared_ptr", pybind11::arg("factor")); + cl.def("cantellate", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(double) const) &mrpt::opengl::CPolyhedron::cantellate, "Cantellates a polyhedron to a given factor.\n \n\n getDual,truncate,augment\n\nC++: mrpt::opengl::CPolyhedron::cantellate(double) const --> class std::shared_ptr", pybind11::arg("factor")); + cl.def("augment", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(double) const) &mrpt::opengl::CPolyhedron::augment, "Augments a polyhedron to a given height. This operation is roughly dual\n to the truncation: given a body P, the operation dtdP and aP yield\n resembling results.\n \n\n getDual,truncate,cantellate\n\nC++: mrpt::opengl::CPolyhedron::augment(double) const --> class std::shared_ptr", pybind11::arg("height")); + cl.def("augment", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(double, size_t) const) &mrpt::opengl::CPolyhedron::augment, "Augments a polyhedron to a given height. This method only affects to\n faces with certain number of vertices.\n \n\n augment(double) const\n\nC++: mrpt::opengl::CPolyhedron::augment(double, size_t) const --> class std::shared_ptr", pybind11::arg("height"), pybind11::arg("numVertices")); + cl.def("augment", [](mrpt::opengl::CPolyhedron const &o) -> std::shared_ptr { return o.augment(); }, ""); + cl.def("augment", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(bool) const) &mrpt::opengl::CPolyhedron::augment, "Augments a polyhedron, so that the resulting triangles are equilateral.\n If the argument is true, triangles are \"cut\" from the polyhedron, instead\n of being added.\n \n\n std::logic_error a non-regular face has been found.\n \n\n augment(double) const\n\nC++: mrpt::opengl::CPolyhedron::augment(bool) const --> class std::shared_ptr", pybind11::arg("direction")); + cl.def("augment", [](mrpt::opengl::CPolyhedron const &o, size_t const & a0) -> std::shared_ptr { return o.augment(a0); }, "", pybind11::arg("numVertices")); + cl.def("augment", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(size_t, bool) const) &mrpt::opengl::CPolyhedron::augment, "Augments a polyhedron, so that the resulting triangles are equilateral;\n affects only faces with certain number of faces. If the second argument\n is true, triangles are \"cut\" from the polyhedron.\n \n\n std::logic_error a non-regular face has been found.\n \n\n augment(double) const\n\nC++: mrpt::opengl::CPolyhedron::augment(size_t, bool) const --> class std::shared_ptr", pybind11::arg("numVertices"), pybind11::arg("direction")); + cl.def("rotate", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(double) const) &mrpt::opengl::CPolyhedron::rotate, "Rotates a polyhedron around the Z axis a given amount of radians. In\nsome cases, this operation may be necessary to view the symmetry between\nrelated objects.\n \n\n scale\n\nC++: mrpt::opengl::CPolyhedron::rotate(double) const --> class std::shared_ptr", pybind11::arg("angle")); + cl.def("scale", (class std::shared_ptr (mrpt::opengl::CPolyhedron::*)(double) const) &mrpt::opengl::CPolyhedron::scale, "Scales a polyhedron to a given factor.\n \n\n std::logic_error factor is not a strictly positive number.\n \n\n rotate\n\nC++: mrpt::opengl::CPolyhedron::scale(double) const --> class std::shared_ptr", pybind11::arg("factor")); + cl.def("updatePolygons", (void (mrpt::opengl::CPolyhedron::*)() const) &mrpt::opengl::CPolyhedron::updatePolygons, "@}\n\n Updates the mutable list of polygons used in rendering and ray tracing.\n\nC++: mrpt::opengl::CPolyhedron::updatePolygons() const --> void"); + cl.def("InitFromVertAndFaces", [](mrpt::opengl::CPolyhedron &o, const int & a0, const int & a1) -> void { return o.InitFromVertAndFaces(a0, a1); }, "", pybind11::arg("vertices"), pybind11::arg("faces")); + cl.def("InitFromVertAndFaces", (void (mrpt::opengl::CPolyhedron::*)(const int &, const int &, bool)) &mrpt::opengl::CPolyhedron::InitFromVertAndFaces, "C++: mrpt::opengl::CPolyhedron::InitFromVertAndFaces(const int &, const int &, bool) --> void", pybind11::arg("vertices"), pybind11::arg("faces"), pybind11::arg("doCheck")); + cl.def_static("CreateNoCheck", (class std::shared_ptr (*)(const int &, const int &)) &mrpt::opengl::CPolyhedron::CreateNoCheck, "Creates a polyhedron without checking its correctness. \n\nC++: mrpt::opengl::CPolyhedron::CreateNoCheck(const int &, const int &) --> class std::shared_ptr", pybind11::arg("vertices"), pybind11::arg("faces")); + cl.def_static("CreateEmpty", (class std::shared_ptr (*)()) &mrpt::opengl::CPolyhedron::CreateEmpty, "Creates an empty Polyhedron. \n\nC++: mrpt::opengl::CPolyhedron::CreateEmpty() --> class std::shared_ptr"); + cl.def("assign", (class mrpt::opengl::CPolyhedron & (mrpt::opengl::CPolyhedron::*)(const class mrpt::opengl::CPolyhedron &)) &mrpt::opengl::CPolyhedron::operator=, "C++: mrpt::opengl::CPolyhedron::operator=(const class mrpt::opengl::CPolyhedron &) --> class mrpt::opengl::CPolyhedron &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::opengl::CPolyhedron::TPolyhedronEdge file:mrpt/opengl/CPolyhedron.h line:66 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TPolyhedronEdge", "Struct used to store a polyhedron edge. The struct consists only of two\n vertex indices, used to access the polyhedron vertex list."); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CPolyhedron::TPolyhedronEdge(); } ) ); + cl.def_readwrite("v1", &mrpt::opengl::CPolyhedron::TPolyhedronEdge::v1); + cl.def_readwrite("v2", &mrpt::opengl::CPolyhedron::TPolyhedronEdge::v2); + cl.def("__eq__", (bool (mrpt::opengl::CPolyhedron::TPolyhedronEdge::*)(const struct mrpt::opengl::CPolyhedron::TPolyhedronEdge &) const) &mrpt::opengl::CPolyhedron::TPolyhedronEdge::operator==, "Comparison agains another edge. Simmetry is taken into account.\n\nC++: mrpt::opengl::CPolyhedron::TPolyhedronEdge::operator==(const struct mrpt::opengl::CPolyhedron::TPolyhedronEdge &) const --> bool", pybind11::arg("e")); + cl.def("length", (double (mrpt::opengl::CPolyhedron::TPolyhedronEdge::*)(const int &) const) &mrpt::opengl::CPolyhedron::TPolyhedronEdge::length, "Given a set of vertices, computes the length of the vertex.\n\nC++: mrpt::opengl::CPolyhedron::TPolyhedronEdge::length(const int &) const --> double", pybind11::arg("vs")); + } + + { // mrpt::opengl::CPolyhedron::TPolyhedronFace file:mrpt/opengl/CPolyhedron.h line:98 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TPolyhedronFace", "Struct used to store a polyhedron face. Consists on a set of vertex\n indices and a normal vector."); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CPolyhedron::TPolyhedronFace(); } ) ); + cl.def_readwrite("vertices", &mrpt::opengl::CPolyhedron::TPolyhedronFace::vertices); + cl.def("area", (double (mrpt::opengl::CPolyhedron::TPolyhedronFace::*)(const int &) const) &mrpt::opengl::CPolyhedron::TPolyhedronFace::area, "Given a set of vertices, computes the area of this face. \n\nC++: mrpt::opengl::CPolyhedron::TPolyhedronFace::area(const int &) const --> double", pybind11::arg("vertices")); + } + + } +} diff --git a/python/generated-sources-pybind/mrpt/opengl/CGridPlaneXZ.cpp b/python/generated-sources-pybind/mrpt/opengl/CGridPlaneXZ.cpp new file mode 100644 index 0000000000..f561a60726 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/opengl/CGridPlaneXZ.cpp @@ -0,0 +1,582 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::opengl::CGridPlaneXZ file:mrpt/opengl/CGridPlaneXZ.h line:23 +struct PyCallBack_mrpt_opengl_CGridPlaneXZ : public mrpt::opengl::CGridPlaneXZ { + using mrpt::opengl::CGridPlaneXZ::CGridPlaneXZ; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CGridPlaneXZ::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CGridPlaneXZ::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CGridPlaneXZ::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CGridPlaneXZ::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CGridPlaneXZ::serializeFrom(a0, a1); + } + void onUpdateBuffers_Wireframe() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Wireframe"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CGridPlaneXZ::onUpdateBuffers_Wireframe(); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderWireFrame::renderUpdateBuffers(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderWireFrame::freeOpenGLResources(); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::traceRay(a0, a1); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +// mrpt::opengl::CMesh file:mrpt/opengl/CMesh.h line:39 +struct PyCallBack_mrpt_opengl_CMesh : public mrpt::opengl::CMesh { + using mrpt::opengl::CMesh::CMesh; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::serializeFrom(a0, a1); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::renderUpdateBuffers(); + } + void onUpdateBuffers_Wireframe() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Wireframe"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::onUpdateBuffers_Wireframe(); + } + void onUpdateBuffers_TexturedTriangles() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_TexturedTriangles"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::onUpdateBuffers_TexturedTriangles(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::freeOpenGLResources(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CMesh::traceRay(a0, a1); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderTexturedTriangles::initializeTextures(); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } +}; + +void bind_mrpt_opengl_CGridPlaneXZ(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::opengl::CGridPlaneXZ file:mrpt/opengl/CGridPlaneXZ.h line:23 + pybind11::class_, PyCallBack_mrpt_opengl_CGridPlaneXZ, mrpt::opengl::CRenderizableShaderWireFrame> cl(M("mrpt::opengl"), "CGridPlaneXZ", "A grid of lines over the XZ plane.\n\n ![mrpt::opengl::CGridPlaneXZ](preview_CGridPlaneXZ.png)\n\n \n opengl::Scene\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CGridPlaneXZ(); }, [](){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(); } ), "doc"); + cl.def( pybind11::init( [](float const & a0){ return new mrpt::opengl::CGridPlaneXZ(a0); }, [](float const & a0){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0); } ), "doc"); + cl.def( pybind11::init( [](float const & a0, float const & a1){ return new mrpt::opengl::CGridPlaneXZ(a0, a1); }, [](float const & a0, float const & a1){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0, a1); } ), "doc"); + cl.def( pybind11::init( [](float const & a0, float const & a1, float const & a2){ return new mrpt::opengl::CGridPlaneXZ(a0, a1, a2); }, [](float const & a0, float const & a1, float const & a2){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0, a1, a2); } ), "doc"); + cl.def( pybind11::init( [](float const & a0, float const & a1, float const & a2, float const & a3){ return new mrpt::opengl::CGridPlaneXZ(a0, a1, a2, a3); }, [](float const & a0, float const & a1, float const & a2, float const & a3){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0, a1, a2, a3); } ), "doc"); + cl.def( pybind11::init( [](float const & a0, float const & a1, float const & a2, float const & a3, float const & a4){ return new mrpt::opengl::CGridPlaneXZ(a0, a1, a2, a3, a4); }, [](float const & a0, float const & a1, float const & a2, float const & a3, float const & a4){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0, a1, a2, a3, a4); } ), "doc"); + cl.def( pybind11::init( [](float const & a0, float const & a1, float const & a2, float const & a3, float const & a4, float const & a5){ return new mrpt::opengl::CGridPlaneXZ(a0, a1, a2, a3, a4, a5); }, [](float const & a0, float const & a1, float const & a2, float const & a3, float const & a4, float const & a5){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0, a1, a2, a3, a4, a5); } ), "doc"); + cl.def( pybind11::init( [](float const & a0, float const & a1, float const & a2, float const & a3, float const & a4, float const & a5, float const & a6){ return new mrpt::opengl::CGridPlaneXZ(a0, a1, a2, a3, a4, a5, a6); }, [](float const & a0, float const & a1, float const & a2, float const & a3, float const & a4, float const & a5, float const & a6){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(a0, a1, a2, a3, a4, a5, a6); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("xMin"), pybind11::arg("xMax"), pybind11::arg("zMin"), pybind11::arg("zMax"), pybind11::arg("y"), pybind11::arg("frequency"), pybind11::arg("lineWidth"), pybind11::arg("antiAliasing") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CGridPlaneXZ const &o){ return new PyCallBack_mrpt_opengl_CGridPlaneXZ(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CGridPlaneXZ const &o){ return new mrpt::opengl::CGridPlaneXZ(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CGridPlaneXZ::getClassName, "C++: mrpt::opengl::CGridPlaneXZ::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CGridPlaneXZ::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CGridPlaneXZ::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CGridPlaneXZ::*)() const) &mrpt::opengl::CGridPlaneXZ::GetRuntimeClass, "C++: mrpt::opengl::CGridPlaneXZ::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CGridPlaneXZ::*)() const) &mrpt::opengl::CGridPlaneXZ::clone, "C++: mrpt::opengl::CGridPlaneXZ::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CGridPlaneXZ::CreateObject, "C++: mrpt::opengl::CGridPlaneXZ::CreateObject() --> class std::shared_ptr"); + cl.def("setPlaneLimits", (void (mrpt::opengl::CGridPlaneXZ::*)(float, float, float, float)) &mrpt::opengl::CGridPlaneXZ::setPlaneLimits, "C++: mrpt::opengl::CGridPlaneXZ::setPlaneLimits(float, float, float, float) --> void", pybind11::arg("xmin"), pybind11::arg("xmax"), pybind11::arg("zmin"), pybind11::arg("zmax")); + cl.def("getPlaneLimits", (void (mrpt::opengl::CGridPlaneXZ::*)(float &, float &, float &, float &) const) &mrpt::opengl::CGridPlaneXZ::getPlaneLimits, "C++: mrpt::opengl::CGridPlaneXZ::getPlaneLimits(float &, float &, float &, float &) const --> void", pybind11::arg("xmin"), pybind11::arg("xmax"), pybind11::arg("zmin"), pybind11::arg("zmax")); + cl.def("setPlaneYcoord", (void (mrpt::opengl::CGridPlaneXZ::*)(float)) &mrpt::opengl::CGridPlaneXZ::setPlaneYcoord, "C++: mrpt::opengl::CGridPlaneXZ::setPlaneYcoord(float) --> void", pybind11::arg("y")); + cl.def("getPlaneYcoord", (float (mrpt::opengl::CGridPlaneXZ::*)() const) &mrpt::opengl::CGridPlaneXZ::getPlaneYcoord, "C++: mrpt::opengl::CGridPlaneXZ::getPlaneYcoord() const --> float"); + cl.def("setGridFrequency", (void (mrpt::opengl::CGridPlaneXZ::*)(float)) &mrpt::opengl::CGridPlaneXZ::setGridFrequency, "C++: mrpt::opengl::CGridPlaneXZ::setGridFrequency(float) --> void", pybind11::arg("freq")); + cl.def("getGridFrequency", (float (mrpt::opengl::CGridPlaneXZ::*)() const) &mrpt::opengl::CGridPlaneXZ::getGridFrequency, "C++: mrpt::opengl::CGridPlaneXZ::getGridFrequency() const --> float"); + cl.def("onUpdateBuffers_Wireframe", (void (mrpt::opengl::CGridPlaneXZ::*)()) &mrpt::opengl::CGridPlaneXZ::onUpdateBuffers_Wireframe, "C++: mrpt::opengl::CGridPlaneXZ::onUpdateBuffers_Wireframe() --> void"); + cl.def("assign", (class mrpt::opengl::CGridPlaneXZ & (mrpt::opengl::CGridPlaneXZ::*)(const class mrpt::opengl::CGridPlaneXZ &)) &mrpt::opengl::CGridPlaneXZ::operator=, "C++: mrpt::opengl::CGridPlaneXZ::operator=(const class mrpt::opengl::CGridPlaneXZ &) --> class mrpt::opengl::CGridPlaneXZ &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::opengl::CMesh file:mrpt/opengl/CMesh.h line:39 + pybind11::class_, PyCallBack_mrpt_opengl_CMesh, mrpt::opengl::CRenderizableShaderTexturedTriangles, mrpt::opengl::CRenderizableShaderWireFrame> cl(M("mrpt::opengl"), "CMesh", "A planar (XY) grid where each cell has an associated height and, optionally,\n a texture map. A typical usage example would be an elevation map or a 3D\n model of a terrain.\n\n The height of each cell/pixel is provided via an elevation `Z` matrix,\n where the z coordinate of the grid cell (x,y) is given by `Z(x,y)`\n (not `Z(y,x)`!!), that is:\n - Z column count = number of cells in direction \"+y\"\n - Z row count = number of cells in direction \"+x\"\n\n Since MRPT 2.7.0, the texture can be wrapped over the mesh using\n setMeshTextureExtension().\n\n ![mrpt::opengl::CMesh](preview_CMesh.png)\n\n \n opengl::Scene\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CMesh(); }, [](){ return new PyCallBack_mrpt_opengl_CMesh(); } ), "doc"); + cl.def( pybind11::init( [](bool const & a0){ return new mrpt::opengl::CMesh(a0); }, [](bool const & a0){ return new PyCallBack_mrpt_opengl_CMesh(a0); } ), "doc"); + cl.def( pybind11::init( [](bool const & a0, float const & a1){ return new mrpt::opengl::CMesh(a0, a1); }, [](bool const & a0, float const & a1){ return new PyCallBack_mrpt_opengl_CMesh(a0, a1); } ), "doc"); + cl.def( pybind11::init( [](bool const & a0, float const & a1, float const & a2){ return new mrpt::opengl::CMesh(a0, a1, a2); }, [](bool const & a0, float const & a1, float const & a2){ return new PyCallBack_mrpt_opengl_CMesh(a0, a1, a2); } ), "doc"); + cl.def( pybind11::init( [](bool const & a0, float const & a1, float const & a2, float const & a3){ return new mrpt::opengl::CMesh(a0, a1, a2, a3); }, [](bool const & a0, float const & a1, float const & a2, float const & a3){ return new PyCallBack_mrpt_opengl_CMesh(a0, a1, a2, a3); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("enableTransparency"), pybind11::arg("xMin"), pybind11::arg("xMax"), pybind11::arg("yMin"), pybind11::arg("yMax") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CMesh const &o){ return new PyCallBack_mrpt_opengl_CMesh(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CMesh const &o){ return new mrpt::opengl::CMesh(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CMesh::getClassName, "C++: mrpt::opengl::CMesh::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CMesh::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CMesh::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::GetRuntimeClass, "C++: mrpt::opengl::CMesh::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::clone, "C++: mrpt::opengl::CMesh::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CMesh::CreateObject, "C++: mrpt::opengl::CMesh::CreateObject() --> class std::shared_ptr"); + cl.def("renderUpdateBuffers", (void (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::renderUpdateBuffers, "C++: mrpt::opengl::CMesh::renderUpdateBuffers() const --> void"); + cl.def("requiredShaders", (int (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::requiredShaders, "C++: mrpt::opengl::CMesh::requiredShaders() const --> int"); + cl.def("onUpdateBuffers_Wireframe", (void (mrpt::opengl::CMesh::*)()) &mrpt::opengl::CMesh::onUpdateBuffers_Wireframe, "C++: mrpt::opengl::CMesh::onUpdateBuffers_Wireframe() --> void"); + cl.def("onUpdateBuffers_TexturedTriangles", (void (mrpt::opengl::CMesh::*)()) &mrpt::opengl::CMesh::onUpdateBuffers_TexturedTriangles, "C++: mrpt::opengl::CMesh::onUpdateBuffers_TexturedTriangles() --> void"); + cl.def("freeOpenGLResources", (void (mrpt::opengl::CMesh::*)()) &mrpt::opengl::CMesh::freeOpenGLResources, "C++: mrpt::opengl::CMesh::freeOpenGLResources() --> void"); + cl.def("getGridLimits", (void (mrpt::opengl::CMesh::*)(float &, float &, float &, float &) const) &mrpt::opengl::CMesh::getGridLimits, "C++: mrpt::opengl::CMesh::getGridLimits(float &, float &, float &, float &) const --> void", pybind11::arg("xMin"), pybind11::arg("xMax"), pybind11::arg("yMin"), pybind11::arg("yMax")); + cl.def("setMeshTextureExtension", (void (mrpt::opengl::CMesh::*)(float, float)) &mrpt::opengl::CMesh::setMeshTextureExtension, "Sets the texture physical size (in \"meters) using to wrap it over the\n mesh extension.\n The default (0) means texture size is equal to whole grid extension. \n\nC++: mrpt::opengl::CMesh::setMeshTextureExtension(float, float) --> void", pybind11::arg("textureSize_x"), pybind11::arg("textureSize_y")); + cl.def("getMeshTextureExtension", (void (mrpt::opengl::CMesh::*)(float &, float &) const) &mrpt::opengl::CMesh::getMeshTextureExtension, "C++: mrpt::opengl::CMesh::getMeshTextureExtension(float &, float &) const --> void", pybind11::arg("textureSize_x"), pybind11::arg("textureSize_y")); + cl.def("enableTransparency", (void (mrpt::opengl::CMesh::*)(bool)) &mrpt::opengl::CMesh::enableTransparency, "C++: mrpt::opengl::CMesh::enableTransparency(bool) --> void", pybind11::arg("v")); + cl.def("enableWireFrame", (void (mrpt::opengl::CMesh::*)(bool)) &mrpt::opengl::CMesh::enableWireFrame, "C++: mrpt::opengl::CMesh::enableWireFrame(bool) --> void", pybind11::arg("v")); + cl.def("enableColorFromZ", [](mrpt::opengl::CMesh &o, bool const & a0) -> void { return o.enableColorFromZ(a0); }, "", pybind11::arg("v")); + cl.def("enableColorFromZ", (void (mrpt::opengl::CMesh::*)(bool, enum mrpt::img::TColormap)) &mrpt::opengl::CMesh::enableColorFromZ, "C++: mrpt::opengl::CMesh::enableColorFromZ(bool, enum mrpt::img::TColormap) --> void", pybind11::arg("v"), pybind11::arg("colorMap")); + cl.def("getxMin", (float (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::getxMin, "C++: mrpt::opengl::CMesh::getxMin() const --> float"); + cl.def("getxMax", (float (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::getxMax, "C++: mrpt::opengl::CMesh::getxMax() const --> float"); + cl.def("getyMin", (float (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::getyMin, "C++: mrpt::opengl::CMesh::getyMin() const --> float"); + cl.def("getyMax", (float (mrpt::opengl::CMesh::*)() const) &mrpt::opengl::CMesh::getyMax, "C++: mrpt::opengl::CMesh::getyMax() const --> float"); + cl.def("setxMin", (void (mrpt::opengl::CMesh::*)(const float)) &mrpt::opengl::CMesh::setxMin, "C++: mrpt::opengl::CMesh::setxMin(const float) --> void", pybind11::arg("nxm")); + cl.def("setxMax", (void (mrpt::opengl::CMesh::*)(const float)) &mrpt::opengl::CMesh::setxMax, "C++: mrpt::opengl::CMesh::setxMax(const float) --> void", pybind11::arg("nxm")); + cl.def("setyMin", (void (mrpt::opengl::CMesh::*)(const float)) &mrpt::opengl::CMesh::setyMin, "C++: mrpt::opengl::CMesh::setyMin(const float) --> void", pybind11::arg("nym")); + cl.def("setyMax", (void (mrpt::opengl::CMesh::*)(const float)) &mrpt::opengl::CMesh::setyMax, "C++: mrpt::opengl::CMesh::setyMax(const float) --> void", pybind11::arg("nym")); + cl.def("getXBounds", (void (mrpt::opengl::CMesh::*)(float &, float &) const) &mrpt::opengl::CMesh::getXBounds, "C++: mrpt::opengl::CMesh::getXBounds(float &, float &) const --> void", pybind11::arg("min"), pybind11::arg("max")); + cl.def("getYBounds", (void (mrpt::opengl::CMesh::*)(float &, float &) const) &mrpt::opengl::CMesh::getYBounds, "C++: mrpt::opengl::CMesh::getYBounds(float &, float &) const --> void", pybind11::arg("min"), pybind11::arg("max")); + cl.def("setXBounds", (void (mrpt::opengl::CMesh::*)(const float, const float)) &mrpt::opengl::CMesh::setXBounds, "C++: mrpt::opengl::CMesh::setXBounds(const float, const float) --> void", pybind11::arg("min"), pybind11::arg("max")); + cl.def("setYBounds", (void (mrpt::opengl::CMesh::*)(const float, const float)) &mrpt::opengl::CMesh::setYBounds, "C++: mrpt::opengl::CMesh::setYBounds(const float, const float) --> void", pybind11::arg("min"), pybind11::arg("max")); + cl.def("assignImage", (void (mrpt::opengl::CMesh::*)(const class mrpt::img::CImage &)) &mrpt::opengl::CMesh::assignImage, "Assigns a texture image.\n\nC++: mrpt::opengl::CMesh::assignImage(const class mrpt::img::CImage &) --> void", pybind11::arg("img")); + cl.def("adjustGridToImageAR", (void (mrpt::opengl::CMesh::*)()) &mrpt::opengl::CMesh::adjustGridToImageAR, "Adjust grid limits according to the image aspect ratio, maintaining the\n X limits and resizing in the Y direction.\n\nC++: mrpt::opengl::CMesh::adjustGridToImageAR() --> void"); + cl.def("traceRay", (bool (mrpt::opengl::CMesh::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CMesh::traceRay, "Trace ray\n\nC++: mrpt::opengl::CMesh::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist")); + cl.def("assign", (class mrpt::opengl::CMesh & (mrpt::opengl::CMesh::*)(const class mrpt::opengl::CMesh &)) &mrpt::opengl::CMesh::operator=, "C++: mrpt::opengl::CMesh::operator=(const class mrpt::opengl::CMesh &) --> class mrpt::opengl::CMesh &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::opengl::CMesh::TTriangleVertexIndices file:mrpt/opengl/CMesh.h line:44 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TTriangleVertexIndices", ""); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CMesh::TTriangleVertexIndices(); } ) ); + } + + } +} diff --git a/python/generated-sources-pybind/mrpt/opengl/CRenderizable.cpp b/python/generated-sources-pybind/mrpt/opengl/CRenderizable.cpp new file mode 100644 index 0000000000..5f530ec15e --- /dev/null +++ b/python/generated-sources-pybind/mrpt/opengl/CRenderizable.cpp @@ -0,0 +1,36 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_opengl_CRenderizable(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::opengl::enqueueForRendering(const int &, const struct mrpt::opengl::TRenderMatrices &, int &, const bool, const bool, struct mrpt::opengl::RenderQueueStats *) file:mrpt/opengl/CRenderizable.h line:535 + M("mrpt::opengl").def("enqueueForRendering", [](const int & a0, const struct mrpt::opengl::TRenderMatrices & a1, int & a2, const bool & a3, const bool & a4) -> void { return mrpt::opengl::enqueueForRendering(a0, a1, a2, a3, a4); }, "", pybind11::arg("objs"), pybind11::arg("state"), pybind11::arg("rq"), pybind11::arg("skipCullChecks"), pybind11::arg("is1stShadowMapPass")); + M("mrpt::opengl").def("enqueueForRendering", (void (*)(const int &, const struct mrpt::opengl::TRenderMatrices &, int &, const bool, const bool, struct mrpt::opengl::RenderQueueStats *)) &mrpt::opengl::enqueueForRendering, "Processes, recursively, all objects in the list, classifying them by shader\n programs into a list suitable to be used within processPendingRendering()\n\n For each object in the list:\n - checks visibility of each object\n - update the MODELVIEW matrix according to its coordinates\n - call its ::render()\n - shows its name (if enabled).\n\n \n Will be true if the render engine already checked that\n the object lies within the viewport area, so it is pointless to waste\n more time checking.\n\n \n Used by CSetOfObjects and Viewport\n\n \n processPendingRendering\n\nC++: mrpt::opengl::enqueueForRendering(const int &, const struct mrpt::opengl::TRenderMatrices &, int &, const bool, const bool, struct mrpt::opengl::RenderQueueStats *) --> void", pybind11::arg("objs"), pybind11::arg("state"), pybind11::arg("rq"), pybind11::arg("skipCullChecks"), pybind11::arg("is1stShadowMapPass"), pybind11::arg("stats")); + +} diff --git a/python/generated-sources-pybind/mrpt/opengl/CSetOfLines.cpp b/python/generated-sources-pybind/mrpt/opengl/CSetOfLines.cpp new file mode 100644 index 0000000000..83c92dbdef --- /dev/null +++ b/python/generated-sources-pybind/mrpt/opengl/CSetOfLines.cpp @@ -0,0 +1,564 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::opengl::CSetOfLines file:mrpt/opengl/CSetOfLines.h line:25 +struct PyCallBack_mrpt_opengl_CSetOfLines : public mrpt::opengl::CSetOfLines { + using mrpt::opengl::CSetOfLines::CSetOfLines; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::serializeFrom(a0, a1); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::renderUpdateBuffers(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::freeOpenGLResources(); + } + void onUpdateBuffers_Wireframe() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Wireframe"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::onUpdateBuffers_Wireframe(); + } + void onUpdateBuffers_Points() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Points"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfLines::onUpdateBuffers_Points(); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::traceRay(a0, a1); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +// mrpt::opengl::CSetOfObjects file:mrpt/opengl/CSetOfObjects.h line:26 +struct PyCallBack_mrpt_opengl_CSetOfObjects : public mrpt::opengl::CSetOfObjects { + using mrpt::opengl::CSetOfObjects::CSetOfObjects; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::serializeFrom(a0, a1); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::renderUpdateBuffers(); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::isCompositeObject(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::freeOpenGLResources(); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::initializeTextures(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::traceRay(a0, a1); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::setColor_u8(a0); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSetOfObjects::setColorA_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } +}; + +void bind_mrpt_opengl_CSetOfLines(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::opengl::CSetOfLines file:mrpt/opengl/CSetOfLines.h line:25 + pybind11::class_, PyCallBack_mrpt_opengl_CSetOfLines, mrpt::opengl::CRenderizableShaderWireFrame, mrpt::opengl::CRenderizableShaderPoints> cl(M("mrpt::opengl"), "CSetOfLines", "A set of independent lines (or segments), one line with its own start and\n end positions (X,Y,Z). Optionally, the vertices can be also shown as dots.\n\n ![mrpt::opengl::CSetOfLines](preview_CSetOfLines.png)\n\n \n opengl::Scene\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CSetOfLines(); }, [](){ return new PyCallBack_mrpt_opengl_CSetOfLines(); } ) ); + cl.def( pybind11::init( [](const int & a0){ return new mrpt::opengl::CSetOfLines(a0); }, [](const int & a0){ return new PyCallBack_mrpt_opengl_CSetOfLines(a0); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("sgms"), pybind11::arg("antiAliasing") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CSetOfLines const &o){ return new PyCallBack_mrpt_opengl_CSetOfLines(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CSetOfLines const &o){ return new mrpt::opengl::CSetOfLines(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CSetOfLines::getClassName, "C++: mrpt::opengl::CSetOfLines::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CSetOfLines::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CSetOfLines::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::GetRuntimeClass, "C++: mrpt::opengl::CSetOfLines::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::clone, "C++: mrpt::opengl::CSetOfLines::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CSetOfLines::CreateObject, "C++: mrpt::opengl::CSetOfLines::CreateObject() --> class std::shared_ptr"); + cl.def("renderUpdateBuffers", (void (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::renderUpdateBuffers, "C++: mrpt::opengl::CSetOfLines::renderUpdateBuffers() const --> void"); + cl.def("freeOpenGLResources", (void (mrpt::opengl::CSetOfLines::*)()) &mrpt::opengl::CSetOfLines::freeOpenGLResources, "C++: mrpt::opengl::CSetOfLines::freeOpenGLResources() --> void"); + cl.def("requiredShaders", (int (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::requiredShaders, "C++: mrpt::opengl::CSetOfLines::requiredShaders() const --> int"); + cl.def("onUpdateBuffers_Wireframe", (void (mrpt::opengl::CSetOfLines::*)()) &mrpt::opengl::CSetOfLines::onUpdateBuffers_Wireframe, "C++: mrpt::opengl::CSetOfLines::onUpdateBuffers_Wireframe() --> void"); + cl.def("onUpdateBuffers_Points", (void (mrpt::opengl::CSetOfLines::*)()) &mrpt::opengl::CSetOfLines::onUpdateBuffers_Points, "C++: mrpt::opengl::CSetOfLines::onUpdateBuffers_Points() --> void"); + cl.def("clear", (void (mrpt::opengl::CSetOfLines::*)()) &mrpt::opengl::CSetOfLines::clear, "Clear the list of segments \n\nC++: mrpt::opengl::CSetOfLines::clear() --> void"); + cl.def("getVerticesPointSize", (float (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::getVerticesPointSize, "C++: mrpt::opengl::CSetOfLines::getVerticesPointSize() const --> float"); + cl.def("setVerticesPointSize", (void (mrpt::opengl::CSetOfLines::*)(const float)) &mrpt::opengl::CSetOfLines::setVerticesPointSize, "Enable showing vertices as dots if size_points>0 \n\nC++: mrpt::opengl::CSetOfLines::setVerticesPointSize(const float) --> void", pybind11::arg("size_points")); + cl.def("appendLine", (void (mrpt::opengl::CSetOfLines::*)(const struct mrpt::math::TSegment3D &)) &mrpt::opengl::CSetOfLines::appendLine, "Appends a line to the set.\n\nC++: mrpt::opengl::CSetOfLines::appendLine(const struct mrpt::math::TSegment3D &) --> void", pybind11::arg("sgm")); + cl.def("appendLine", (void (mrpt::opengl::CSetOfLines::*)(double, double, double, double, double, double)) &mrpt::opengl::CSetOfLines::appendLine, "Appends a line to the set, given the coordinates of its bounds.\n\nC++: mrpt::opengl::CSetOfLines::appendLine(double, double, double, double, double, double) --> void", pybind11::arg("x0"), pybind11::arg("y0"), pybind11::arg("z0"), pybind11::arg("x1"), pybind11::arg("y1"), pybind11::arg("z1")); + cl.def("appendLineStrip", (void (mrpt::opengl::CSetOfLines::*)(float, float, float)) &mrpt::opengl::CSetOfLines::appendLineStrip, "Appends a line whose starting point is the end point of the last line\n (similar to OpenGL's GL_LINE_STRIP)\n \n\n std::exception If there is no previous segment \n\nC++: mrpt::opengl::CSetOfLines::appendLineStrip(float, float, float) --> void", pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z")); + cl.def("resize", (void (mrpt::opengl::CSetOfLines::*)(size_t)) &mrpt::opengl::CSetOfLines::resize, "Resizes the set.\n \n\n reserve\n\nC++: mrpt::opengl::CSetOfLines::resize(size_t) --> void", pybind11::arg("nLines")); + cl.def("reserve", (void (mrpt::opengl::CSetOfLines::*)(size_t)) &mrpt::opengl::CSetOfLines::reserve, "Reserves an amount of lines to the set. This method should be used when\n some known amount of lines is going to be inserted, so that only a memory\n allocation is needed.\n \n\n resize\n\nC++: mrpt::opengl::CSetOfLines::reserve(size_t) --> void", pybind11::arg("r")); + cl.def("getLineCount", (size_t (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::getLineCount, "Returns the total count of lines in this set. \n\nC++: mrpt::opengl::CSetOfLines::getLineCount() const --> size_t"); + cl.def("size", (size_t (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::size, "Returns the total count of lines in this set. \n\nC++: mrpt::opengl::CSetOfLines::size() const --> size_t"); + cl.def("empty", (bool (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::empty, "Returns true if there are no line segments. \n\nC++: mrpt::opengl::CSetOfLines::empty() const --> bool"); + cl.def("setLineByIndex", (void (mrpt::opengl::CSetOfLines::*)(size_t, const struct mrpt::math::TSegment3D &)) &mrpt::opengl::CSetOfLines::setLineByIndex, "Sets a specific line in the set, given its index.\n \n\n appendLine\n\nC++: mrpt::opengl::CSetOfLines::setLineByIndex(size_t, const struct mrpt::math::TSegment3D &) --> void", pybind11::arg("index"), pybind11::arg("segm")); + cl.def("setLineByIndex", (void (mrpt::opengl::CSetOfLines::*)(size_t, double, double, double, double, double, double)) &mrpt::opengl::CSetOfLines::setLineByIndex, "Sets a specific line in the set, given its index.\n \n\n appendLine\n\nC++: mrpt::opengl::CSetOfLines::setLineByIndex(size_t, double, double, double, double, double, double) --> void", pybind11::arg("index"), pybind11::arg("x0"), pybind11::arg("y0"), pybind11::arg("z0"), pybind11::arg("x1"), pybind11::arg("y1"), pybind11::arg("z1")); + cl.def("getLineByIndex", (void (mrpt::opengl::CSetOfLines::*)(size_t, double &, double &, double &, double &, double &, double &) const) &mrpt::opengl::CSetOfLines::getLineByIndex, "Gets a specific line in the set, given its index.\n \n\n getLineByIndex\n\nC++: mrpt::opengl::CSetOfLines::getLineByIndex(size_t, double &, double &, double &, double &, double &, double &) const --> void", pybind11::arg("index"), pybind11::arg("x0"), pybind11::arg("y0"), pybind11::arg("z0"), pybind11::arg("x1"), pybind11::arg("y1"), pybind11::arg("z1")); + cl.def("begin", (int (mrpt::opengl::CSetOfLines::*)()) &mrpt::opengl::CSetOfLines::begin, "C++: mrpt::opengl::CSetOfLines::begin() --> int"); + cl.def("end", (int (mrpt::opengl::CSetOfLines::*)()) &mrpt::opengl::CSetOfLines::end, "C++: mrpt::opengl::CSetOfLines::end() --> int"); + cl.def("rbegin", (int (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::rbegin, "Beginning const reverse iterator (actually, accesses the end of the\n set).\n \n\n rend,begin,end\n\nC++: mrpt::opengl::CSetOfLines::rbegin() const --> int"); + cl.def("rend", (int (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::rend, "Ending const reverse iterator (actually, refers to the starting point of\n the set).\n \n\n rbegin,end,begin\n\nC++: mrpt::opengl::CSetOfLines::rend() const --> int"); + cl.def("enableAntiAliasing", [](mrpt::opengl::CSetOfLines &o) -> void { return o.enableAntiAliasing(); }, ""); + cl.def("enableAntiAliasing", (void (mrpt::opengl::CSetOfLines::*)(bool)) &mrpt::opengl::CSetOfLines::enableAntiAliasing, "C++: mrpt::opengl::CSetOfLines::enableAntiAliasing(bool) --> void", pybind11::arg("enable")); + cl.def("isAntiAliasingEnabled", (bool (mrpt::opengl::CSetOfLines::*)() const) &mrpt::opengl::CSetOfLines::isAntiAliasingEnabled, "C++: mrpt::opengl::CSetOfLines::isAntiAliasingEnabled() const --> bool"); + cl.def("assign", (class mrpt::opengl::CSetOfLines & (mrpt::opengl::CSetOfLines::*)(const class mrpt::opengl::CSetOfLines &)) &mrpt::opengl::CSetOfLines::operator=, "C++: mrpt::opengl::CSetOfLines::operator=(const class mrpt::opengl::CSetOfLines &) --> class mrpt::opengl::CSetOfLines &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::opengl::CSetOfObjects file:mrpt/opengl/CSetOfObjects.h line:26 + pybind11::class_, PyCallBack_mrpt_opengl_CSetOfObjects, mrpt::opengl::CRenderizable> cl(M("mrpt::opengl"), "CSetOfObjects", "A set of object, which are referenced to the coordinates framework\n established in this object.\n It can be established a hierarchy of \"CSetOfObjects\", where the coordinates\n framework of each one will be referenced to the parent's one.\n The list of child objects is accessed directly as in the class Scene\n\n \n opengl::Scene\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CSetOfObjects(); }, [](){ return new PyCallBack_mrpt_opengl_CSetOfObjects(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CSetOfObjects const &o){ return new PyCallBack_mrpt_opengl_CSetOfObjects(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CSetOfObjects const &o){ return new mrpt::opengl::CSetOfObjects(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CSetOfObjects::getClassName, "C++: mrpt::opengl::CSetOfObjects::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CSetOfObjects::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CSetOfObjects::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::GetRuntimeClass, "C++: mrpt::opengl::CSetOfObjects::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::clone, "C++: mrpt::opengl::CSetOfObjects::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CSetOfObjects::CreateObject, "C++: mrpt::opengl::CSetOfObjects::CreateObject() --> class std::shared_ptr"); + cl.def("begin", (int (mrpt::opengl::CSetOfObjects::*)()) &mrpt::opengl::CSetOfObjects::begin, "C++: mrpt::opengl::CSetOfObjects::begin() --> int"); + cl.def("end", (int (mrpt::opengl::CSetOfObjects::*)()) &mrpt::opengl::CSetOfObjects::end, "C++: mrpt::opengl::CSetOfObjects::end() --> int"); + cl.def("insert", (void (mrpt::opengl::CSetOfObjects::*)(const class std::shared_ptr &)) &mrpt::opengl::CSetOfObjects::insert, "Insert a new object to the list.\n\nC++: mrpt::opengl::CSetOfObjects::insert(const class std::shared_ptr &) --> void", pybind11::arg("newObject")); + cl.def("requiredShaders", (int (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::requiredShaders, "C++: mrpt::opengl::CSetOfObjects::requiredShaders() const --> int"); + cl.def("renderUpdateBuffers", (void (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::renderUpdateBuffers, "C++: mrpt::opengl::CSetOfObjects::renderUpdateBuffers() const --> void"); + cl.def("enqueueForRenderRecursive", (void (mrpt::opengl::CSetOfObjects::*)(const struct mrpt::opengl::TRenderMatrices &, int &, bool, bool) const) &mrpt::opengl::CSetOfObjects::enqueueForRenderRecursive, "C++: mrpt::opengl::CSetOfObjects::enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices &, int &, bool, bool) const --> void", pybind11::arg("state"), pybind11::arg("rq"), pybind11::arg("wholeInView"), pybind11::arg("is1stShadowMapPass")); + cl.def("isCompositeObject", (bool (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::isCompositeObject, "C++: mrpt::opengl::CSetOfObjects::isCompositeObject() const --> bool"); + cl.def("freeOpenGLResources", (void (mrpt::opengl::CSetOfObjects::*)()) &mrpt::opengl::CSetOfObjects::freeOpenGLResources, "C++: mrpt::opengl::CSetOfObjects::freeOpenGLResources() --> void"); + cl.def("initializeTextures", (void (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::initializeTextures, "C++: mrpt::opengl::CSetOfObjects::initializeTextures() const --> void"); + cl.def("clear", (void (mrpt::opengl::CSetOfObjects::*)()) &mrpt::opengl::CSetOfObjects::clear, "Clear the list of objects in the scene, deleting objects' memory.\n\nC++: mrpt::opengl::CSetOfObjects::clear() --> void"); + cl.def("size", (size_t (mrpt::opengl::CSetOfObjects::*)()) &mrpt::opengl::CSetOfObjects::size, "Returns number of objects. \n\nC++: mrpt::opengl::CSetOfObjects::size() --> size_t"); + cl.def("empty", (bool (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::empty, "Returns true if there are no objects. \n\nC++: mrpt::opengl::CSetOfObjects::empty() const --> bool"); + cl.def("getByName", (class std::shared_ptr (mrpt::opengl::CSetOfObjects::*)(const std::string &)) &mrpt::opengl::CSetOfObjects::getByName, "Returns the first object with a given name, or a nullptr pointer if not\n found.\n\nC++: mrpt::opengl::CSetOfObjects::getByName(const std::string &) --> class std::shared_ptr", pybind11::arg("str")); + cl.def("removeObject", (void (mrpt::opengl::CSetOfObjects::*)(const class std::shared_ptr &)) &mrpt::opengl::CSetOfObjects::removeObject, "Removes the given object from the scene (it also deletes the object to\n free its memory).\n\nC++: mrpt::opengl::CSetOfObjects::removeObject(const class std::shared_ptr &) --> void", pybind11::arg("obj")); + cl.def("dumpListOfObjects", (void (mrpt::opengl::CSetOfObjects::*)(int &) const) &mrpt::opengl::CSetOfObjects::dumpListOfObjects, "Retrieves a list of all objects in text form\n \n\n Prefer asYAML() (since MRPT 2.1.3) \n\nC++: mrpt::opengl::CSetOfObjects::dumpListOfObjects(int &) const --> void", pybind11::arg("lst")); + cl.def("asYAML", (class mrpt::containers::yaml (mrpt::opengl::CSetOfObjects::*)() const) &mrpt::opengl::CSetOfObjects::asYAML, "Prints all objects in human-readable YAML form.\n \n\n (New in MRPT 2.1.3) \n\nC++: mrpt::opengl::CSetOfObjects::asYAML() const --> class mrpt::containers::yaml"); + cl.def("traceRay", (bool (mrpt::opengl::CSetOfObjects::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CSetOfObjects::traceRay, "C++: mrpt::opengl::CSetOfObjects::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist")); + cl.def("setColor_u8", (class mrpt::opengl::CRenderizable & (mrpt::opengl::CSetOfObjects::*)(const struct mrpt::img::TColor &)) &mrpt::opengl::CSetOfObjects::setColor_u8, "C++: mrpt::opengl::CSetOfObjects::setColor_u8(const struct mrpt::img::TColor &) --> class mrpt::opengl::CRenderizable &", pybind11::return_value_policy::automatic, pybind11::arg("c")); + cl.def("setColorA_u8", (class mrpt::opengl::CRenderizable & (mrpt::opengl::CSetOfObjects::*)(const unsigned char)) &mrpt::opengl::CSetOfObjects::setColorA_u8, "C++: mrpt::opengl::CSetOfObjects::setColorA_u8(const unsigned char) --> class mrpt::opengl::CRenderizable &", pybind11::return_value_policy::automatic, pybind11::arg("a")); + cl.def("contains", (bool (mrpt::opengl::CSetOfObjects::*)(const class std::shared_ptr &) const) &mrpt::opengl::CSetOfObjects::contains, "C++: mrpt::opengl::CSetOfObjects::contains(const class std::shared_ptr &) const --> bool", pybind11::arg("obj")); + cl.def_static("posePDF2opengl", (class std::shared_ptr (*)(const class mrpt::poses::CPosePDF &)) &mrpt::opengl::CSetOfObjects::posePDF2opengl, "Returns a representation of a the PDF - this is just an auxiliary\n function, it's more natural to call\n mrpt::poses::CPosePDF::getAs3DObject \n\nC++: mrpt::opengl::CSetOfObjects::posePDF2opengl(const class mrpt::poses::CPosePDF &) --> class std::shared_ptr", pybind11::arg("o")); + cl.def_static("posePDF2opengl", (class std::shared_ptr (*)(const class mrpt::poses::CPointPDF &)) &mrpt::opengl::CSetOfObjects::posePDF2opengl, "Returns a representation of a the PDF - this is just an auxiliary\n function, it's more natural to call\n mrpt::poses::CPointPDF::getAs3DObject \n\nC++: mrpt::opengl::CSetOfObjects::posePDF2opengl(const class mrpt::poses::CPointPDF &) --> class std::shared_ptr", pybind11::arg("o")); + cl.def_static("posePDF2opengl", (class std::shared_ptr (*)(const class mrpt::poses::CPose3DPDF &)) &mrpt::opengl::CSetOfObjects::posePDF2opengl, "Returns a representation of a the PDF - this is just an auxiliary\n function, it's more natural to call\n mrpt::poses::CPose3DPDF::getAs3DObject \n\nC++: mrpt::opengl::CSetOfObjects::posePDF2opengl(const class mrpt::poses::CPose3DPDF &) --> class std::shared_ptr", pybind11::arg("o")); + cl.def_static("posePDF2opengl", (class std::shared_ptr (*)(const class mrpt::poses::CPose3DQuatPDF &)) &mrpt::opengl::CSetOfObjects::posePDF2opengl, "Returns a representation of a the PDF - this is just an auxiliary\n function, it's more natural to call\n mrpt::poses::CPose3DQuatPDF::getAs3DObject \n\nC++: mrpt::opengl::CSetOfObjects::posePDF2opengl(const class mrpt::poses::CPose3DQuatPDF &) --> class std::shared_ptr", pybind11::arg("o")); + cl.def("assign", (class mrpt::opengl::CSetOfObjects & (mrpt::opengl::CSetOfObjects::*)(const class mrpt::opengl::CSetOfObjects &)) &mrpt::opengl::CSetOfObjects::operator=, "C++: mrpt::opengl::CSetOfObjects::operator=(const class mrpt::opengl::CSetOfObjects &) --> class mrpt::opengl::CSetOfObjects &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/opengl/CSphere.cpp b/python/generated-sources-pybind/mrpt/opengl/CSphere.cpp new file mode 100644 index 0000000000..d82a7eb6b7 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/opengl/CSphere.cpp @@ -0,0 +1,610 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::opengl::CSphere file:mrpt/opengl/CSphere.h line:22 +struct PyCallBack_mrpt_opengl_CSphere : public mrpt::opengl::CSphere { + using mrpt::opengl::CSphere::CSphere; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSphere::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CSphere::clone(); + } +}; + +// mrpt::opengl::CCylinder file:mrpt/opengl/CCylinder.h line:23 +struct PyCallBack_mrpt_opengl_CCylinder : public mrpt::opengl::CCylinder { + using mrpt::opengl::CCylinder::CCylinder; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::serializeFrom(a0, a1); + } + void onUpdateBuffers_Triangles() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Triangles"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::onUpdateBuffers_Triangles(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CCylinder::traceRay(a0, a1); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderTriangles::renderUpdateBuffers(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderTriangles::freeOpenGLResources(); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +// mrpt::opengl::CEllipsoidInverseDepth2D file:mrpt/opengl/CEllipsoidInverseDepth2D.h line:37 +struct PyCallBack_mrpt_opengl_CEllipsoidInverseDepth2D : public mrpt::opengl::CEllipsoidInverseDepth2D { + using mrpt::opengl::CEllipsoidInverseDepth2D::CEllipsoidInverseDepth2D; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth2D::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth2D::clone(); + } +}; + +// mrpt::opengl::CEllipsoidInverseDepth3D file:mrpt/opengl/CEllipsoidInverseDepth3D.h line:39 +struct PyCallBack_mrpt_opengl_CEllipsoidInverseDepth3D : public mrpt::opengl::CEllipsoidInverseDepth3D { + using mrpt::opengl::CEllipsoidInverseDepth3D::CEllipsoidInverseDepth3D; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth3D::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth3D::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth3D::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth3D::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CEllipsoidInverseDepth3D::serializeFrom(a0, a1); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::toYAMLMap(a0); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + pybind11::pybind11_fail("Tried to call pure virtual function \"CRenderizable::renderUpdateBuffers\""); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::traceRay(a0, a1); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + pybind11::pybind11_fail("Tried to call pure virtual function \"CRenderizable::freeOpenGLResources\""); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +void bind_mrpt_opengl_CSphere(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::opengl::CSphere file:mrpt/opengl/CSphere.h line:22 + pybind11::class_, PyCallBack_mrpt_opengl_CSphere> cl(M("mrpt::opengl"), "CSphere", "A solid or wire-frame sphere.\n\n ![mrpt::opengl::CSphere](preview_CSphere.png)\n\n \n opengl::Scene\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CSphere(); }, [](){ return new PyCallBack_mrpt_opengl_CSphere(); } ), "doc"); + cl.def( pybind11::init( [](float const & a0){ return new mrpt::opengl::CSphere(a0); }, [](float const & a0){ return new PyCallBack_mrpt_opengl_CSphere(a0); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("radius"), pybind11::arg("nDivs") ); + + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CSphere::getClassName, "C++: mrpt::opengl::CSphere::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CSphere::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CSphere::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CSphere::*)() const) &mrpt::opengl::CSphere::GetRuntimeClass, "C++: mrpt::opengl::CSphere::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CSphere::*)() const) &mrpt::opengl::CSphere::clone, "C++: mrpt::opengl::CSphere::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (int (*)()) &mrpt::opengl::CSphere::CreateObject, "C++: mrpt::opengl::CSphere::CreateObject() --> int"); + cl.def("renderUpdateBuffers", (void (mrpt::opengl::CSphere::*)() const) &mrpt::opengl::CSphere::renderUpdateBuffers, "C++: mrpt::opengl::CSphere::renderUpdateBuffers() const --> void"); + cl.def("setRadius", (void (mrpt::opengl::CSphere::*)(float)) &mrpt::opengl::CSphere::setRadius, "C++: mrpt::opengl::CSphere::setRadius(float) --> void", pybind11::arg("r")); + cl.def("getRadius", (float (mrpt::opengl::CSphere::*)() const) &mrpt::opengl::CSphere::getRadius, "C++: mrpt::opengl::CSphere::getRadius() const --> float"); + cl.def("setNumberDivs", (void (mrpt::opengl::CSphere::*)(int)) &mrpt::opengl::CSphere::setNumberDivs, "C++: mrpt::opengl::CSphere::setNumberDivs(int) --> void", pybind11::arg("N")); + cl.def("traceRay", (bool (mrpt::opengl::CSphere::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CSphere::traceRay, "C++: mrpt::opengl::CSphere::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist")); + cl.def("assign", (class mrpt::opengl::CSphere & (mrpt::opengl::CSphere::*)(const class mrpt::opengl::CSphere &)) &mrpt::opengl::CSphere::operator=, "C++: mrpt::opengl::CSphere::operator=(const class mrpt::opengl::CSphere &) --> class mrpt::opengl::CSphere &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::opengl::CCylinder file:mrpt/opengl/CCylinder.h line:23 + pybind11::class_, PyCallBack_mrpt_opengl_CCylinder, mrpt::opengl::CRenderizableShaderTriangles> cl(M("mrpt::opengl"), "CCylinder", "A cylinder or cone whose base lies in the XY plane.\n\n ![mrpt::opengl::CCylinder](preview_CCylinder.png)\n\n \n opengl::Scene,opengl::CDisk\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CCylinder(); }, [](){ return new PyCallBack_mrpt_opengl_CCylinder(); } ) ); + cl.def( pybind11::init( [](const float & a0, const float & a1){ return new mrpt::opengl::CCylinder(a0, a1); }, [](const float & a0, const float & a1){ return new PyCallBack_mrpt_opengl_CCylinder(a0, a1); } ), "doc"); + cl.def( pybind11::init( [](const float & a0, const float & a1, const float & a2){ return new mrpt::opengl::CCylinder(a0, a1, a2); }, [](const float & a0, const float & a1, const float & a2){ return new PyCallBack_mrpt_opengl_CCylinder(a0, a1, a2); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("baseRadius"), pybind11::arg("topRadius"), pybind11::arg("height"), pybind11::arg("slices") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CCylinder const &o){ return new PyCallBack_mrpt_opengl_CCylinder(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CCylinder const &o){ return new mrpt::opengl::CCylinder(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CCylinder::getClassName, "C++: mrpt::opengl::CCylinder::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CCylinder::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CCylinder::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::GetRuntimeClass, "C++: mrpt::opengl::CCylinder::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::clone, "C++: mrpt::opengl::CCylinder::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CCylinder::CreateObject, "C++: mrpt::opengl::CCylinder::CreateObject() --> class std::shared_ptr"); + cl.def("onUpdateBuffers_Triangles", (void (mrpt::opengl::CCylinder::*)()) &mrpt::opengl::CCylinder::onUpdateBuffers_Triangles, "@{ \n\nC++: mrpt::opengl::CCylinder::onUpdateBuffers_Triangles() --> void"); + cl.def("traceRay", (bool (mrpt::opengl::CCylinder::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CCylinder::traceRay, "@} \n\nC++: mrpt::opengl::CCylinder::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist")); + cl.def("setHasBases", [](mrpt::opengl::CCylinder &o) -> void { return o.setHasBases(); }, ""); + cl.def("setHasBases", [](mrpt::opengl::CCylinder &o, bool const & a0) -> void { return o.setHasBases(a0); }, "", pybind11::arg("top")); + cl.def("setHasBases", (void (mrpt::opengl::CCylinder::*)(bool, bool)) &mrpt::opengl::CCylinder::setHasBases, "Configuration of the cylinder's bases display.\n\nC++: mrpt::opengl::CCylinder::setHasBases(bool, bool) --> void", pybind11::arg("top"), pybind11::arg("bottom")); + cl.def("hasTopBase", (bool (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::hasTopBase, "Check whether top base is displayed.\n \n\n hasBottomBase\n\nC++: mrpt::opengl::CCylinder::hasTopBase() const --> bool"); + cl.def("hasBottomBase", (bool (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::hasBottomBase, "Check whether bottom base is displayed.\n \n\n hasTopBase\n\nC++: mrpt::opengl::CCylinder::hasBottomBase() const --> bool"); + cl.def("setRadius", (void (mrpt::opengl::CCylinder::*)(float)) &mrpt::opengl::CCylinder::setRadius, "Sets both radii to a single value, thus configuring the object as a\n cylinder.\n \n\n setRadii\n\nC++: mrpt::opengl::CCylinder::setRadius(float) --> void", pybind11::arg("radius")); + cl.def("setRadii", (void (mrpt::opengl::CCylinder::*)(float, float)) &mrpt::opengl::CCylinder::setRadii, "Sets both radii independently.\n \n\n setRadius\n\nC++: mrpt::opengl::CCylinder::setRadii(float, float) --> void", pybind11::arg("bottom"), pybind11::arg("top")); + cl.def("setHeight", (void (mrpt::opengl::CCylinder::*)(float)) &mrpt::opengl::CCylinder::setHeight, "Chenges cylinder's height.\n\nC++: mrpt::opengl::CCylinder::setHeight(float) --> void", pybind11::arg("height")); + cl.def("getBottomRadius", (float (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::getBottomRadius, "Gets the bottom radius.\n\nC++: mrpt::opengl::CCylinder::getBottomRadius() const --> float"); + cl.def("getTopRadius", (float (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::getTopRadius, "Gets the top radius.\n\nC++: mrpt::opengl::CCylinder::getTopRadius() const --> float"); + cl.def("getHeight", (float (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::getHeight, "Gets the cylinder's height.\n\nC++: mrpt::opengl::CCylinder::getHeight() const --> float"); + cl.def("setSlicesCount", (void (mrpt::opengl::CCylinder::*)(uint32_t)) &mrpt::opengl::CCylinder::setSlicesCount, "Number of radial divisions \n\nC++: mrpt::opengl::CCylinder::setSlicesCount(uint32_t) --> void", pybind11::arg("slices")); + cl.def("getSlicesCount", (uint32_t (mrpt::opengl::CCylinder::*)() const) &mrpt::opengl::CCylinder::getSlicesCount, "Number of radial divisions \n\nC++: mrpt::opengl::CCylinder::getSlicesCount() const --> uint32_t"); + cl.def("assign", (class mrpt::opengl::CCylinder & (mrpt::opengl::CCylinder::*)(const class mrpt::opengl::CCylinder &)) &mrpt::opengl::CCylinder::operator=, "C++: mrpt::opengl::CCylinder::operator=(const class mrpt::opengl::CCylinder &) --> class mrpt::opengl::CCylinder &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::opengl::CEllipsoidInverseDepth2D file:mrpt/opengl/CEllipsoidInverseDepth2D.h line:37 + pybind11::class_, PyCallBack_mrpt_opengl_CEllipsoidInverseDepth2D> cl(M("mrpt::opengl"), "CEllipsoidInverseDepth2D", "An especial \"ellipsoid\" in 3D computed as the uncertainty iso-surfaces of a\n (inv_range,yaw) variable.\n The parameter space of this ellipsoid comprises these variables (in this\n order):\n - inv_range: The inverse distance from the sensor to the feature.\n - yaw: Angle for the rotation around +Z (\"azimuth\").\n\n This parameterization is a 2D version of that presented in the paper:\n - Civera, J. and Davison, A.J. and Montiel, J., \"Inverse depth\n parametrization for monocular SLAM\", T-RO, 2008.\n\n This class expects you to provide a mean vector of length 4 and a 4x4\n covariance matrix, set with \n\n Please read the documentation of\n CGeneralizedEllipsoidTemplate::setQuantiles() for learning\n the mathematical details about setting the desired confidence interval.\n\n ![mrpt::opengl::CEllipsoidInverseDepth2D](preview_CEllipsoidInverseDepth2D.png)\n\n \n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CEllipsoidInverseDepth2D(); }, [](){ return new PyCallBack_mrpt_opengl_CEllipsoidInverseDepth2D(); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CEllipsoidInverseDepth2D::getClassName, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CEllipsoidInverseDepth2D::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CEllipsoidInverseDepth2D::*)() const) &mrpt::opengl::CEllipsoidInverseDepth2D::GetRuntimeClass, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CEllipsoidInverseDepth2D::*)() const) &mrpt::opengl::CEllipsoidInverseDepth2D::clone, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (int (*)()) &mrpt::opengl::CEllipsoidInverseDepth2D::CreateObject, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::CreateObject() --> int"); + cl.def("setUnderflowMaxRange", (void (mrpt::opengl::CEllipsoidInverseDepth2D::*)(const double)) &mrpt::opengl::CEllipsoidInverseDepth2D::setUnderflowMaxRange, "The maximum range to be used as a correction when a point of the\n ellipsoid falls in the negative ranges (default: 1e6) \n\nC++: mrpt::opengl::CEllipsoidInverseDepth2D::setUnderflowMaxRange(const double) --> void", pybind11::arg("maxRange")); + cl.def("getUnderflowMaxRange", (double (mrpt::opengl::CEllipsoidInverseDepth2D::*)() const) &mrpt::opengl::CEllipsoidInverseDepth2D::getUnderflowMaxRange, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::getUnderflowMaxRange() const --> double"); + cl.def("assign", (class mrpt::opengl::CEllipsoidInverseDepth2D & (mrpt::opengl::CEllipsoidInverseDepth2D::*)(const class mrpt::opengl::CEllipsoidInverseDepth2D &)) &mrpt::opengl::CEllipsoidInverseDepth2D::operator=, "C++: mrpt::opengl::CEllipsoidInverseDepth2D::operator=(const class mrpt::opengl::CEllipsoidInverseDepth2D &) --> class mrpt::opengl::CEllipsoidInverseDepth2D &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::opengl::CEllipsoidInverseDepth3D file:mrpt/opengl/CEllipsoidInverseDepth3D.h line:39 + pybind11::class_, PyCallBack_mrpt_opengl_CEllipsoidInverseDepth3D, mrpt::opengl::CRenderizable> cl(M("mrpt::opengl"), "CEllipsoidInverseDepth3D", "An especial \"ellipsoid\" in 3D computed as the uncertainty iso-surfaces of a\n (inv_range,yaw,pitch) variable.\n The parameter space of this ellipsoid comprises these variables (in this\n order):\n - inv_range: The inverse distance from the sensor to the feature.\n - yaw: Angle for the rotation around +Z (\"azimuth\").\n - pitch: Angle for the rotation around +Y (\"elevation\"). Positive means\n pointing below the XY plane.\n\n This parameterization is based on the paper:\n - Civera, J. and Davison, A.J. and Montiel, J., \"Inverse depth\n parametrization for monocular SLAM\", T-RO, 2008.\n\n This class expects you to provide a mean vector of length 3 and a 3x3\n covariance matrix, set with \n\n Please read the documentation of\n CGeneralizedEllipsoidTemplate::setQuantiles() for learning\n the mathematical details about setting the desired confidence interval.\n\n ![mrpt::opengl::CEllipsoidInverseDepth3D](preview_CEllipsoidInverseDepth3D.png)\n\n \n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CEllipsoidInverseDepth3D(); }, [](){ return new PyCallBack_mrpt_opengl_CEllipsoidInverseDepth3D(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CEllipsoidInverseDepth3D const &o){ return new PyCallBack_mrpt_opengl_CEllipsoidInverseDepth3D(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CEllipsoidInverseDepth3D const &o){ return new mrpt::opengl::CEllipsoidInverseDepth3D(o); } ) ); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CEllipsoidInverseDepth3D::getClassName, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CEllipsoidInverseDepth3D::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CEllipsoidInverseDepth3D::*)() const) &mrpt::opengl::CEllipsoidInverseDepth3D::GetRuntimeClass, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CEllipsoidInverseDepth3D::*)() const) &mrpt::opengl::CEllipsoidInverseDepth3D::clone, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CEllipsoidInverseDepth3D::CreateObject, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::CreateObject() --> class std::shared_ptr"); + cl.def("setUnderflowMaxRange", (void (mrpt::opengl::CEllipsoidInverseDepth3D::*)(const float)) &mrpt::opengl::CEllipsoidInverseDepth3D::setUnderflowMaxRange, "The maximum range to be used as a correction when a point of the\n ellipsoid falls in the negative ranges (default: 1e6) \n\nC++: mrpt::opengl::CEllipsoidInverseDepth3D::setUnderflowMaxRange(const float) --> void", pybind11::arg("maxRange")); + cl.def("getUnderflowMaxRange", (float (mrpt::opengl::CEllipsoidInverseDepth3D::*)() const) &mrpt::opengl::CEllipsoidInverseDepth3D::getUnderflowMaxRange, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::getUnderflowMaxRange() const --> float"); + cl.def("assign", (class mrpt::opengl::CEllipsoidInverseDepth3D & (mrpt::opengl::CEllipsoidInverseDepth3D::*)(const class mrpt::opengl::CEllipsoidInverseDepth3D &)) &mrpt::opengl::CEllipsoidInverseDepth3D::operator=, "C++: mrpt::opengl::CEllipsoidInverseDepth3D::operator=(const class mrpt::opengl::CEllipsoidInverseDepth3D &) --> class mrpt::opengl::CEllipsoidInverseDepth3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/opengl/CText3D.cpp b/python/generated-sources-pybind/mrpt/opengl/CText3D.cpp new file mode 100644 index 0000000000..1f8d8e0c32 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/opengl/CText3D.cpp @@ -0,0 +1,299 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::opengl::CText3D file:mrpt/opengl/CText3D.h line:34 +struct PyCallBack_mrpt_opengl_CText3D : public mrpt::opengl::CText3D { + using mrpt::opengl::CText3D::CText3D; + + const struct mrpt::rtti::TRuntimeClassId * GetRuntimeClass() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "GetRuntimeClass"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::GetRuntimeClass(); + } + class mrpt::rtti::CObject * clone() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "clone"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::clone(); + } + uint8_t serializeGetVersion() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeGetVersion"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::serializeGetVersion(); + } + void serializeTo(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeTo"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::serializeTo(a0); + } + void serializeFrom(class mrpt::serialization::CArchive & a0, uint8_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "serializeFrom"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::serializeFrom(a0, a1); + } + void onUpdateBuffers_Text() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "onUpdateBuffers_Text"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::onUpdateBuffers_Text(); + } + void toYAMLMap(class mrpt::containers::yaml & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "toYAMLMap"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CText3D::toYAMLMap(a0); + } + void renderUpdateBuffers() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "renderUpdateBuffers"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderText::renderUpdateBuffers(); + } + void freeOpenGLResources() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "freeOpenGLResources"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizableShaderText::freeOpenGLResources(); + } + class mrpt::opengl::CRenderizable & setColorA_u8(const unsigned char a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColorA_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColorA_u8(a0); + } + class mrpt::opengl::CRenderizable & setColor_u8(const struct mrpt::img::TColor & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "setColor_u8"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::setColor_u8(a0); + } + bool cullElegible() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "cullElegible"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::cullElegible(); + } + void enqueueForRenderRecursive(const struct mrpt::opengl::TRenderMatrices & a0, int & a1, bool a2, bool a3) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "enqueueForRenderRecursive"); + if (overload) { + auto o = overload.operator()(a0, a1, a2, a3); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::enqueueForRenderRecursive(a0, a1, a2, a3); + } + bool isCompositeObject() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "isCompositeObject"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::isCompositeObject(); + } + bool traceRay(const class mrpt::poses::CPose3D & a0, double & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "traceRay"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::traceRay(a0, a1); + } + void initializeTextures() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "initializeTextures"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CRenderizable::initializeTextures(); + } +}; + +void bind_mrpt_opengl_CText3D(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::opengl::CText3D file:mrpt/opengl/CText3D.h line:34 + pybind11::class_, PyCallBack_mrpt_opengl_CText3D, mrpt::opengl::CRenderizableShaderText> cl(M("mrpt::opengl"), "CText3D", "A 3D text (rendered with OpenGL primitives), with selectable font face and\n drawing style.\n Use and to change the text displayed by this object\n (can be multi-lined).\n\n Text is drawn along the (+X,+Y) axes.\n\n Default size of characters is \"1.0 units\". Change it with the standard\n method as with any other 3D object.\n The color can be also changed with standard methods in the base class \n\n ![mrpt::opengl::CText3D](preview_CText3D.png)\n\n \n opengl::Scene, CText\n \n\n This class is based on code from libcvd (BSD,\n http://www.edwardrosten.com/cvd/ ) \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::opengl::CText3D(); }, [](){ return new PyCallBack_mrpt_opengl_CText3D(); } ), "doc"); + cl.def( pybind11::init( [](const std::string & a0){ return new mrpt::opengl::CText3D(a0); }, [](const std::string & a0){ return new PyCallBack_mrpt_opengl_CText3D(a0); } ), "doc"); + cl.def( pybind11::init( [](const std::string & a0, const std::string & a1){ return new mrpt::opengl::CText3D(a0, a1); }, [](const std::string & a0, const std::string & a1){ return new PyCallBack_mrpt_opengl_CText3D(a0, a1); } ), "doc"); + cl.def( pybind11::init( [](const std::string & a0, const std::string & a1, const float & a2){ return new mrpt::opengl::CText3D(a0, a1, a2); }, [](const std::string & a0, const std::string & a1, const float & a2){ return new PyCallBack_mrpt_opengl_CText3D(a0, a1, a2); } ), "doc"); + cl.def( pybind11::init( [](const std::string & a0, const std::string & a1, const float & a2, const enum mrpt::opengl::TOpenGLFontStyle & a3){ return new mrpt::opengl::CText3D(a0, a1, a2, a3); }, [](const std::string & a0, const std::string & a1, const float & a2, const enum mrpt::opengl::TOpenGLFontStyle & a3){ return new PyCallBack_mrpt_opengl_CText3D(a0, a1, a2, a3); } ), "doc"); + cl.def( pybind11::init( [](const std::string & a0, const std::string & a1, const float & a2, const enum mrpt::opengl::TOpenGLFontStyle & a3, const double & a4){ return new mrpt::opengl::CText3D(a0, a1, a2, a3, a4); }, [](const std::string & a0, const std::string & a1, const float & a2, const enum mrpt::opengl::TOpenGLFontStyle & a3, const double & a4){ return new PyCallBack_mrpt_opengl_CText3D(a0, a1, a2, a3, a4); } ), "doc"); + cl.def( pybind11::init(), pybind11::arg("str"), pybind11::arg("fontName"), pybind11::arg("scale"), pybind11::arg("text_style"), pybind11::arg("text_spacing"), pybind11::arg("text_kerning") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_opengl_CText3D const &o){ return new PyCallBack_mrpt_opengl_CText3D(o); } ) ); + cl.def( pybind11::init( [](mrpt::opengl::CText3D const &o){ return new mrpt::opengl::CText3D(o); } ) ); + cl.def_readwrite("m_fontName", &mrpt::opengl::CText3D::m_fontName); + cl.def_static("getClassName", (auto (*)()) &mrpt::opengl::CText3D::getClassName, "C++: mrpt::opengl::CText3D::getClassName() --> auto"); + cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::opengl::CText3D::GetRuntimeClassIdStatic, "C++: mrpt::opengl::CText3D::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); + cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::GetRuntimeClass, "C++: mrpt::opengl::CText3D::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::clone, "C++: mrpt::opengl::CText3D::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); + cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::CText3D::CreateObject, "C++: mrpt::opengl::CText3D::CreateObject() --> class std::shared_ptr"); + cl.def("setString", (void (mrpt::opengl::CText3D::*)(const std::string &)) &mrpt::opengl::CText3D::setString, "Sets the displayed string \n\nC++: mrpt::opengl::CText3D::setString(const std::string &) --> void", pybind11::arg("s")); + cl.def("getString", (const std::string & (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::getString, "Returns the currently text associated to this object \n\nC++: mrpt::opengl::CText3D::getString() const --> const std::string &", pybind11::return_value_policy::automatic); + cl.def("setFont", (void (mrpt::opengl::CText3D::*)(const std::string &)) &mrpt::opengl::CText3D::setFont, "Changes the font name, among accepted values: \"sans\", \"mono\", \"serif\" \n\nC++: mrpt::opengl::CText3D::setFont(const std::string &) --> void", pybind11::arg("font")); + cl.def("getFont", (const std::string & (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::getFont, "Returns the text font \n\nC++: mrpt::opengl::CText3D::getFont() const --> const std::string &", pybind11::return_value_policy::automatic); + cl.def("setTextStyle", (void (mrpt::opengl::CText3D::*)(const enum mrpt::opengl::TOpenGLFontStyle)) &mrpt::opengl::CText3D::setTextStyle, "Change drawing style: FILL, OUTLINE, NICE \n\nC++: mrpt::opengl::CText3D::setTextStyle(const enum mrpt::opengl::TOpenGLFontStyle) --> void", pybind11::arg("text_style")); + cl.def("getTextStyle", (enum mrpt::opengl::TOpenGLFontStyle (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::getTextStyle, "Gets the current drawing style \n\nC++: mrpt::opengl::CText3D::getTextStyle() const --> enum mrpt::opengl::TOpenGLFontStyle"); + cl.def("setTextSpacing", (void (mrpt::opengl::CText3D::*)(const double)) &mrpt::opengl::CText3D::setTextSpacing, "C++: mrpt::opengl::CText3D::setTextSpacing(const double) --> void", pybind11::arg("text_spacing")); + cl.def("setTextSpacing", (double (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::setTextSpacing, "C++: mrpt::opengl::CText3D::setTextSpacing() const --> double"); + cl.def("setTextKerning", (void (mrpt::opengl::CText3D::*)(const double)) &mrpt::opengl::CText3D::setTextKerning, "C++: mrpt::opengl::CText3D::setTextKerning(const double) --> void", pybind11::arg("text_kerning")); + cl.def("setTextKerning", (double (mrpt::opengl::CText3D::*)() const) &mrpt::opengl::CText3D::setTextKerning, "C++: mrpt::opengl::CText3D::setTextKerning() const --> double"); + cl.def("toYAMLMap", (void (mrpt::opengl::CText3D::*)(class mrpt::containers::yaml &) const) &mrpt::opengl::CText3D::toYAMLMap, "C++: mrpt::opengl::CText3D::toYAMLMap(class mrpt::containers::yaml &) const --> void", pybind11::arg("propertiesMap")); + cl.def("assign", (class mrpt::opengl::CText3D & (mrpt::opengl::CText3D::*)(const class mrpt::opengl::CText3D &)) &mrpt::opengl::CText3D::operator=, "C++: mrpt::opengl::CText3D::operator=(const class mrpt::opengl::CText3D &) --> class mrpt::opengl::CText3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/serialization/CArchive.cpp b/python/generated-sources-pybind/mrpt/serialization/CArchive.cpp index d62babc64c..c51511b565 100644 --- a/python/generated-sources-pybind/mrpt/serialization/CArchive.cpp +++ b/python/generated-sources-pybind/mrpt/serialization/CArchive.cpp @@ -1,9 +1,12 @@ #include #include +#include +#include #include #include #include #include +#include #include // __str__ #include #include @@ -86,6 +89,51 @@ struct PyCallBack_mrpt_serialization_CArchive : public mrpt::serialization::CArc } }; +// mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 +struct PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZInputStream_t : public mrpt::serialization::CArchiveStreamBase { + using mrpt::serialization::CArchiveStreamBase::CArchiveStreamBase; + + std::string getArchiveDescription() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "getArchiveDescription"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::getArchiveDescription(); + } + size_t write(const void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "write"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::write(a0, a1); + } + size_t read(void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "read"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::read(a0, a1); + } +}; + void bind_mrpt_serialization_CArchive(std::function< pybind11::module &(std::string const &namespace_) > &M) { { // mrpt::serialization::CExceptionEOF file:mrpt/serialization/CArchive.h line:38 @@ -99,6 +147,33 @@ void bind_mrpt_serialization_CArchive(std::function< pybind11::module &(std::str { // mrpt::serialization::CArchive file:mrpt/serialization/CArchive.h line:56 pybind11::class_, PyCallBack_mrpt_serialization_CArchive> cl(M("mrpt::serialization"), "CArchive", "Virtual base class for \"archives\": classes abstracting I/O streams.\n This class separates the implementation details of serialization (in\n CSerializable) and data storage (CArchive children: files, sockets,...).\n\n Two main sets of implementations are provided:\n - archiveFrom: for MRPT mrpt::io::CArchive objects, and\n - CArchiveStdIStream and CArchiveStdOStream: for std::istream and\n std::ostream, respectively.\n\n \n mrpt::io::CArchive, mrpt::serialization::CSerializable\n \n\n\n "); cl.def( pybind11::init( [](){ return new PyCallBack_mrpt_serialization_CArchive(); } ) ); + cl.def(pybind11::init()); + cl.def("ReadAs", (unsigned int (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadAs, "C++: mrpt::serialization::CArchive::ReadAs() --> unsigned int"); + cl.def("WriteAs", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const unsigned long &)) &mrpt::serialization::CArchive::WriteAs, "C++: mrpt::serialization::CArchive::WriteAs(const unsigned long &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("value")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "C++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("ReadBuffer", (size_t (mrpt::serialization::CArchive::*)(void *, size_t)) &mrpt::serialization::CArchive::ReadBuffer, "@{ \n\n Reads a block of bytes from the stream into Buffer\n \n\n std::exception On any error, or if ZERO bytes are read.\n \n\n The amound of bytes actually read.\n \n\n This method is endianness-dependent.\n \n\n ReadBufferImmediate ; Important, see: ReadBufferFixEndianness,\n\nC++: mrpt::serialization::CArchive::ReadBuffer(void *, size_t) --> size_t", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteBuffer", (void (mrpt::serialization::CArchive::*)(const void *, size_t)) &mrpt::serialization::CArchive::WriteBuffer, "Writes a block of bytes to the stream from Buffer.\n \n\n std::exception On any error\n \n\n Important, see: WriteBufferFixEndianness\n \n\n This method is endianness-dependent.\n\nC++: mrpt::serialization::CArchive::WriteBuffer(const void *, size_t) --> void", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::WriteObject, "Writes an object to the stream.\n\nC++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable *) --> void", pybind11::arg("o")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::WriteObject, "C++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable &) --> void", pybind11::arg("o")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const struct std::monostate &)) &mrpt::serialization::CArchive::operator<<, "Requires to serialize variants without a proper value. \n\nC++: mrpt::serialization::CArchive::operator<<(const struct std::monostate &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, its class determined at runtime, and\n returns a smart pointer to the object.\n \n\n std::exception On I/O error or undefined class.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchive::*)() const) &mrpt::serialization::CArchive::getArchiveDescription, "If redefined in derived classes, allows finding a human-friendly\n description of the underlying stream (e.g. filename) \n\nC++: mrpt::serialization::CArchive::getArchiveDescription() const --> std::string"); + cl.def("ReadObject", (void (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, where its class must be the same\n as the supplied object, where the loaded object will be stored in.\n \n\n std::exception On I/O error or different class found.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject(class mrpt::serialization::CSerializable *) --> void", pybind11::arg("existingObj")); + cl.def("sendMessage", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::sendMessage, "Send a message to the device.\n Note that only the low byte from the \"type\" field will be used.\n\n For frames of size < 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n For frames of size > 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n\n \n std::exception On communication errors\n\nC++: mrpt::serialization::CArchive::sendMessage(const class mrpt::serialization::CMessage &) --> void", pybind11::arg("msg")); + cl.def("receiveMessage", (bool (mrpt::serialization::CArchive::*)(class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::receiveMessage, "Tries to receive a message from the device.\n \n\n std::exception On communication errors\n \n\n True if successful, false if there is no new data from the\n device (but communications seem to work fine)\n \n\n The frame format is described in sendMessage()\n\nC++: mrpt::serialization::CArchive::receiveMessage(class mrpt::serialization::CMessage &) --> bool", pybind11::arg("msg")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator<<, "Write a CSerializable object to a stream in the binary MRPT format \n\nC++: mrpt::serialization::CArchive::operator<<(const class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class std::shared_ptr &)) &mrpt::serialization::CArchive::operator<<, "C++: mrpt::serialization::CArchive::operator<<(const class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator>>, "Reads a CSerializable object from the stream \n\nC++: mrpt::serialization::CArchive::operator>>(class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class std::shared_ptr &)) &mrpt::serialization::CArchive::operator>>, "C++: mrpt::serialization::CArchive::operator>>(class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("assign", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CArchive &)) &mrpt::serialization::CArchive::operator=, "C++: mrpt::serialization::CArchive::operator=(const class mrpt::serialization::CArchive &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 + pybind11::class_, std::shared_ptr>, PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZInputStream_t, mrpt::serialization::CArchive> cl(M("mrpt::serialization"), "CArchiveStreamBase_mrpt_io_CFileGZInputStream_t", ""); + cl.def( pybind11::init(), pybind11::arg("s") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZInputStream_t const &o){ return new PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZInputStream_t(o); } ) ); + cl.def( pybind11::init( [](mrpt::serialization::CArchiveStreamBase const &o){ return new mrpt::serialization::CArchiveStreamBase(o); } ) ); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchiveStreamBase::*)() const) &mrpt::serialization::CArchiveStreamBase::getArchiveDescription, "C++: mrpt::serialization::CArchiveStreamBase::getArchiveDescription() const --> std::string"); cl.def("ReadAs", (unsigned int (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadAs, "C++: mrpt::serialization::CArchive::ReadAs() --> unsigned int"); cl.def("WriteAs", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const unsigned long &)) &mrpt::serialization::CArchive::WriteAs, "C++: mrpt::serialization::CArchive::WriteAs(const unsigned long &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("value")); cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "C++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); diff --git a/python/generated-sources-pybind/mrpt/serialization/CArchive_1.cpp b/python/generated-sources-pybind/mrpt/serialization/CArchive_1.cpp index 9a88058ec0..da3cc4fec0 100644 --- a/python/generated-sources-pybind/mrpt/serialization/CArchive_1.cpp +++ b/python/generated-sources-pybind/mrpt/serialization/CArchive_1.cpp @@ -1,8 +1,13 @@ +#include #include -#include +#include +#include +#include +#include #include +#include #include // __str__ -#include +#include #include #include @@ -17,11 +22,148 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif +// mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 +struct PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZOutputStream_t : public mrpt::serialization::CArchiveStreamBase { + using mrpt::serialization::CArchiveStreamBase::CArchiveStreamBase; + + std::string getArchiveDescription() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "getArchiveDescription"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::getArchiveDescription(); + } + size_t write(const void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "write"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::write(a0, a1); + } + size_t read(void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "read"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::read(a0, a1); + } +}; + +// mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 +struct PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileInputStream_t : public mrpt::serialization::CArchiveStreamBase { + using mrpt::serialization::CArchiveStreamBase::CArchiveStreamBase; + + std::string getArchiveDescription() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "getArchiveDescription"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::getArchiveDescription(); + } + size_t write(const void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "write"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::write(a0, a1); + } + size_t read(void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "read"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::read(a0, a1); + } +}; + void bind_mrpt_serialization_CArchive_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::rtti::CLASS_ID_impl file:mrpt/serialization/CArchive.h line:655 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::rtti"), "CLASS_ID_impl_std_monostate_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::rtti::CLASS_ID_impl(); } ) ); - cl.def_static("get", (const struct mrpt::rtti::TRuntimeClassId * (*)()) &mrpt::rtti::CLASS_ID_impl::get, "C++: mrpt::rtti::CLASS_ID_impl::get() --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + { // mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 + pybind11::class_, std::shared_ptr>, PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZOutputStream_t, mrpt::serialization::CArchive> cl(M("mrpt::serialization"), "CArchiveStreamBase_mrpt_io_CFileGZOutputStream_t", ""); + cl.def( pybind11::init(), pybind11::arg("s") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZOutputStream_t const &o){ return new PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileGZOutputStream_t(o); } ) ); + cl.def( pybind11::init( [](mrpt::serialization::CArchiveStreamBase const &o){ return new mrpt::serialization::CArchiveStreamBase(o); } ) ); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchiveStreamBase::*)() const) &mrpt::serialization::CArchiveStreamBase::getArchiveDescription, "C++: mrpt::serialization::CArchiveStreamBase::getArchiveDescription() const --> std::string"); + cl.def("ReadAs", (unsigned int (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadAs, "C++: mrpt::serialization::CArchive::ReadAs() --> unsigned int"); + cl.def("WriteAs", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const unsigned long &)) &mrpt::serialization::CArchive::WriteAs, "C++: mrpt::serialization::CArchive::WriteAs(const unsigned long &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("value")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "C++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("ReadBuffer", (size_t (mrpt::serialization::CArchive::*)(void *, size_t)) &mrpt::serialization::CArchive::ReadBuffer, "@{ \n\n Reads a block of bytes from the stream into Buffer\n \n\n std::exception On any error, or if ZERO bytes are read.\n \n\n The amound of bytes actually read.\n \n\n This method is endianness-dependent.\n \n\n ReadBufferImmediate ; Important, see: ReadBufferFixEndianness,\n\nC++: mrpt::serialization::CArchive::ReadBuffer(void *, size_t) --> size_t", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteBuffer", (void (mrpt::serialization::CArchive::*)(const void *, size_t)) &mrpt::serialization::CArchive::WriteBuffer, "Writes a block of bytes to the stream from Buffer.\n \n\n std::exception On any error\n \n\n Important, see: WriteBufferFixEndianness\n \n\n This method is endianness-dependent.\n\nC++: mrpt::serialization::CArchive::WriteBuffer(const void *, size_t) --> void", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::WriteObject, "Writes an object to the stream.\n\nC++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable *) --> void", pybind11::arg("o")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::WriteObject, "C++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable &) --> void", pybind11::arg("o")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const struct std::monostate &)) &mrpt::serialization::CArchive::operator<<, "Requires to serialize variants without a proper value. \n\nC++: mrpt::serialization::CArchive::operator<<(const struct std::monostate &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, its class determined at runtime, and\n returns a smart pointer to the object.\n \n\n std::exception On I/O error or undefined class.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchive::*)() const) &mrpt::serialization::CArchive::getArchiveDescription, "If redefined in derived classes, allows finding a human-friendly\n description of the underlying stream (e.g. filename) \n\nC++: mrpt::serialization::CArchive::getArchiveDescription() const --> std::string"); + cl.def("ReadObject", (void (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, where its class must be the same\n as the supplied object, where the loaded object will be stored in.\n \n\n std::exception On I/O error or different class found.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject(class mrpt::serialization::CSerializable *) --> void", pybind11::arg("existingObj")); + cl.def("sendMessage", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::sendMessage, "Send a message to the device.\n Note that only the low byte from the \"type\" field will be used.\n\n For frames of size < 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n For frames of size > 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n\n \n std::exception On communication errors\n\nC++: mrpt::serialization::CArchive::sendMessage(const class mrpt::serialization::CMessage &) --> void", pybind11::arg("msg")); + cl.def("receiveMessage", (bool (mrpt::serialization::CArchive::*)(class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::receiveMessage, "Tries to receive a message from the device.\n \n\n std::exception On communication errors\n \n\n True if successful, false if there is no new data from the\n device (but communications seem to work fine)\n \n\n The frame format is described in sendMessage()\n\nC++: mrpt::serialization::CArchive::receiveMessage(class mrpt::serialization::CMessage &) --> bool", pybind11::arg("msg")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator<<, "Write a CSerializable object to a stream in the binary MRPT format \n\nC++: mrpt::serialization::CArchive::operator<<(const class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class std::shared_ptr &)) &mrpt::serialization::CArchive::operator<<, "C++: mrpt::serialization::CArchive::operator<<(const class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator>>, "Reads a CSerializable object from the stream \n\nC++: mrpt::serialization::CArchive::operator>>(class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class std::shared_ptr &)) &mrpt::serialization::CArchive::operator>>, "C++: mrpt::serialization::CArchive::operator>>(class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("assign", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CArchive &)) &mrpt::serialization::CArchive::operator=, "C++: mrpt::serialization::CArchive::operator=(const class mrpt::serialization::CArchive &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 + pybind11::class_, std::shared_ptr>, PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileInputStream_t, mrpt::serialization::CArchive> cl(M("mrpt::serialization"), "CArchiveStreamBase_mrpt_io_CFileInputStream_t", ""); + cl.def( pybind11::init(), pybind11::arg("s") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileInputStream_t const &o){ return new PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileInputStream_t(o); } ) ); + cl.def( pybind11::init( [](mrpt::serialization::CArchiveStreamBase const &o){ return new mrpt::serialization::CArchiveStreamBase(o); } ) ); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchiveStreamBase::*)() const) &mrpt::serialization::CArchiveStreamBase::getArchiveDescription, "C++: mrpt::serialization::CArchiveStreamBase::getArchiveDescription() const --> std::string"); + cl.def("ReadAs", (unsigned int (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadAs, "C++: mrpt::serialization::CArchive::ReadAs() --> unsigned int"); + cl.def("WriteAs", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const unsigned long &)) &mrpt::serialization::CArchive::WriteAs, "C++: mrpt::serialization::CArchive::WriteAs(const unsigned long &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("value")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "C++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("ReadBuffer", (size_t (mrpt::serialization::CArchive::*)(void *, size_t)) &mrpt::serialization::CArchive::ReadBuffer, "@{ \n\n Reads a block of bytes from the stream into Buffer\n \n\n std::exception On any error, or if ZERO bytes are read.\n \n\n The amound of bytes actually read.\n \n\n This method is endianness-dependent.\n \n\n ReadBufferImmediate ; Important, see: ReadBufferFixEndianness,\n\nC++: mrpt::serialization::CArchive::ReadBuffer(void *, size_t) --> size_t", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteBuffer", (void (mrpt::serialization::CArchive::*)(const void *, size_t)) &mrpt::serialization::CArchive::WriteBuffer, "Writes a block of bytes to the stream from Buffer.\n \n\n std::exception On any error\n \n\n Important, see: WriteBufferFixEndianness\n \n\n This method is endianness-dependent.\n\nC++: mrpt::serialization::CArchive::WriteBuffer(const void *, size_t) --> void", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::WriteObject, "Writes an object to the stream.\n\nC++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable *) --> void", pybind11::arg("o")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::WriteObject, "C++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable &) --> void", pybind11::arg("o")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const struct std::monostate &)) &mrpt::serialization::CArchive::operator<<, "Requires to serialize variants without a proper value. \n\nC++: mrpt::serialization::CArchive::operator<<(const struct std::monostate &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, its class determined at runtime, and\n returns a smart pointer to the object.\n \n\n std::exception On I/O error or undefined class.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchive::*)() const) &mrpt::serialization::CArchive::getArchiveDescription, "If redefined in derived classes, allows finding a human-friendly\n description of the underlying stream (e.g. filename) \n\nC++: mrpt::serialization::CArchive::getArchiveDescription() const --> std::string"); + cl.def("ReadObject", (void (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, where its class must be the same\n as the supplied object, where the loaded object will be stored in.\n \n\n std::exception On I/O error or different class found.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject(class mrpt::serialization::CSerializable *) --> void", pybind11::arg("existingObj")); + cl.def("sendMessage", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::sendMessage, "Send a message to the device.\n Note that only the low byte from the \"type\" field will be used.\n\n For frames of size < 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n For frames of size > 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n\n \n std::exception On communication errors\n\nC++: mrpt::serialization::CArchive::sendMessage(const class mrpt::serialization::CMessage &) --> void", pybind11::arg("msg")); + cl.def("receiveMessage", (bool (mrpt::serialization::CArchive::*)(class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::receiveMessage, "Tries to receive a message from the device.\n \n\n std::exception On communication errors\n \n\n True if successful, false if there is no new data from the\n device (but communications seem to work fine)\n \n\n The frame format is described in sendMessage()\n\nC++: mrpt::serialization::CArchive::receiveMessage(class mrpt::serialization::CMessage &) --> bool", pybind11::arg("msg")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator<<, "Write a CSerializable object to a stream in the binary MRPT format \n\nC++: mrpt::serialization::CArchive::operator<<(const class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class std::shared_ptr &)) &mrpt::serialization::CArchive::operator<<, "C++: mrpt::serialization::CArchive::operator<<(const class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator>>, "Reads a CSerializable object from the stream \n\nC++: mrpt::serialization::CArchive::operator>>(class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class std::shared_ptr &)) &mrpt::serialization::CArchive::operator>>, "C++: mrpt::serialization::CArchive::operator>>(class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("assign", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CArchive &)) &mrpt::serialization::CArchive::operator=, "C++: mrpt::serialization::CArchive::operator=(const class mrpt::serialization::CArchive &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/generated-sources-pybind/mrpt/serialization/CArchive_2.cpp b/python/generated-sources-pybind/mrpt/serialization/CArchive_2.cpp new file mode 100644 index 0000000000..cc713c2ad8 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/serialization/CArchive_2.cpp @@ -0,0 +1,96 @@ +#include +#include +#include +#include +#include +#include +#include // __str__ +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 +struct PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileOutputStream_t : public mrpt::serialization::CArchiveStreamBase { + using mrpt::serialization::CArchiveStreamBase::CArchiveStreamBase; + + std::string getArchiveDescription() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "getArchiveDescription"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::getArchiveDescription(); + } + size_t write(const void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "write"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::write(a0, a1); + } + size_t read(void * a0, size_t a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast *>(this), "read"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CArchiveStreamBase::read(a0, a1); + } +}; + +void bind_mrpt_serialization_CArchive_2(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::serialization::CArchiveStreamBase file:mrpt/serialization/CArchive.h line:604 + pybind11::class_, std::shared_ptr>, PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileOutputStream_t, mrpt::serialization::CArchive> cl(M("mrpt::serialization"), "CArchiveStreamBase_mrpt_io_CFileOutputStream_t", ""); + cl.def( pybind11::init(), pybind11::arg("s") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileOutputStream_t const &o){ return new PyCallBack_mrpt_serialization_CArchiveStreamBase_mrpt_io_CFileOutputStream_t(o); } ) ); + cl.def( pybind11::init( [](mrpt::serialization::CArchiveStreamBase const &o){ return new mrpt::serialization::CArchiveStreamBase(o); } ) ); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchiveStreamBase::*)() const) &mrpt::serialization::CArchiveStreamBase::getArchiveDescription, "C++: mrpt::serialization::CArchiveStreamBase::getArchiveDescription() const --> std::string"); + cl.def("ReadAs", (unsigned int (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadAs, "C++: mrpt::serialization::CArchive::ReadAs() --> unsigned int"); + cl.def("WriteAs", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const unsigned long &)) &mrpt::serialization::CArchive::WriteAs, "C++: mrpt::serialization::CArchive::WriteAs(const unsigned long &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("value")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "C++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("ReadBuffer", (size_t (mrpt::serialization::CArchive::*)(void *, size_t)) &mrpt::serialization::CArchive::ReadBuffer, "@{ \n\n Reads a block of bytes from the stream into Buffer\n \n\n std::exception On any error, or if ZERO bytes are read.\n \n\n The amound of bytes actually read.\n \n\n This method is endianness-dependent.\n \n\n ReadBufferImmediate ; Important, see: ReadBufferFixEndianness,\n\nC++: mrpt::serialization::CArchive::ReadBuffer(void *, size_t) --> size_t", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteBuffer", (void (mrpt::serialization::CArchive::*)(const void *, size_t)) &mrpt::serialization::CArchive::WriteBuffer, "Writes a block of bytes to the stream from Buffer.\n \n\n std::exception On any error\n \n\n Important, see: WriteBufferFixEndianness\n \n\n This method is endianness-dependent.\n\nC++: mrpt::serialization::CArchive::WriteBuffer(const void *, size_t) --> void", pybind11::arg("Buffer"), pybind11::arg("Count")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::WriteObject, "Writes an object to the stream.\n\nC++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable *) --> void", pybind11::arg("o")); + cl.def("WriteObject", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::WriteObject, "C++: mrpt::serialization::CArchive::WriteObject(const class mrpt::serialization::CSerializable &) --> void", pybind11::arg("o")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const struct std::monostate &)) &mrpt::serialization::CArchive::operator<<, "Requires to serialize variants without a proper value. \n\nC++: mrpt::serialization::CArchive::operator<<(const struct std::monostate &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + cl.def("ReadObject", (class std::shared_ptr (mrpt::serialization::CArchive::*)()) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, its class determined at runtime, and\n returns a smart pointer to the object.\n \n\n std::exception On I/O error or undefined class.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject() --> class std::shared_ptr"); + cl.def("getArchiveDescription", (std::string (mrpt::serialization::CArchive::*)() const) &mrpt::serialization::CArchive::getArchiveDescription, "If redefined in derived classes, allows finding a human-friendly\n description of the underlying stream (e.g. filename) \n\nC++: mrpt::serialization::CArchive::getArchiveDescription() const --> std::string"); + cl.def("ReadObject", (void (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable *)) &mrpt::serialization::CArchive::ReadObject, "Reads an object from stream, where its class must be the same\n as the supplied object, where the loaded object will be stored in.\n \n\n std::exception On I/O error or different class found.\n \n\n CExceptionEOF On an End-Of-File condition found\n at a correct place: an EOF that abruptly finishes in the middle of one\n object raises a plain std::exception instead.\n\nC++: mrpt::serialization::CArchive::ReadObject(class mrpt::serialization::CSerializable *) --> void", pybind11::arg("existingObj")); + cl.def("sendMessage", (void (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::sendMessage, "Send a message to the device.\n Note that only the low byte from the \"type\" field will be used.\n\n For frames of size < 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n For frames of size > 255 the frame format is an array of bytes in this\n order:\n \n\n\n\n\n\n\n\n\n\n\n \n std::exception On communication errors\n\nC++: mrpt::serialization::CArchive::sendMessage(const class mrpt::serialization::CMessage &) --> void", pybind11::arg("msg")); + cl.def("receiveMessage", (bool (mrpt::serialization::CArchive::*)(class mrpt::serialization::CMessage &)) &mrpt::serialization::CArchive::receiveMessage, "Tries to receive a message from the device.\n \n\n std::exception On communication errors\n \n\n True if successful, false if there is no new data from the\n device (but communications seem to work fine)\n \n\n The frame format is described in sendMessage()\n\nC++: mrpt::serialization::CArchive::receiveMessage(class mrpt::serialization::CMessage &) --> bool", pybind11::arg("msg")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator<<, "Write a CSerializable object to a stream in the binary MRPT format \n\nC++: mrpt::serialization::CArchive::operator<<(const class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__lshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class std::shared_ptr &)) &mrpt::serialization::CArchive::operator<<, "C++: mrpt::serialization::CArchive::operator<<(const class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class mrpt::serialization::CSerializable &)) &mrpt::serialization::CArchive::operator>>, "Reads a CSerializable object from the stream \n\nC++: mrpt::serialization::CArchive::operator>>(class mrpt::serialization::CSerializable &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("obj")); + cl.def("__rshift__", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(class std::shared_ptr &)) &mrpt::serialization::CArchive::operator>>, "C++: mrpt::serialization::CArchive::operator>>(class std::shared_ptr &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("pObj")); + cl.def("assign", (class mrpt::serialization::CArchive & (mrpt::serialization::CArchive::*)(const class mrpt::serialization::CArchive &)) &mrpt::serialization::CArchive::operator=, "C++: mrpt::serialization::CArchive::operator=(const class mrpt::serialization::CArchive &) --> class mrpt::serialization::CArchive &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/generated-sources-pybind/mrpt/serialization/CArchive_3.cpp b/python/generated-sources-pybind/mrpt/serialization/CArchive_3.cpp new file mode 100644 index 0000000000..711414efec --- /dev/null +++ b/python/generated-sources-pybind/mrpt/serialization/CArchive_3.cpp @@ -0,0 +1,27 @@ +#include +#include +#include +#include // __str__ +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_serialization_CArchive_3(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::rtti::CLASS_ID_impl file:mrpt/serialization/CArchive.h line:655 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::rtti"), "CLASS_ID_impl_std_monostate_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::rtti::CLASS_ID_impl(); } ) ); + cl.def_static("get", (const struct mrpt::rtti::TRuntimeClassId * (*)()) &mrpt::rtti::CLASS_ID_impl::get, "C++: mrpt::rtti::CLASS_ID_impl::get() --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); + } +} diff --git a/python/generated-sources-pybind/mrpt/system/crc.cpp b/python/generated-sources-pybind/mrpt/system/crc.cpp new file mode 100644 index 0000000000..53587afeb7 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/system/crc.cpp @@ -0,0 +1,150 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_system_crc(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::system::compute_CRC16(const int &, const unsigned short) file:mrpt/system/crc.h line:24 + M("mrpt::system").def("compute_CRC16", [](const int & a0) -> uint16_t { return mrpt::system::compute_CRC16(a0); }, "", pybind11::arg("data")); + M("mrpt::system").def("compute_CRC16", (uint16_t (*)(const int &, const unsigned short)) &mrpt::system::compute_CRC16, "Computes the CRC16 checksum of a block of data. \n\nC++: mrpt::system::compute_CRC16(const int &, const unsigned short) --> uint16_t", pybind11::arg("data"), pybind11::arg("gen_pol")); + + // mrpt::system::compute_CRC16(const unsigned char *, size_t, const unsigned short) file:mrpt/system/crc.h line:27 + M("mrpt::system").def("compute_CRC16", [](const unsigned char * a0, size_t const & a1) -> uint16_t { return mrpt::system::compute_CRC16(a0, a1); }, "", pybind11::arg("data"), pybind11::arg("len")); + M("mrpt::system").def("compute_CRC16", (uint16_t (*)(const unsigned char *, size_t, const unsigned short)) &mrpt::system::compute_CRC16, "C++: mrpt::system::compute_CRC16(const unsigned char *, size_t, const unsigned short) --> uint16_t", pybind11::arg("data"), pybind11::arg("len"), pybind11::arg("gen_pol")); + + // mrpt::system::compute_CRC32(const int &, const unsigned int) file:mrpt/system/crc.h line:30 + M("mrpt::system").def("compute_CRC32", [](const int & a0) -> uint32_t { return mrpt::system::compute_CRC32(a0); }, "", pybind11::arg("data")); + M("mrpt::system").def("compute_CRC32", (uint32_t (*)(const int &, const unsigned int)) &mrpt::system::compute_CRC32, "Computes the CRC32 checksum of a block of data. \n\nC++: mrpt::system::compute_CRC32(const int &, const unsigned int) --> uint32_t", pybind11::arg("data"), pybind11::arg("gen_pol")); + + // mrpt::system::compute_CRC32(const unsigned char *, size_t, const unsigned int) file:mrpt/system/crc.h line:33 + M("mrpt::system").def("compute_CRC32", [](const unsigned char * a0, size_t const & a1) -> uint32_t { return mrpt::system::compute_CRC32(a0, a1); }, "", pybind11::arg("data"), pybind11::arg("len")); + M("mrpt::system").def("compute_CRC32", (uint32_t (*)(const unsigned char *, size_t, const unsigned int)) &mrpt::system::compute_CRC32, "C++: mrpt::system::compute_CRC32(const unsigned char *, size_t, const unsigned int) --> uint32_t", pybind11::arg("data"), pybind11::arg("len"), pybind11::arg("gen_pol")); + + // mrpt::system::getTempFileName() file:mrpt/system/filesystem.h line:36 + M("mrpt::system").def("getTempFileName", (std::string (*)()) &mrpt::system::getTempFileName, "Returns the name of a proposed temporary file name \n\nC++: mrpt::system::getTempFileName() --> std::string"); + + // mrpt::system::getcwd() file:mrpt/system/filesystem.h line:39 + M("mrpt::system").def("getcwd", (std::string (*)()) &mrpt::system::getcwd, "Returns the current working directory \n\nC++: mrpt::system::getcwd() --> std::string"); + + // mrpt::system::getShareMRPTDir() file:mrpt/system/filesystem.h line:45 + M("mrpt::system").def("getShareMRPTDir", (std::string (*)()) &mrpt::system::getShareMRPTDir, "Attempts to find the directory `[PREFIX/]share/mrpt/` and returns its\n absolute path, or empty string if not found.\n Example return paths: Linux after installing = `/usr/share/mrpt/`;\n manually-built system = `[MRPT_SOURCE_DIR]/share/mrpt/`, etc. \n\nC++: mrpt::system::getShareMRPTDir() --> std::string"); + + // mrpt::system::createDirectory(const std::string &) file:mrpt/system/filesystem.h line:51 + M("mrpt::system").def("createDirectory", (bool (*)(const std::string &)) &mrpt::system::createDirectory, "Creates a directory\n \n\n Returns false on any error, true on directory created or already\n existed.\n\nC++: mrpt::system::createDirectory(const std::string &) --> bool", pybind11::arg("dirName")); + + // mrpt::system::deleteFile(const std::string &) file:mrpt/system/filesystem.h line:57 + M("mrpt::system").def("deleteFile", (bool (*)(const std::string &)) &mrpt::system::deleteFile, "Deletes a single file. For multiple files see deleteFiles\n \n\n Returns false on any error, true on everything OK.\n \n\n deleteFiles\n\nC++: mrpt::system::deleteFile(const std::string &) --> bool", pybind11::arg("fileName")); + + // mrpt::system::deleteFiles(const std::string &) file:mrpt/system/filesystem.h line:65 + M("mrpt::system").def("deleteFiles", (void (*)(const std::string &)) &mrpt::system::deleteFiles, "Delete one or more files, especified by the (optional) path and the file\n name (including '?' or '*') - Use forward slash ('/') for directories for\n compatibility between Windows and Linux, since they will be internally\n traslated into backward slashes ('\\') if MRPT is compiled under Windows.\n \n\n deleteFile\n\nC++: mrpt::system::deleteFiles(const std::string &) --> void", pybind11::arg("s")); + + // mrpt::system::renameFile(const std::string &, const std::string &, std::string *) file:mrpt/system/filesystem.h line:72 + M("mrpt::system").def("renameFile", [](const std::string & a0, const std::string & a1) -> bool { return mrpt::system::renameFile(a0, a1); }, "", pybind11::arg("oldFileName"), pybind11::arg("newFileName")); + M("mrpt::system").def("renameFile", (bool (*)(const std::string &, const std::string &, std::string *)) &mrpt::system::renameFile, "Renames a file - If the target path is different and the filesystem allows\n it, it will be moved to the new location.\n \n\n false on any error. In that case, if a pointer to a receiver string\n is passed in error_msg, a description of the error is saved there.\n\nC++: mrpt::system::renameFile(const std::string &, const std::string &, std::string *) --> bool", pybind11::arg("oldFileName"), pybind11::arg("newFileName"), pybind11::arg("error_msg")); + + // mrpt::system::deleteFilesInDirectory(const std::string &, bool) file:mrpt/system/filesystem.h line:81 + M("mrpt::system").def("deleteFilesInDirectory", [](const std::string & a0) -> bool { return mrpt::system::deleteFilesInDirectory(a0); }, "", pybind11::arg("s")); + M("mrpt::system").def("deleteFilesInDirectory", (bool (*)(const std::string &, bool)) &mrpt::system::deleteFilesInDirectory, "Delete all the files in a given directory (nothing done if directory does\n not exists, or path is a file).\n \n\n deleteFile\n \n\n true on success\n\nC++: mrpt::system::deleteFilesInDirectory(const std::string &, bool) --> bool", pybind11::arg("s"), pybind11::arg("deleteDirectoryAsWell")); + + // mrpt::system::extractFileName(const std::string &) file:mrpt/system/filesystem.h line:89 + M("mrpt::system").def("extractFileName", (std::string (*)(const std::string &)) &mrpt::system::extractFileName, "Extract just the name (without extension) of a filename from a complete path\n plus name plus extension.\n This function works for either \"/\" or \"\" directory separators.\n \n\n extractFileExtension,extractFileDirectory\n\nC++: mrpt::system::extractFileName(const std::string &) --> std::string", pybind11::arg("filePath")); + + // mrpt::system::extractFileExtension(const std::string &, bool) file:mrpt/system/filesystem.h line:98 + M("mrpt::system").def("extractFileExtension", [](const std::string & a0) -> std::string { return mrpt::system::extractFileExtension(a0); }, "", pybind11::arg("filePath")); + M("mrpt::system").def("extractFileExtension", (std::string (*)(const std::string &, bool)) &mrpt::system::extractFileExtension, "Extract the extension of a filename.\n For example, for \"dummy.cpp\", it will return \"cpp\".\n If \"ignore_gz\" is true, the second extension will be returned if the file\n name\n ends in \".gz\", for example, for \"foo.map.gz\", this will return \"map\".\n \n\n extractFileName,extractFileDirectory\n\nC++: mrpt::system::extractFileExtension(const std::string &, bool) --> std::string", pybind11::arg("filePath"), pybind11::arg("ignore_gz")); + + // mrpt::system::extractFileDirectory(const std::string &) file:mrpt/system/filesystem.h line:106 + M("mrpt::system").def("extractFileDirectory", (std::string (*)(const std::string &)) &mrpt::system::extractFileDirectory, "Extract the whole path (the directory) of a filename from a complete path\n plus name plus extension.\n This function works for either \"/\" or \"\" directory separators.\n \n\n extractFileName,extractFileExtension\n\nC++: mrpt::system::extractFileDirectory(const std::string &) --> std::string", pybind11::arg("filePath")); + + // mrpt::system::fileExists(const std::string &) file:mrpt/system/filesystem.h line:111 + M("mrpt::system").def("fileExists", (bool (*)(const std::string &)) &mrpt::system::fileExists, "Test if a given file (or directory) exists.\n \n\n directoryExists\n\nC++: mrpt::system::fileExists(const std::string &) --> bool", pybind11::arg("fileName")); + + // mrpt::system::directoryExists(const std::string &) file:mrpt/system/filesystem.h line:117 + M("mrpt::system").def("directoryExists", (bool (*)(const std::string &)) &mrpt::system::directoryExists, "Test if a given directory exists (it fails if the given path refers to an\n existing file).\n \n\n fileExists\n\nC++: mrpt::system::directoryExists(const std::string &) --> bool", pybind11::arg("fileName")); + + // mrpt::system::fileNameStripInvalidChars(const std::string &, const char) file:mrpt/system/filesystem.h line:123 + M("mrpt::system").def("fileNameStripInvalidChars", [](const std::string & a0) -> std::string { return mrpt::system::fileNameStripInvalidChars(a0); }, "", pybind11::arg("filename")); + M("mrpt::system").def("fileNameStripInvalidChars", (std::string (*)(const std::string &, const char)) &mrpt::system::fileNameStripInvalidChars, "Replace invalid filename chars by underscores ('_') or any other user-given\n char.\n Invalid chars are: '<','>',':','\"','/','\\','|','?','*'\n\nC++: mrpt::system::fileNameStripInvalidChars(const std::string &, const char) --> std::string", pybind11::arg("filename"), pybind11::arg("replacement_to_invalid_chars")); + + // mrpt::system::fileNameChangeExtension(const std::string &, const std::string &) file:mrpt/system/filesystem.h line:132 + M("mrpt::system").def("fileNameChangeExtension", (std::string (*)(const std::string &, const std::string &)) &mrpt::system::fileNameChangeExtension, "Replace the filename extension by another one.\n Example:\n \n\n\n\n \n\nC++: mrpt::system::fileNameChangeExtension(const std::string &, const std::string &) --> std::string", pybind11::arg("filename"), pybind11::arg("newExtension")); + + // mrpt::system::getFileSize(const std::string &) file:mrpt/system/filesystem.h line:137 + M("mrpt::system").def("getFileSize", (uint64_t (*)(const std::string &)) &mrpt::system::getFileSize, "Return the size of the given file, or size_t(-1) if some error is found\n accessing that file. \n\nC++: mrpt::system::getFileSize(const std::string &) --> uint64_t", pybind11::arg("fileName")); + + // mrpt::system::getFileModificationTime(const std::string &) file:mrpt/system/filesystem.h line:141 + M("mrpt::system").def("getFileModificationTime", (long (*)(const std::string &)) &mrpt::system::getFileModificationTime, "Return the time of the file last modification, or \"0\" if the file doesn't\n exist. \n\nC++: mrpt::system::getFileModificationTime(const std::string &) --> long", pybind11::arg("filename")); + + // mrpt::system::filePathSeparatorsToNative(const std::string &) file:mrpt/system/filesystem.h line:144 + M("mrpt::system").def("filePathSeparatorsToNative", (std::string (*)(const std::string &)) &mrpt::system::filePathSeparatorsToNative, "Windows: replace all '/'->'\\' , in Linux/MacOS: replace all '\\'->'/' \n\nC++: mrpt::system::filePathSeparatorsToNative(const std::string &) --> std::string", pybind11::arg("filePath")); + + // mrpt::system::copyFile(const std::string &, const std::string &, std::string *) file:mrpt/system/filesystem.h line:154 + M("mrpt::system").def("copyFile", [](const std::string & a0, const std::string & a1) -> bool { return mrpt::system::copyFile(a0, a1); }, "", pybind11::arg("sourceFile"), pybind11::arg("targetFile")); + M("mrpt::system").def("copyFile", (bool (*)(const std::string &, const std::string &, std::string *)) &mrpt::system::copyFile, "Copies file to If the target file exists, it\n will be overwritten.\n\n \n true on success, false on any error, whose description can be\n optionally get in outErrStr\n\n \n (In MRPT 2.5.0, the copyAttributes param was removed)\n\nC++: mrpt::system::copyFile(const std::string &, const std::string &, std::string *) --> bool", pybind11::arg("sourceFile"), pybind11::arg("targetFile"), pybind11::arg("outErrStr")); + + // mrpt::system::toAbsolutePath(const std::string &, bool) file:mrpt/system/filesystem.h line:172 + M("mrpt::system").def("toAbsolutePath", [](const std::string & a0) -> std::string { return mrpt::system::toAbsolutePath(a0); }, "", pybind11::arg("path")); + M("mrpt::system").def("toAbsolutePath", (std::string (*)(const std::string &, bool)) &mrpt::system::toAbsolutePath, "Portable version of std::filesystem::absolute() and canonical()\n\n If `canonical==true` relative paths, symlinks, etc. will be resolved too,\n but an exception will be thrown if the referenced file/path does not exist.\n If `canonical==true`, an absolute path will be always returned, even if does\n not actually exist.\n\n \n\n\n\n \n (New in MRPT 2.5.0)\n\nC++: mrpt::system::toAbsolutePath(const std::string &, bool) --> std::string", pybind11::arg("path"), pybind11::arg("resolveToCanonical")); + + // mrpt::system::pathJoin(const int &) file:mrpt/system/filesystem.h line:185 + M("mrpt::system").def("pathJoin", (std::string (*)(const int &)) &mrpt::system::pathJoin, "Portable version of std::filesystem::path::append(), with Python-like name.\n\n \n\n\n\n\n \n (New in MRPT 2.5.0)\n\nC++: mrpt::system::pathJoin(const int &) --> std::string", pybind11::arg("paths")); + + // mrpt::system::md5(const std::string &) file:mrpt/system/md5.h line:24 + M("mrpt::system").def("md5", (std::string (*)(const std::string &)) &mrpt::system::md5, "Header: `#include `.\n Library: \n \n\n\n @{ \n\n Computes the md5 of a block of data. \n\nC++: mrpt::system::md5(const std::string &) --> std::string", pybind11::arg("str")); + + // mrpt::system::md5(const int &) file:mrpt/system/md5.h line:26 + M("mrpt::system").def("md5", (std::string (*)(const int &)) &mrpt::system::md5, "Computes the md5 of a block of data. \n\nC++: mrpt::system::md5(const int &) --> std::string", pybind11::arg("str")); + + // mrpt::system::md5(const unsigned char *, size_t) file:mrpt/system/md5.h line:28 + M("mrpt::system").def("md5", (std::string (*)(const unsigned char *, size_t)) &mrpt::system::md5, "Computes the md5 of a block of data. \n\nC++: mrpt::system::md5(const unsigned char *, size_t) --> std::string", pybind11::arg("data"), pybind11::arg("len")); + + // mrpt::system::getMemoryUsage() file:mrpt/system/memory.h line:25 + M("mrpt::system").def("getMemoryUsage", (unsigned long (*)()) &mrpt::system::getMemoryUsage, "Returns the memory occupied by this process, in bytes \n\nC++: mrpt::system::getMemoryUsage() --> unsigned long"); + + // mrpt::system::progress(const double, const unsigned long, bool) file:mrpt/system/progress.h line:29 + M("mrpt::system").def("progress", [](const double & a0, const unsigned long & a1) -> std::string { return mrpt::system::progress(a0, a1); }, "", pybind11::arg("progressRatio0to1"), pybind11::arg("barLength")); + M("mrpt::system").def("progress", (std::string (*)(const double, const unsigned long, bool)) &mrpt::system::progress, "Build an text incremental progress bar with\n [UNICODE block elements](https://en.wikipedia.org/wiki/Block_Elements),\n for example:\n \n\n\n\n See example: \n system_progress_bar/test.cpp example-system-progress-bar\n\n \n\n \n (New in MRPT 2.3.0)\n\nC++: mrpt::system::progress(const double, const unsigned long, bool) --> std::string", pybind11::arg("progressRatio0to1"), pybind11::arg("barLength"), pybind11::arg("encloseInSquareBrackets")); + + // mrpt::system::TProcessPriority file:mrpt/system/scheduler.h line:22 + pybind11::enum_(M("mrpt::system"), "TProcessPriority", pybind11::arithmetic(), "The type for cross-platform process (application) priorities.\n \n\n changeCurrentProcessPriority") + .value("ppIdle", mrpt::system::ppIdle) + .value("ppNormal", mrpt::system::ppNormal) + .value("ppHigh", mrpt::system::ppHigh) + .value("ppVeryHigh", mrpt::system::ppVeryHigh) + .export_values(); + +; + + // mrpt::system::TThreadPriority file:mrpt/system/scheduler.h line:33 + pybind11::enum_(M("mrpt::system"), "TThreadPriority", pybind11::arithmetic(), "The type for cross-platform thread priorities.\n \n\n changeThreadPriority") + .value("tpLowests", mrpt::system::tpLowests) + .value("tpLower", mrpt::system::tpLower) + .value("tpLow", mrpt::system::tpLow) + .value("tpNormal", mrpt::system::tpNormal) + .value("tpHigh", mrpt::system::tpHigh) + .value("tpHigher", mrpt::system::tpHigher) + .value("tpHighest", mrpt::system::tpHighest) + .export_values(); + +; + +} diff --git a/python/generated-sources-pybind/mrpt/system/scheduler.cpp b/python/generated-sources-pybind/mrpt/system/scheduler.cpp new file mode 100644 index 0000000000..03022705b5 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/system/scheduler.cpp @@ -0,0 +1,34 @@ +#include +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +void bind_mrpt_system_scheduler(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::system::changeCurrentThreadPriority(enum mrpt::system::TThreadPriority) file:mrpt/system/scheduler.h line:54 + M("mrpt::system").def("changeCurrentThreadPriority", (void (*)(enum mrpt::system::TThreadPriority)) &mrpt::system::changeCurrentThreadPriority, "Change the priority of the current thread - for Windows, see also\n changeCurrentProcessPriority()\n - Windows: This is equivalent to\n [SetThreadPriority()](https://msdn.microsoft.com/en-us/library/windows/desktop/ms686277(v=vs.85).aspx)\n (read the docs there)\n - Linux (pthreads): May require `root` permissions! This sets the Round Robin\n scheduler with the given priority level. Read\n [sched_setscheduler](http://linux.die.net/man/2/sched_setscheduler). \n\n\n createThread, changeCurrentProcessPriority, changeCurrentThreadPriority\n\nC++: mrpt::system::changeCurrentThreadPriority(enum mrpt::system::TThreadPriority) --> void", pybind11::arg("priority")); + + // mrpt::system::changeCurrentProcessPriority(enum mrpt::system::TProcessPriority) file:mrpt/system/scheduler.h line:66 + M("mrpt::system").def("changeCurrentProcessPriority", (void (*)(enum mrpt::system::TProcessPriority)) &mrpt::system::changeCurrentProcessPriority, "Change the priority of the given process (it applies to all the threads,\n plus independent modifiers for each thread).\n - Windows: See\n [SetPriorityClass](https://msdn.microsoft.com/es-es/library/windows/desktop/ms686219(v=vs.85).aspx)\n - Linux (pthreads): Requires `root` permissions to increase process\n priority! Internally it calls [nice()](http://linux.die.net/man/3/nice), so it\n has no effect if\n () was called and a SCHED_RR is already active.\n \n\n createThread, changeThreadPriority\n\nC++: mrpt::system::changeCurrentProcessPriority(enum mrpt::system::TProcessPriority) --> void", pybind11::arg("priority")); + + // mrpt::system::thread_name(const std::string &) file:mrpt/system/thread_name.h line:26 + M("mrpt::system").def("thread_name", (void (*)(const std::string &)) &mrpt::system::thread_name, "Sets the name of the current thread; useful for debuggers.\n \n\n\n \n New in MRPT 2.0.4\n\nC++: mrpt::system::thread_name(const std::string &) --> void", pybind11::arg("name")); + + // mrpt::system::thread_name() file:mrpt/system/thread_name.h line:38 + M("mrpt::system").def("thread_name", (std::string (*)()) &mrpt::system::thread_name, "Gets the name of the current thread; useful for debuggers.\n \n\n\n \n New in MRPT 2.0.4\n\nC++: mrpt::system::thread_name() --> std::string"); + +} diff --git a/python/generated-sources-pybind/mrpt/vision/utils.cpp b/python/generated-sources-pybind/mrpt/vision/utils.cpp new file mode 100644 index 0000000000..90b14f3543 --- /dev/null +++ b/python/generated-sources-pybind/mrpt/vision/utils.cpp @@ -0,0 +1,301 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::vision::CFeatureExtraction::TOptions file:mrpt/vision/CFeatureExtraction.h line:85 +struct PyCallBack_mrpt_vision_CFeatureExtraction_TOptions : public mrpt::vision::CFeatureExtraction::TOptions { + using mrpt::vision::CFeatureExtraction::TOptions::TOptions; + + void loadFromConfigFile(const class mrpt::config::CConfigFileBase & a0, const std::string & a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "loadFromConfigFile"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return TOptions::loadFromConfigFile(a0, a1); + } + void saveToConfigFile(class mrpt::config::CConfigFileBase & a0, const std::string & a1) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "saveToConfigFile"); + if (overload) { + auto o = overload.operator()(a0, a1); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return CLoadableOptions::saveToConfigFile(a0, a1); + } +}; + +void bind_mrpt_vision_utils(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::vision::computeStereoRectificationMaps(const class mrpt::img::TCamera &, const class mrpt::img::TCamera &, const class mrpt::poses::CPose3D &, void *, void *, void *, void *) file:mrpt/vision/utils.h line:298 + M("mrpt::vision").def("computeStereoRectificationMaps", (void (*)(const class mrpt::img::TCamera &, const class mrpt::img::TCamera &, const class mrpt::poses::CPose3D &, void *, void *, void *, void *)) &mrpt::vision::computeStereoRectificationMaps, "Computes a pair of x-and-y maps for stereo rectification from a pair of\ncameras and the relative pose of the second one wrt the first one.\n \n\n cam2 [IN] The pair of involved cameras\n \n\n [IN] The change in pose of the second camera\nwrt the first one\n \n\n [OUT] The x-and-y maps corresponding to cam1\n(should be converted to *cv::Mat)\n \n\n [OUT] The x-and-y maps corresponding to cam2\n(should be converted to *cv::Mat)\n \n\n An easier to use class for stereo rectification\nmrpt::vision::CStereoRectifyMap\n\nC++: mrpt::vision::computeStereoRectificationMaps(const class mrpt::img::TCamera &, const class mrpt::img::TCamera &, const class mrpt::poses::CPose3D &, void *, void *, void *, void *) --> void", pybind11::arg("cam1"), pybind11::arg("cam2"), pybind11::arg("rightCameraPose"), pybind11::arg("outMap1x"), pybind11::arg("outMap1y"), pybind11::arg("outMap2x"), pybind11::arg("outMap2y")); + + { // mrpt::vision::CFeatureExtraction file:mrpt/vision/CFeatureExtraction.h line:71 + pybind11::class_> cl(M("mrpt::vision"), "CFeatureExtraction", "The central class from which images can be analyzed in search of different\nkinds of interest points and descriptors computed for them.\n To extract features from an image, create an instance of\nCFeatureExtraction,\n fill out its CFeatureExtraction::options field, including the algorithm to\nuse (see\n CFeatureExtraction::TOptions::featsType), and call\nCFeatureExtraction::detectFeatures.\n This will return a set of features of the class mrpt::vision::CFeature,\nwhich include\n details for each interest point as well as the desired descriptors and/or\npatches.\n\n By default, a 21x21 patch is extracted for each detected feature. If the\npatch is not needed,\n set patchSize to 0 in CFeatureExtraction::options\n\n The implemented detection algorithms are (see\nCFeatureExtraction::TOptions::featsType):\n - KLT (Kanade-Lucas-Tomasi): A detector (no descriptor vector).\n - Harris: A detector (no descriptor vector).\n - BCD (Binary Corner Detector): A detector (no descriptor vector) (Not\nimplemented yet).\n - SIFT: An implementation of the SIFT detector and descriptor. The\nimplemention may be selected with\nCFeatureExtraction::TOptions::SIFTOptions::implementation.\n - SURF: OpenCV's implementation of SURF detector and descriptor.\n - The FAST feature detector (OpenCV's implementation)\n\n Additionally, given a list of interest points onto an image, the following\n descriptors can be computed for each point by calling\nCFeatureExtraction::computeDescriptors :\n - SIFT descriptor (Lowe's descriptors).\n - SURF descriptor (OpenCV's implementation - Requires OpenCV 1.1.0 from\nSVN\nor later).\n - Intensity-domain spin images (SpinImage): Creates a vector descriptor\nwith the 2D histogram as a single row.\n - A circular patch in polar coordinates (Polar images): The matrix\ndescriptor is a 2D polar image centered at the interest point.\n - A log-polar image patch (Log-polar images): The matrix descriptor is\nthe\n2D log-polar image centered at the interest point.\n\n \n The descriptor \"Intensity-domain spin images\" is described in \"A\nsparse texture representation using affine-invariant regions\", S Lazebnik, C\nSchmid, J Ponce, 2003 IEEE Computer Society Conference on Computer Vision.\n \n\n mrpt::vision::CFeature\n \n\n\n "); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction(); } ) ); + + pybind11::enum_(cl, "TSIFTImplementation", pybind11::arithmetic(), "") + .value("OpenCV", mrpt::vision::CFeatureExtraction::OpenCV) + .export_values(); + + cl.def_readwrite("profiler", &mrpt::vision::CFeatureExtraction::profiler); + cl.def_readwrite("options", &mrpt::vision::CFeatureExtraction::options); + cl.def("detectFeatures", [](mrpt::vision::CFeatureExtraction &o, const class mrpt::img::CImage & a0, class mrpt::vision::CFeatureList & a1) -> void { return o.detectFeatures(a0, a1); }, "", pybind11::arg("img"), pybind11::arg("feats")); + cl.def("detectFeatures", [](mrpt::vision::CFeatureExtraction &o, const class mrpt::img::CImage & a0, class mrpt::vision::CFeatureList & a1, const unsigned int & a2) -> void { return o.detectFeatures(a0, a1, a2); }, "", pybind11::arg("img"), pybind11::arg("feats"), pybind11::arg("init_ID")); + cl.def("detectFeatures", [](mrpt::vision::CFeatureExtraction &o, const class mrpt::img::CImage & a0, class mrpt::vision::CFeatureList & a1, const unsigned int & a2, const unsigned int & a3) -> void { return o.detectFeatures(a0, a1, a2, a3); }, "", pybind11::arg("img"), pybind11::arg("feats"), pybind11::arg("init_ID"), pybind11::arg("nDesiredFeatures")); + cl.def("detectFeatures", (void (mrpt::vision::CFeatureExtraction::*)(const class mrpt::img::CImage &, class mrpt::vision::CFeatureList &, const unsigned int, const unsigned int, const struct mrpt::vision::TImageROI &)) &mrpt::vision::CFeatureExtraction::detectFeatures, "Extract features from the image based on the method defined in\n TOptions. \n\n (input) The image from where to extract the\n images. \n\n (output) A complete list of features (containing\n a patch for each one of them if options.patchsize > 0). \n\n\n (op. input) Number of features to be extracted.\n Default: all possible.\n\n \n computeDescriptors\n\nC++: mrpt::vision::CFeatureExtraction::detectFeatures(const class mrpt::img::CImage &, class mrpt::vision::CFeatureList &, const unsigned int, const unsigned int, const struct mrpt::vision::TImageROI &) --> void", pybind11::arg("img"), pybind11::arg("feats"), pybind11::arg("init_ID"), pybind11::arg("nDesiredFeatures"), pybind11::arg("ROI")); + cl.def("computeDescriptors", (void (mrpt::vision::CFeatureExtraction::*)(const class mrpt::img::CImage &, class mrpt::vision::CFeatureList &, enum mrpt::vision::TDescriptorType)) &mrpt::vision::CFeatureExtraction::computeDescriptors, "Compute one (or more) descriptors for the given set of interest\n points onto the image, which may have been filled out manually or\n from \n\n (input) The image from where to\n compute the descriptors. \n\n (input/output) The\n list of features whose descriptors are going to be computed. \n\n\n (input) The bitwise OR of one or several\n descriptors defined in TDescriptorType.\n\n Each value in \"in_descriptor_list\" represents one descriptor to be\n computed, for example:\n \n\n\n\n\n\n \n The SIFT descriptors for already located features can only be\n computed through the Hess and\n CSBinary implementations which may be specified in\n CFeatureExtraction::TOptions::SIFTOptions.\n\n \n This call will also use additional parameters from \n \n\nC++: mrpt::vision::CFeatureExtraction::computeDescriptors(const class mrpt::img::CImage &, class mrpt::vision::CFeatureList &, enum mrpt::vision::TDescriptorType) --> void", pybind11::arg("in_img"), pybind11::arg("inout_features"), pybind11::arg("in_descriptor_list")); + + { // mrpt::vision::CFeatureExtraction::TOptions file:mrpt/vision/CFeatureExtraction.h line:85 + auto & enclosing_class = cl; + pybind11::class_, PyCallBack_mrpt_vision_CFeatureExtraction_TOptions, mrpt::config::CLoadableOptions> cl(enclosing_class, "TOptions", "The set of parameters for all the detectors & descriptor algorithms "); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions(); }, [](){ return new PyCallBack_mrpt_vision_CFeatureExtraction_TOptions(); } ) ); + cl.def( pybind11::init(), pybind11::arg("ft") ); + + cl.def( pybind11::init( [](PyCallBack_mrpt_vision_CFeatureExtraction_TOptions const &o){ return new PyCallBack_mrpt_vision_CFeatureExtraction_TOptions(o); } ) ); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions(o); } ) ); + cl.def_readwrite("featsType", &mrpt::vision::CFeatureExtraction::TOptions::featsType); + cl.def_readwrite("patchSize", &mrpt::vision::CFeatureExtraction::TOptions::patchSize); + cl.def_readwrite("useMask", &mrpt::vision::CFeatureExtraction::TOptions::useMask); + cl.def_readwrite("addNewFeatures", &mrpt::vision::CFeatureExtraction::TOptions::addNewFeatures); + cl.def_readwrite("FIND_SUBPIXEL", &mrpt::vision::CFeatureExtraction::TOptions::FIND_SUBPIXEL); + cl.def_readwrite("KLTOptions", &mrpt::vision::CFeatureExtraction::TOptions::KLTOptions); + cl.def_readwrite("harrisOptions", &mrpt::vision::CFeatureExtraction::TOptions::harrisOptions); + cl.def_readwrite("BCDOptions", &mrpt::vision::CFeatureExtraction::TOptions::BCDOptions); + cl.def_readwrite("FASTOptions", &mrpt::vision::CFeatureExtraction::TOptions::FASTOptions); + cl.def_readwrite("ORBOptions", &mrpt::vision::CFeatureExtraction::TOptions::ORBOptions); + cl.def_readwrite("SIFTOptions", &mrpt::vision::CFeatureExtraction::TOptions::SIFTOptions); + cl.def_readwrite("SURFOptions", &mrpt::vision::CFeatureExtraction::TOptions::SURFOptions); + cl.def_readwrite("SpinImagesOptions", &mrpt::vision::CFeatureExtraction::TOptions::SpinImagesOptions); + cl.def_readwrite("PolarImagesOptions", &mrpt::vision::CFeatureExtraction::TOptions::PolarImagesOptions); + cl.def_readwrite("LogPolarImagesOptions", &mrpt::vision::CFeatureExtraction::TOptions::LogPolarImagesOptions); + cl.def_readwrite("AKAZEOptions", &mrpt::vision::CFeatureExtraction::TOptions::AKAZEOptions); + cl.def_readwrite("LSDOptions", &mrpt::vision::CFeatureExtraction::TOptions::LSDOptions); + cl.def_readwrite("BLDOptions", &mrpt::vision::CFeatureExtraction::TOptions::BLDOptions); + cl.def_readwrite("LATCHOptions", &mrpt::vision::CFeatureExtraction::TOptions::LATCHOptions); + cl.def("loadFromConfigFile", (void (mrpt::vision::CFeatureExtraction::TOptions::*)(const class mrpt::config::CConfigFileBase &, const std::string &)) &mrpt::vision::CFeatureExtraction::TOptions::loadFromConfigFile, "C++: mrpt::vision::CFeatureExtraction::TOptions::loadFromConfigFile(const class mrpt::config::CConfigFileBase &, const std::string &) --> void", pybind11::arg("c"), pybind11::arg("s")); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions & (mrpt::vision::CFeatureExtraction::TOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions file:mrpt/vision/CFeatureExtraction.h line:120 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TKLTOptions", "KLT Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions(); } ) ); + cl.def_readwrite("radius", &mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions::radius); + cl.def_readwrite("threshold", &mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions::threshold); + cl.def_readwrite("min_distance", &mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions::min_distance); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions & (mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TKLTOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions file:mrpt/vision/CFeatureExtraction.h line:132 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "THarrisOptions", "Harris Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions(); } ) ); + cl.def_readwrite("threshold", &mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::threshold); + cl.def_readwrite("sigma", &mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::sigma); + cl.def_readwrite("radius", &mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::radius); + cl.def_readwrite("min_distance", &mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::min_distance); + cl.def_readwrite("k", &mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::k); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions & (mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::THarrisOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions file:mrpt/vision/CFeatureExtraction.h line:147 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TBCDOptions", "BCD Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions(); } ) ); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions & (mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TBCDOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions file:mrpt/vision/CFeatureExtraction.h line:152 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TFASTOptions", "FAST Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions(); } ) ); + cl.def_readwrite("threshold", &mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::threshold); + cl.def_readwrite("min_distance", &mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::min_distance); + cl.def_readwrite("nonmax_suppression", &mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::nonmax_suppression); + cl.def_readwrite("use_KLT_response", &mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::use_KLT_response); + cl.def_readwrite("KLT_response_half_win_size", &mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::KLT_response_half_win_size); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions & (mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TFASTOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TORBOptions file:mrpt/vision/CFeatureExtraction.h line:169 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TORBOptions", "ORB Options "); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TORBOptions(); } ) ); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TORBOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TORBOptions(o); } ) ); + cl.def_readwrite("n_levels", &mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::n_levels); + cl.def_readwrite("min_distance", &mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::min_distance); + cl.def_readwrite("scale_factor", &mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::scale_factor); + cl.def_readwrite("extract_patch", &mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::extract_patch); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TORBOptions & (mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TORBOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TORBOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TORBOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TORBOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions file:mrpt/vision/CFeatureExtraction.h line:179 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TSIFTOptions", "SIFT Options "); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions(); } ) ); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions(o); } ) ); + cl.def_readwrite("implementation", &mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::implementation); + cl.def_readwrite("octaveLayers", &mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::octaveLayers); + cl.def_readwrite("threshold", &mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::threshold); + cl.def_readwrite("edgeThreshold", &mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::edgeThreshold); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions & (mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TSIFTOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions file:mrpt/vision/CFeatureExtraction.h line:189 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TSURFOptions", "SURF Options "); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions(); } ) ); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions(o); } ) ); + cl.def_readwrite("rotation_invariant", &mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::rotation_invariant); + cl.def_readwrite("hessianThreshold", &mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::hessianThreshold); + cl.def_readwrite("nOctaves", &mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::nOctaves); + cl.def_readwrite("nLayersPerOctave", &mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::nLayersPerOctave); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions & (mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TSURFOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions file:mrpt/vision/CFeatureExtraction.h line:201 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TSpinImagesOptions", "SpinImages Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions(); } ) ); + cl.def_readwrite("hist_size_intensity", &mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::hist_size_intensity); + cl.def_readwrite("hist_size_distance", &mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::hist_size_distance); + cl.def_readwrite("std_dist", &mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::std_dist); + cl.def_readwrite("std_intensity", &mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::std_intensity); + cl.def_readwrite("radius", &mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::radius); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions & (mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TSpinImagesOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions file:mrpt/vision/CFeatureExtraction.h line:221 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TPolarImagesOptions", "PolarImagesOptions options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions(); } ) ); + cl.def_readwrite("bins_angle", &mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions::bins_angle); + cl.def_readwrite("bins_distance", &mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions::bins_distance); + cl.def_readwrite("radius", &mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions::radius); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions & (mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TPolarImagesOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions file:mrpt/vision/CFeatureExtraction.h line:236 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TLogPolarImagesOptions", "LogPolarImagesOptions Options"); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions(); } ) ); + cl.def_readwrite("radius", &mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions::radius); + cl.def_readwrite("num_angles", &mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions::num_angles); + cl.def_readwrite("rho_scale", &mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions::rho_scale); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions & (mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TLogPolarImagesOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions file:mrpt/vision/CFeatureExtraction.h line:251 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TAKAZEOptions", "AKAZEOptions Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions(); } ) ); + cl.def_readwrite("descriptor_type", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::descriptor_type); + cl.def_readwrite("descriptor_size", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::descriptor_size); + cl.def_readwrite("descriptor_channels", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::descriptor_channels); + cl.def_readwrite("threshold", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::threshold); + cl.def_readwrite("nOctaves", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::nOctaves); + cl.def_readwrite("nOctaveLayers", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::nOctaveLayers); + cl.def_readwrite("diffusivity", &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::diffusivity); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions & (mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TAKAZEOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions file:mrpt/vision/CFeatureExtraction.h line:267 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TLSDOptions", "LSDOptions Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions(); } ) ); + cl.def_readwrite("scale", &mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions::scale); + cl.def_readwrite("nOctaves", &mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions::nOctaves); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions & (mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TLSDOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions file:mrpt/vision/CFeatureExtraction.h line:274 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TBLDOptions", "BLDOptions Descriptor Options "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions(); } ) ); + cl.def_readwrite("ksize_", &mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::ksize_); + cl.def_readwrite("reductionRatio", &mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::reductionRatio); + cl.def_readwrite("widthOfBand", &mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::widthOfBand); + cl.def_readwrite("numOfOctave", &mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::numOfOctave); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions & (mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TBLDOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + { // mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions file:mrpt/vision/CFeatureExtraction.h line:283 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "TLATCHOptions", "LATCHOptions Descriptor "); + cl.def( pybind11::init( [](mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions const &o){ return new mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions(); } ) ); + cl.def_readwrite("bytes", &mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions::bytes); + cl.def_readwrite("rotationInvariance", &mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions::rotationInvariance); + cl.def_readwrite("half_ssd_size", &mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions::half_ssd_size); + cl.def("assign", (struct mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions & (mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions::*)(const struct mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions &)) &mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions::operator=, "C++: mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions::operator=(const struct mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions &) --> struct mrpt::vision::CFeatureExtraction::TOptions::TLATCHOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + + } +} diff --git a/python/generated-sources-pybind/pymrpt.cpp b/python/generated-sources-pybind/pymrpt.cpp index 5bb7c691ff..49a8bfd14f 100644 --- a/python/generated-sources-pybind/pymrpt.cpp +++ b/python/generated-sources-pybind/pymrpt.cpp @@ -54,6 +54,9 @@ void bind_mrpt_typemeta_TEnumType_6(std::function< pybind11::module &(std::strin void bind_std_variant(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_serialization_CArchive(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_serialization_CArchive_1(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_serialization_CArchive_2(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_serialization_CArchive_3(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_unknown_unknown(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_config_CLoadableOptions(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_system_CTicTac(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_system_os(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -193,7 +196,6 @@ void bind_mrpt_hwdrivers_CMyntEyeCamera(std::function< pybind11::module &(std::s void bind_mrpt_hwdrivers_CStereoGrabber_Bumblebee_libdc1394(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_hwdrivers_CCameraSensor(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_obs_gnss_messages_type_list(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_unknown_unknown(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_1(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_2(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_3(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -201,6 +203,7 @@ void bind_unknown_unknown_4(std::function< pybind11::module &(std::string const void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_obs_CObservationGPS(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_hwdrivers_CGPSInterface(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_containers_MT_buffer(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -481,6 +484,9 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_std_variant(M); bind_mrpt_serialization_CArchive(M); bind_mrpt_serialization_CArchive_1(M); + bind_mrpt_serialization_CArchive_2(M); + bind_mrpt_serialization_CArchive_3(M); + bind_unknown_unknown(M); bind_mrpt_config_CLoadableOptions(M); bind_mrpt_system_CTicTac(M); bind_mrpt_system_os(M); @@ -620,7 +626,6 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_hwdrivers_CStereoGrabber_Bumblebee_libdc1394(M); bind_mrpt_hwdrivers_CCameraSensor(M); bind_mrpt_obs_gnss_messages_type_list(M); - bind_unknown_unknown(M); bind_unknown_unknown_1(M); bind_unknown_unknown_2(M); bind_unknown_unknown_3(M); @@ -628,6 +633,7 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_unknown_unknown_5(M); bind_unknown_unknown_6(M); bind_unknown_unknown_7(M); + bind_unknown_unknown_8(M); bind_mrpt_obs_CObservationGPS(M); bind_mrpt_hwdrivers_CGPSInterface(M); bind_mrpt_containers_MT_buffer(M); diff --git a/python/generated-sources-pybind/pymrpt.sources b/python/generated-sources-pybind/pymrpt.sources index 44b4664641..d12c73b01d 100644 --- a/python/generated-sources-pybind/pymrpt.sources +++ b/python/generated-sources-pybind/pymrpt.sources @@ -44,6 +44,9 @@ mrpt/typemeta/TEnumType_6.cpp std/variant.cpp mrpt/serialization/CArchive.cpp mrpt/serialization/CArchive_1.cpp +mrpt/serialization/CArchive_2.cpp +mrpt/serialization/CArchive_3.cpp +unknown/unknown.cpp mrpt/config/CLoadableOptions.cpp mrpt/system/CTicTac.cpp mrpt/system/os.cpp @@ -183,7 +186,6 @@ mrpt/hwdrivers/CMyntEyeCamera.cpp mrpt/hwdrivers/CStereoGrabber_Bumblebee_libdc1394.cpp mrpt/hwdrivers/CCameraSensor.cpp mrpt/obs/gnss_messages_type_list.cpp -unknown/unknown.cpp unknown/unknown_1.cpp unknown/unknown_2.cpp unknown/unknown_3.cpp @@ -191,6 +193,7 @@ unknown/unknown_4.cpp unknown/unknown_5.cpp unknown/unknown_6.cpp unknown/unknown_7.cpp +unknown/unknown_8.cpp mrpt/obs/CObservationGPS.cpp mrpt/hwdrivers/CGPSInterface.cpp mrpt/containers/MT_buffer.cpp diff --git a/python/generated-sources-pybind/unknown/unknown.cpp b/python/generated-sources-pybind/unknown/unknown.cpp index 9eced7599a..5bade7b095 100644 --- a/python/generated-sources-pybind/unknown/unknown.cpp +++ b/python/generated-sources-pybind/unknown/unknown.cpp @@ -1,19 +1,14 @@ -#include -#include #include #include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include -#include -#include -#include -#include -#include // __str__ -#include +#include #include -#include #include #include @@ -28,367 +23,18 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NMEA_GLL file: line:104 -struct PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL : public mrpt::obs::gnss::Message_NMEA_GLL { - using mrpt::obs::gnss::Message_NMEA_GLL::Message_NMEA_GLL; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_GLL::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_GLL::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NMEA_RMC file: line:133 -struct PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC : public mrpt::obs::gnss::Message_NMEA_RMC { - using mrpt::obs::gnss::Message_NMEA_RMC::Message_NMEA_RMC; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_RMC::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_RMC::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NMEA_VTG file: line:177 -struct PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG : public mrpt::obs::gnss::Message_NMEA_VTG { - using mrpt::obs::gnss::Message_NMEA_VTG::Message_NMEA_VTG; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_VTG::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_VTG::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NMEA_GSA file: line:201 -struct PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA : public mrpt::obs::gnss::Message_NMEA_GSA { - using mrpt::obs::gnss::Message_NMEA_GSA::Message_NMEA_GSA; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_GSA::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_GSA::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NMEA_ZDA file: line:227 -struct PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA : public mrpt::obs::gnss::Message_NMEA_ZDA { - using mrpt::obs::gnss::Message_NMEA_ZDA::Message_NMEA_ZDA; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_ZDA::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NMEA_ZDA::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - void bind_unknown_unknown(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NMEA_GLL file: line:104 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_GLL", "NMEA datum: GLL. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GLL(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GLL const &o){ return new mrpt::obs::gnss::Message_NMEA_GLL(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_GLL::fields); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GLL & (mrpt::obs::gnss::Message_NMEA_GLL::*)(const struct mrpt::obs::gnss::Message_NMEA_GLL &)) &mrpt::obs::gnss::Message_NMEA_GLL::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GLL::operator=(const struct mrpt::obs::gnss::Message_NMEA_GLL &) --> struct mrpt::obs::gnss::Message_NMEA_GLL &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NMEA_GLL::content_t file: line:113 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GLL::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GLL::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_GLL::content_t(o); } ) ); - cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::UTCTime); - cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::latitude_degrees); - cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::longitude_degrees); - cl.def_readwrite("validity_char", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::validity_char); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GLL::content_t & (mrpt::obs::gnss::Message_NMEA_GLL::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &)) &mrpt::obs::gnss::Message_NMEA_GLL::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GLL::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NMEA_RMC file: line:133 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_RMC", "NMEA datum: RMC. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_RMC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_RMC const &o){ return new mrpt::obs::gnss::Message_NMEA_RMC(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_RMC::fields); - cl.def("getDateAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_RMC::*)() const) &mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp, "Build an MRPT timestamp with the year/month/day of this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp() const --> mrpt::Clock::time_point"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_RMC & (mrpt::obs::gnss::Message_NMEA_RMC::*)(const struct mrpt::obs::gnss::Message_NMEA_RMC &)) &mrpt::obs::gnss::Message_NMEA_RMC::operator=, "C++: mrpt::obs::gnss::Message_NMEA_RMC::operator=(const struct mrpt::obs::gnss::Message_NMEA_RMC &) --> struct mrpt::obs::gnss::Message_NMEA_RMC &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NMEA_RMC::content_t file: line:142 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_RMC::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_RMC::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_RMC::content_t(o); } ) ); - cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::UTCTime); - cl.def_readwrite("validity_char", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::validity_char); - cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::latitude_degrees); - cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::longitude_degrees); - cl.def_readwrite("speed_knots", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::speed_knots); - cl.def_readwrite("direction_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::direction_degrees); - cl.def_readwrite("date_day", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_day); - cl.def_readwrite("date_month", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_month); - cl.def_readwrite("date_year", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_year); - cl.def_readwrite("magnetic_dir", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::magnetic_dir); - cl.def_readwrite("positioning_mode", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::positioning_mode); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_RMC::content_t & (mrpt::obs::gnss::Message_NMEA_RMC::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &)) &mrpt::obs::gnss::Message_NMEA_RMC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_RMC::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NMEA_VTG file: line:177 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_VTG", "NMEA datum: VTG. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_VTG(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_VTG const &o){ return new mrpt::obs::gnss::Message_NMEA_VTG(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_VTG::fields); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_VTG & (mrpt::obs::gnss::Message_NMEA_VTG::*)(const struct mrpt::obs::gnss::Message_NMEA_VTG &)) &mrpt::obs::gnss::Message_NMEA_VTG::operator=, "C++: mrpt::obs::gnss::Message_NMEA_VTG::operator=(const struct mrpt::obs::gnss::Message_NMEA_VTG &) --> struct mrpt::obs::gnss::Message_NMEA_VTG &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NMEA_VTG::content_t file: line:186 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_VTG::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_VTG::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_VTG::content_t(o); } ) ); - cl.def_readwrite("true_track", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::true_track); - cl.def_readwrite("magnetic_track", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::magnetic_track); - cl.def_readwrite("ground_speed_knots", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::ground_speed_knots); - cl.def_readwrite("ground_speed_kmh", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::ground_speed_kmh); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_VTG::content_t & (mrpt::obs::gnss::Message_NMEA_VTG::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_VTG::content_t &)) &mrpt::obs::gnss::Message_NMEA_VTG::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_VTG::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_VTG::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_VTG::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NMEA_GSA file: line:201 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_GSA", "NMEA datum: GSA. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GSA(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GSA const &o){ return new mrpt::obs::gnss::Message_NMEA_GSA(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_GSA::fields); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GSA & (mrpt::obs::gnss::Message_NMEA_GSA::*)(const struct mrpt::obs::gnss::Message_NMEA_GSA &)) &mrpt::obs::gnss::Message_NMEA_GSA::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GSA::operator=(const struct mrpt::obs::gnss::Message_NMEA_GSA &) --> struct mrpt::obs::gnss::Message_NMEA_GSA &", pybind11::return_value_policy::automatic, pybind11::arg("")); + // mrpt::serialization::archiveFrom(class mrpt::io::CFileGZInputStream &) file: line:15 + M("mrpt::serialization").def("archiveFrom", (class mrpt::serialization::CArchiveStreamBase (*)(class mrpt::io::CFileGZInputStream &)) &mrpt::serialization::archiveFrom, "C++: mrpt::serialization::archiveFrom(class mrpt::io::CFileGZInputStream &) --> class mrpt::serialization::CArchiveStreamBase", pybind11::arg("s")); - { // mrpt::obs::gnss::Message_NMEA_GSA::content_t file: line:210 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GSA::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GSA::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_GSA::content_t(o); } ) ); - cl.def_readwrite("auto_selection_fix", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::auto_selection_fix); - cl.def_readwrite("fix_2D_3D", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::fix_2D_3D); - cl.def_readwrite("PDOP", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::PDOP); - cl.def_readwrite("HDOP", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::HDOP); - cl.def_readwrite("VDOP", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::VDOP); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GSA::content_t & (mrpt::obs::gnss::Message_NMEA_GSA::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_GSA::content_t &)) &mrpt::obs::gnss::Message_NMEA_GSA::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GSA::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_GSA::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_GSA::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } + // mrpt::serialization::archiveFrom(class mrpt::io::CFileGZOutputStream &) file: line:20 + M("mrpt::serialization").def("archiveFrom", (class mrpt::serialization::CArchiveStreamBase (*)(class mrpt::io::CFileGZOutputStream &)) &mrpt::serialization::archiveFrom, "C++: mrpt::serialization::archiveFrom(class mrpt::io::CFileGZOutputStream &) --> class mrpt::serialization::CArchiveStreamBase", pybind11::arg("s")); - } - { // mrpt::obs::gnss::Message_NMEA_ZDA file: line:227 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_ZDA", "NMEA datum: ZDA. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_ZDA(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_ZDA const &o){ return new mrpt::obs::gnss::Message_NMEA_ZDA(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_ZDA::fields); - cl.def("getDateTimeAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_ZDA::*)() const) &mrpt::obs::gnss::Message_NMEA_ZDA::getDateTimeAsTimestamp, "Build an MRPT UTC timestamp with the year/month/day + hour/minute/sec of\n this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_ZDA::getDateTimeAsTimestamp() const --> mrpt::Clock::time_point"); - cl.def("getDateAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_ZDA::*)() const) &mrpt::obs::gnss::Message_NMEA_ZDA::getDateAsTimestamp, "Build an MRPT timestamp with the year/month/day of this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_ZDA::getDateAsTimestamp() const --> mrpt::Clock::time_point"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_ZDA & (mrpt::obs::gnss::Message_NMEA_ZDA::*)(const struct mrpt::obs::gnss::Message_NMEA_ZDA &)) &mrpt::obs::gnss::Message_NMEA_ZDA::operator=, "C++: mrpt::obs::gnss::Message_NMEA_ZDA::operator=(const struct mrpt::obs::gnss::Message_NMEA_ZDA &) --> struct mrpt::obs::gnss::Message_NMEA_ZDA &", pybind11::return_value_policy::automatic, pybind11::arg("")); + // mrpt::serialization::archiveFrom(class mrpt::io::CFileInputStream &) file: line:25 + M("mrpt::serialization").def("archiveFrom", (class mrpt::serialization::CArchiveStreamBase (*)(class mrpt::io::CFileInputStream &)) &mrpt::serialization::archiveFrom, "C++: mrpt::serialization::archiveFrom(class mrpt::io::CFileInputStream &) --> class mrpt::serialization::CArchiveStreamBase", pybind11::arg("s")); - { // mrpt::obs::gnss::Message_NMEA_ZDA::content_t file: line:236 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_ZDA::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_ZDA::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_ZDA::content_t(o); } ) ); - cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::UTCTime); - cl.def_readwrite("date_day", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::date_day); - cl.def_readwrite("date_month", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::date_month); - cl.def_readwrite("date_year", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::date_year); - cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t & (mrpt::obs::gnss::Message_NMEA_ZDA::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t &)) &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_ZDA::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } + // mrpt::serialization::archiveFrom(class mrpt::io::CFileOutputStream &) file: line:30 + M("mrpt::serialization").def("archiveFrom", (class mrpt::serialization::CArchiveStreamBase (*)(class mrpt::io::CFileOutputStream &)) &mrpt::serialization::archiveFrom, "C++: mrpt::serialization::archiveFrom(class mrpt::io::CFileOutputStream &) --> class mrpt::serialization::CArchiveStreamBase", pybind11::arg("s")); - } - { // mrpt::obs::gnss::nv_oem6_header_t file: line:19 - pybind11::class_> cl(M("mrpt::obs::gnss"), "nv_oem6_header_t", "Novatel OEM6 regular header structure \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](mrpt::obs::gnss::nv_oem6_header_t const &o){ return new mrpt::obs::gnss::nv_oem6_header_t(o); } ) ); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::nv_oem6_header_t(); } ) ); - cl.def_readwrite("hdr_len", &mrpt::obs::gnss::nv_oem6_header_t::hdr_len); - cl.def_readwrite("msg_id", &mrpt::obs::gnss::nv_oem6_header_t::msg_id); - cl.def_readwrite("msg_type", &mrpt::obs::gnss::nv_oem6_header_t::msg_type); - cl.def_readwrite("port_addr", &mrpt::obs::gnss::nv_oem6_header_t::port_addr); - cl.def_readwrite("msg_len", &mrpt::obs::gnss::nv_oem6_header_t::msg_len); - cl.def_readwrite("seq_number", &mrpt::obs::gnss::nv_oem6_header_t::seq_number); - cl.def_readwrite("idle_percent", &mrpt::obs::gnss::nv_oem6_header_t::idle_percent); - cl.def_readwrite("time_status", &mrpt::obs::gnss::nv_oem6_header_t::time_status); - cl.def_readwrite("week", &mrpt::obs::gnss::nv_oem6_header_t::week); - cl.def_readwrite("ms_in_week", &mrpt::obs::gnss::nv_oem6_header_t::ms_in_week); - cl.def_readwrite("receiver_status", &mrpt::obs::gnss::nv_oem6_header_t::receiver_status); - cl.def_readwrite("reserved", &mrpt::obs::gnss::nv_oem6_header_t::reserved); - cl.def_readwrite("receiver_sw_version", &mrpt::obs::gnss::nv_oem6_header_t::receiver_sw_version); - cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_header_t::*)()) &mrpt::obs::gnss::nv_oem6_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_header_t::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_header_t & (mrpt::obs::gnss::nv_oem6_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_header_t &)) &mrpt::obs::gnss::nv_oem6_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_header_t &) --> struct mrpt::obs::gnss::nv_oem6_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } } diff --git a/python/generated-sources-pybind/unknown/unknown_1.cpp b/python/generated-sources-pybind/unknown/unknown_1.cpp index 6f3ab0ec08..00f425a6bc 100644 --- a/python/generated-sources-pybind/unknown/unknown_1.cpp +++ b/python/generated-sources-pybind/unknown/unknown_1.cpp @@ -1,5 +1,19 @@ +#include +#include +#include +#include +#include #include +#include +#include +#include +#include +#include +#include #include // __str__ +#include +#include +#include #include #include @@ -14,17 +28,367 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif +// mrpt::obs::gnss::Message_NMEA_GLL file: line:104 +struct PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL : public mrpt::obs::gnss::Message_NMEA_GLL { + using mrpt::obs::gnss::Message_NMEA_GLL::Message_NMEA_GLL; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_GLL::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_GLL::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NMEA_RMC file: line:133 +struct PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC : public mrpt::obs::gnss::Message_NMEA_RMC { + using mrpt::obs::gnss::Message_NMEA_RMC::Message_NMEA_RMC; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_RMC::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_RMC::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NMEA_VTG file: line:177 +struct PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG : public mrpt::obs::gnss::Message_NMEA_VTG { + using mrpt::obs::gnss::Message_NMEA_VTG::Message_NMEA_VTG; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_VTG::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_VTG::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NMEA_GSA file: line:201 +struct PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA : public mrpt::obs::gnss::Message_NMEA_GSA { + using mrpt::obs::gnss::Message_NMEA_GSA::Message_NMEA_GSA; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_GSA::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_GSA::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NMEA_ZDA file: line:227 +struct PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA : public mrpt::obs::gnss::Message_NMEA_ZDA { + using mrpt::obs::gnss::Message_NMEA_ZDA::Message_NMEA_ZDA; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_ZDA::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NMEA_ZDA::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + void bind_unknown_unknown_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::nv_oem6_short_header_t file: line:59 - pybind11::class_> cl(M("mrpt::obs::gnss"), "nv_oem6_short_header_t", "Novatel OEM6 short header structure \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](mrpt::obs::gnss::nv_oem6_short_header_t const &o){ return new mrpt::obs::gnss::nv_oem6_short_header_t(o); } ) ); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::nv_oem6_short_header_t(); } ) ); - cl.def_readwrite("msg_len", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_len); - cl.def_readwrite("msg_id", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_id); - cl.def_readwrite("week", &mrpt::obs::gnss::nv_oem6_short_header_t::week); - cl.def_readwrite("ms_in_week", &mrpt::obs::gnss::nv_oem6_short_header_t::ms_in_week); - cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_short_header_t::*)()) &mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_short_header_t & (mrpt::obs::gnss::nv_oem6_short_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_short_header_t &)) &mrpt::obs::gnss::nv_oem6_short_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_short_header_t &) --> struct mrpt::obs::gnss::nv_oem6_short_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NMEA_GLL file: line:104 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_GLL", "NMEA datum: GLL. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GLL(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GLL(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GLL const &o){ return new mrpt::obs::gnss::Message_NMEA_GLL(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_GLL::fields); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GLL & (mrpt::obs::gnss::Message_NMEA_GLL::*)(const struct mrpt::obs::gnss::Message_NMEA_GLL &)) &mrpt::obs::gnss::Message_NMEA_GLL::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GLL::operator=(const struct mrpt::obs::gnss::Message_NMEA_GLL &) --> struct mrpt::obs::gnss::Message_NMEA_GLL &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NMEA_GLL::content_t file: line:113 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GLL::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GLL::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_GLL::content_t(o); } ) ); + cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::UTCTime); + cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::latitude_degrees); + cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::longitude_degrees); + cl.def_readwrite("validity_char", &mrpt::obs::gnss::Message_NMEA_GLL::content_t::validity_char); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GLL::content_t & (mrpt::obs::gnss::Message_NMEA_GLL::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &)) &mrpt::obs::gnss::Message_NMEA_GLL::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GLL::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_GLL::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NMEA_RMC file: line:133 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_RMC", "NMEA datum: RMC. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_RMC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_RMC(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_RMC const &o){ return new mrpt::obs::gnss::Message_NMEA_RMC(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_RMC::fields); + cl.def("getDateAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_RMC::*)() const) &mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp, "Build an MRPT timestamp with the year/month/day of this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_RMC::getDateAsTimestamp() const --> mrpt::Clock::time_point"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_RMC & (mrpt::obs::gnss::Message_NMEA_RMC::*)(const struct mrpt::obs::gnss::Message_NMEA_RMC &)) &mrpt::obs::gnss::Message_NMEA_RMC::operator=, "C++: mrpt::obs::gnss::Message_NMEA_RMC::operator=(const struct mrpt::obs::gnss::Message_NMEA_RMC &) --> struct mrpt::obs::gnss::Message_NMEA_RMC &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NMEA_RMC::content_t file: line:142 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_RMC::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_RMC::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_RMC::content_t(o); } ) ); + cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::UTCTime); + cl.def_readwrite("validity_char", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::validity_char); + cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::latitude_degrees); + cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::longitude_degrees); + cl.def_readwrite("speed_knots", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::speed_knots); + cl.def_readwrite("direction_degrees", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::direction_degrees); + cl.def_readwrite("date_day", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_day); + cl.def_readwrite("date_month", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_month); + cl.def_readwrite("date_year", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::date_year); + cl.def_readwrite("magnetic_dir", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::magnetic_dir); + cl.def_readwrite("positioning_mode", &mrpt::obs::gnss::Message_NMEA_RMC::content_t::positioning_mode); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_RMC::content_t & (mrpt::obs::gnss::Message_NMEA_RMC::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &)) &mrpt::obs::gnss::Message_NMEA_RMC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_RMC::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_RMC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NMEA_VTG file: line:177 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_VTG", "NMEA datum: VTG. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_VTG(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_VTG(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_VTG const &o){ return new mrpt::obs::gnss::Message_NMEA_VTG(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_VTG::fields); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_VTG & (mrpt::obs::gnss::Message_NMEA_VTG::*)(const struct mrpt::obs::gnss::Message_NMEA_VTG &)) &mrpt::obs::gnss::Message_NMEA_VTG::operator=, "C++: mrpt::obs::gnss::Message_NMEA_VTG::operator=(const struct mrpt::obs::gnss::Message_NMEA_VTG &) --> struct mrpt::obs::gnss::Message_NMEA_VTG &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NMEA_VTG::content_t file: line:186 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_VTG::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_VTG::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_VTG::content_t(o); } ) ); + cl.def_readwrite("true_track", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::true_track); + cl.def_readwrite("magnetic_track", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::magnetic_track); + cl.def_readwrite("ground_speed_knots", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::ground_speed_knots); + cl.def_readwrite("ground_speed_kmh", &mrpt::obs::gnss::Message_NMEA_VTG::content_t::ground_speed_kmh); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_VTG::content_t & (mrpt::obs::gnss::Message_NMEA_VTG::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_VTG::content_t &)) &mrpt::obs::gnss::Message_NMEA_VTG::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_VTG::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_VTG::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_VTG::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NMEA_GSA file: line:201 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_GSA", "NMEA datum: GSA. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GSA(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_GSA(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GSA const &o){ return new mrpt::obs::gnss::Message_NMEA_GSA(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_GSA::fields); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GSA & (mrpt::obs::gnss::Message_NMEA_GSA::*)(const struct mrpt::obs::gnss::Message_NMEA_GSA &)) &mrpt::obs::gnss::Message_NMEA_GSA::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GSA::operator=(const struct mrpt::obs::gnss::Message_NMEA_GSA &) --> struct mrpt::obs::gnss::Message_NMEA_GSA &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NMEA_GSA::content_t file: line:210 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_GSA::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_GSA::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_GSA::content_t(o); } ) ); + cl.def_readwrite("auto_selection_fix", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::auto_selection_fix); + cl.def_readwrite("fix_2D_3D", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::fix_2D_3D); + cl.def_readwrite("PDOP", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::PDOP); + cl.def_readwrite("HDOP", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::HDOP); + cl.def_readwrite("VDOP", &mrpt::obs::gnss::Message_NMEA_GSA::content_t::VDOP); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_GSA::content_t & (mrpt::obs::gnss::Message_NMEA_GSA::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_GSA::content_t &)) &mrpt::obs::gnss::Message_NMEA_GSA::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_GSA::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_GSA::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_GSA::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NMEA_ZDA file: line:227 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NMEA_ZDA", "NMEA datum: ZDA. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_ZDA(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NMEA_ZDA(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_ZDA const &o){ return new mrpt::obs::gnss::Message_NMEA_ZDA(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NMEA_ZDA::fields); + cl.def("getDateTimeAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_ZDA::*)() const) &mrpt::obs::gnss::Message_NMEA_ZDA::getDateTimeAsTimestamp, "Build an MRPT UTC timestamp with the year/month/day + hour/minute/sec of\n this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_ZDA::getDateTimeAsTimestamp() const --> mrpt::Clock::time_point"); + cl.def("getDateAsTimestamp", (mrpt::Clock::time_point (mrpt::obs::gnss::Message_NMEA_ZDA::*)() const) &mrpt::obs::gnss::Message_NMEA_ZDA::getDateAsTimestamp, "Build an MRPT timestamp with the year/month/day of this observation. \n\nC++: mrpt::obs::gnss::Message_NMEA_ZDA::getDateAsTimestamp() const --> mrpt::Clock::time_point"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_ZDA & (mrpt::obs::gnss::Message_NMEA_ZDA::*)(const struct mrpt::obs::gnss::Message_NMEA_ZDA &)) &mrpt::obs::gnss::Message_NMEA_ZDA::operator=, "C++: mrpt::obs::gnss::Message_NMEA_ZDA::operator=(const struct mrpt::obs::gnss::Message_NMEA_ZDA &) --> struct mrpt::obs::gnss::Message_NMEA_ZDA &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NMEA_ZDA::content_t file: line:236 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NMEA_ZDA::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NMEA_ZDA::content_t const &o){ return new mrpt::obs::gnss::Message_NMEA_ZDA::content_t(o); } ) ); + cl.def_readwrite("UTCTime", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::UTCTime); + cl.def_readwrite("date_day", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::date_day); + cl.def_readwrite("date_month", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::date_month); + cl.def_readwrite("date_year", &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::date_year); + cl.def("assign", (struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t & (mrpt::obs::gnss::Message_NMEA_ZDA::content_t::*)(const struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t &)) &mrpt::obs::gnss::Message_NMEA_ZDA::content_t::operator=, "C++: mrpt::obs::gnss::Message_NMEA_ZDA::content_t::operator=(const struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t &) --> struct mrpt::obs::gnss::Message_NMEA_ZDA::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::nv_oem6_header_t file: line:19 + pybind11::class_> cl(M("mrpt::obs::gnss"), "nv_oem6_header_t", "Novatel OEM6 regular header structure \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](mrpt::obs::gnss::nv_oem6_header_t const &o){ return new mrpt::obs::gnss::nv_oem6_header_t(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::nv_oem6_header_t(); } ) ); + cl.def_readwrite("hdr_len", &mrpt::obs::gnss::nv_oem6_header_t::hdr_len); + cl.def_readwrite("msg_id", &mrpt::obs::gnss::nv_oem6_header_t::msg_id); + cl.def_readwrite("msg_type", &mrpt::obs::gnss::nv_oem6_header_t::msg_type); + cl.def_readwrite("port_addr", &mrpt::obs::gnss::nv_oem6_header_t::port_addr); + cl.def_readwrite("msg_len", &mrpt::obs::gnss::nv_oem6_header_t::msg_len); + cl.def_readwrite("seq_number", &mrpt::obs::gnss::nv_oem6_header_t::seq_number); + cl.def_readwrite("idle_percent", &mrpt::obs::gnss::nv_oem6_header_t::idle_percent); + cl.def_readwrite("time_status", &mrpt::obs::gnss::nv_oem6_header_t::time_status); + cl.def_readwrite("week", &mrpt::obs::gnss::nv_oem6_header_t::week); + cl.def_readwrite("ms_in_week", &mrpt::obs::gnss::nv_oem6_header_t::ms_in_week); + cl.def_readwrite("receiver_status", &mrpt::obs::gnss::nv_oem6_header_t::receiver_status); + cl.def_readwrite("reserved", &mrpt::obs::gnss::nv_oem6_header_t::reserved); + cl.def_readwrite("receiver_sw_version", &mrpt::obs::gnss::nv_oem6_header_t::receiver_sw_version); + cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_header_t::*)()) &mrpt::obs::gnss::nv_oem6_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_header_t::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_header_t & (mrpt::obs::gnss::nv_oem6_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_header_t &)) &mrpt::obs::gnss::nv_oem6_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_header_t &) --> struct mrpt::obs::gnss::nv_oem6_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/generated-sources-pybind/unknown/unknown_2.cpp b/python/generated-sources-pybind/unknown/unknown_2.cpp index 5251ba0efd..e37f94a9e7 100644 --- a/python/generated-sources-pybind/unknown/unknown_2.cpp +++ b/python/generated-sources-pybind/unknown/unknown_2.cpp @@ -1,7 +1,5 @@ -#include -#include -#include -#include +#include +#include // __str__ #include #include @@ -18,41 +16,15 @@ void bind_unknown_unknown_2(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::obs::gnss::nv_oem6_position_type::nv_position_type_t file: line:88 - pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_position_type"), "nv_position_type_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 84; Novatel SPAN on OEM6 firmware\n manual, table 26. ") - .value("NONE", mrpt::obs::gnss::nv_oem6_position_type::NONE) - .value("FIXEDPOS", mrpt::obs::gnss::nv_oem6_position_type::FIXEDPOS) - .value("FIXEDHEIGHT", mrpt::obs::gnss::nv_oem6_position_type::FIXEDHEIGHT) - .value("Reserved", mrpt::obs::gnss::nv_oem6_position_type::Reserved) - .value("FLOATCONV", mrpt::obs::gnss::nv_oem6_position_type::FLOATCONV) - .value("WIDELANE", mrpt::obs::gnss::nv_oem6_position_type::WIDELANE) - .value("NARROWLANE", mrpt::obs::gnss::nv_oem6_position_type::NARROWLANE) - .value("DOPPLER_VELOCITY", mrpt::obs::gnss::nv_oem6_position_type::DOPPLER_VELOCITY) - .value("SINGLE", mrpt::obs::gnss::nv_oem6_position_type::SINGLE) - .value("PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::PSRDIFF) - .value("WAAS", mrpt::obs::gnss::nv_oem6_position_type::WAAS) - .value("PROPAGATED", mrpt::obs::gnss::nv_oem6_position_type::PROPAGATED) - .value("OMNISTAR", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR) - .value("L1_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::L1_FLOAT) - .value("IONOFREE_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::IONOFREE_FLOAT) - .value("NARROW_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_FLOAT) - .value("L1_INT", mrpt::obs::gnss::nv_oem6_position_type::L1_INT) - .value("WIDE_INT", mrpt::obs::gnss::nv_oem6_position_type::WIDE_INT) - .value("NARROW_INT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_INT) - .value("RTK_DIRECT_INS", mrpt::obs::gnss::nv_oem6_position_type::RTK_DIRECT_INS) - .value("INS", mrpt::obs::gnss::nv_oem6_position_type::INS) - .value("INS_PSRSP", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRSP) - .value("INS_PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRDIFF) - .value("INS_RTKFLOAT", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFLOAT) - .value("INS_RTKFIXED", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFIXED) - .value("OMNISTAR_HP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_HP) - .value("OMNISTAR_XP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_XP) - .value("CDGPS", mrpt::obs::gnss::nv_oem6_position_type::CDGPS) - .export_values(); - -; - - // mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) file: line:120 - M("mrpt::obs::gnss::nv_oem6_position_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_position_type::enum2str, "for nv_position_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); - + { // mrpt::obs::gnss::nv_oem6_short_header_t file: line:59 + pybind11::class_> cl(M("mrpt::obs::gnss"), "nv_oem6_short_header_t", "Novatel OEM6 short header structure \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](mrpt::obs::gnss::nv_oem6_short_header_t const &o){ return new mrpt::obs::gnss::nv_oem6_short_header_t(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::nv_oem6_short_header_t(); } ) ); + cl.def_readwrite("msg_len", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_len); + cl.def_readwrite("msg_id", &mrpt::obs::gnss::nv_oem6_short_header_t::msg_id); + cl.def_readwrite("week", &mrpt::obs::gnss::nv_oem6_short_header_t::week); + cl.def_readwrite("ms_in_week", &mrpt::obs::gnss::nv_oem6_short_header_t::ms_in_week); + cl.def("fixEndianness", (void (mrpt::obs::gnss::nv_oem6_short_header_t::*)()) &mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::nv_oem6_short_header_t & (mrpt::obs::gnss::nv_oem6_short_header_t::*)(const struct mrpt::obs::gnss::nv_oem6_short_header_t &)) &mrpt::obs::gnss::nv_oem6_short_header_t::operator=, "C++: mrpt::obs::gnss::nv_oem6_short_header_t::operator=(const struct mrpt::obs::gnss::nv_oem6_short_header_t &) --> struct mrpt::obs::gnss::nv_oem6_short_header_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } } diff --git a/python/generated-sources-pybind/unknown/unknown_3.cpp b/python/generated-sources-pybind/unknown/unknown_3.cpp index 936f6f97fa..08a98dc282 100644 --- a/python/generated-sources-pybind/unknown/unknown_3.cpp +++ b/python/generated-sources-pybind/unknown/unknown_3.cpp @@ -18,32 +18,41 @@ void bind_unknown_unknown_3(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::obs::gnss::nv_oem6_solution_status::nv_solution_status_t file: line:126 - pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_solution_status"), "nv_solution_status_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 85 ") - .value("SOL_COMPUTED", mrpt::obs::gnss::nv_oem6_solution_status::SOL_COMPUTED) - .value("INSUFFICIENT_OBS", mrpt::obs::gnss::nv_oem6_solution_status::INSUFFICIENT_OBS) - .value("NO_CONVERGENCE", mrpt::obs::gnss::nv_oem6_solution_status::NO_CONVERGENCE) - .value("SINGULARITY", mrpt::obs::gnss::nv_oem6_solution_status::SINGULARITY) - .value("COV_TRACE", mrpt::obs::gnss::nv_oem6_solution_status::COV_TRACE) - .value("TEST_DIST", mrpt::obs::gnss::nv_oem6_solution_status::TEST_DIST) - .value("COLD_START", mrpt::obs::gnss::nv_oem6_solution_status::COLD_START) - .value("V_H_LIMIT", mrpt::obs::gnss::nv_oem6_solution_status::V_H_LIMIT) - .value("VARIANCE", mrpt::obs::gnss::nv_oem6_solution_status::VARIANCE) - .value("RESIDUALS", mrpt::obs::gnss::nv_oem6_solution_status::RESIDUALS) - .value("DELTA_POS", mrpt::obs::gnss::nv_oem6_solution_status::DELTA_POS) - .value("NEGATIVE_VAR", mrpt::obs::gnss::nv_oem6_solution_status::NEGATIVE_VAR) - .value("INTEGRITY_WARNING", mrpt::obs::gnss::nv_oem6_solution_status::INTEGRITY_WARNING) - .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_solution_status::INS_INACTIVE) - .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_solution_status::INS_ALIGNING) - .value("INS_BAD", mrpt::obs::gnss::nv_oem6_solution_status::INS_BAD) - .value("IMU_UNPLUGGED", mrpt::obs::gnss::nv_oem6_solution_status::IMU_UNPLUGGED) - .value("PENDING", mrpt::obs::gnss::nv_oem6_solution_status::PENDING) - .value("INVALID_FIX", mrpt::obs::gnss::nv_oem6_solution_status::INVALID_FIX) + // mrpt::obs::gnss::nv_oem6_position_type::nv_position_type_t file: line:88 + pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_position_type"), "nv_position_type_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 84; Novatel SPAN on OEM6 firmware\n manual, table 26. ") + .value("NONE", mrpt::obs::gnss::nv_oem6_position_type::NONE) + .value("FIXEDPOS", mrpt::obs::gnss::nv_oem6_position_type::FIXEDPOS) + .value("FIXEDHEIGHT", mrpt::obs::gnss::nv_oem6_position_type::FIXEDHEIGHT) + .value("Reserved", mrpt::obs::gnss::nv_oem6_position_type::Reserved) + .value("FLOATCONV", mrpt::obs::gnss::nv_oem6_position_type::FLOATCONV) + .value("WIDELANE", mrpt::obs::gnss::nv_oem6_position_type::WIDELANE) + .value("NARROWLANE", mrpt::obs::gnss::nv_oem6_position_type::NARROWLANE) + .value("DOPPLER_VELOCITY", mrpt::obs::gnss::nv_oem6_position_type::DOPPLER_VELOCITY) + .value("SINGLE", mrpt::obs::gnss::nv_oem6_position_type::SINGLE) + .value("PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::PSRDIFF) + .value("WAAS", mrpt::obs::gnss::nv_oem6_position_type::WAAS) + .value("PROPAGATED", mrpt::obs::gnss::nv_oem6_position_type::PROPAGATED) + .value("OMNISTAR", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR) + .value("L1_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::L1_FLOAT) + .value("IONOFREE_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::IONOFREE_FLOAT) + .value("NARROW_FLOAT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_FLOAT) + .value("L1_INT", mrpt::obs::gnss::nv_oem6_position_type::L1_INT) + .value("WIDE_INT", mrpt::obs::gnss::nv_oem6_position_type::WIDE_INT) + .value("NARROW_INT", mrpt::obs::gnss::nv_oem6_position_type::NARROW_INT) + .value("RTK_DIRECT_INS", mrpt::obs::gnss::nv_oem6_position_type::RTK_DIRECT_INS) + .value("INS", mrpt::obs::gnss::nv_oem6_position_type::INS) + .value("INS_PSRSP", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRSP) + .value("INS_PSRDIFF", mrpt::obs::gnss::nv_oem6_position_type::INS_PSRDIFF) + .value("INS_RTKFLOAT", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFLOAT) + .value("INS_RTKFIXED", mrpt::obs::gnss::nv_oem6_position_type::INS_RTKFIXED) + .value("OMNISTAR_HP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_HP) + .value("OMNISTAR_XP", mrpt::obs::gnss::nv_oem6_position_type::OMNISTAR_XP) + .value("CDGPS", mrpt::obs::gnss::nv_oem6_position_type::CDGPS) .export_values(); ; - // mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) file: line:170 - M("mrpt::obs::gnss::nv_oem6_solution_status").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_solution_status::enum2str, "for nv_solution_status_t \n\nC++: mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); + // mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) file: line:120 + M("mrpt::obs::gnss::nv_oem6_position_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_position_type::enum2str, "for nv_position_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_position_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); } diff --git a/python/generated-sources-pybind/unknown/unknown_4.cpp b/python/generated-sources-pybind/unknown/unknown_4.cpp index 12917630f1..f888ddd16e 100644 --- a/python/generated-sources-pybind/unknown/unknown_4.cpp +++ b/python/generated-sources-pybind/unknown/unknown_4.cpp @@ -18,21 +18,32 @@ void bind_unknown_unknown_4(std::function< pybind11::module &(std::string const &namespace_) > &M) { - // mrpt::obs::gnss::nv_oem6_ins_status_type::nv_ins_status_type_t file: line:175 - pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_ins_status_type"), "nv_ins_status_type_t", pybind11::arithmetic(), "Novatel SPAN on OEM6 firmware reference, table 33 ") - .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_INACTIVE) - .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNING) - .value("INS_HIGH_VARIANCE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_HIGH_VARIANCE) - .value("INS_SOLUTION_GOOD", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_GOOD) - .value("INS_SOLUTION_FREE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_FREE) - .value("INS_ALIGNMENT_COMPLETE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNMENT_COMPLETE) - .value("DETERMINING_ORIENTATION", mrpt::obs::gnss::nv_oem6_ins_status_type::DETERMINING_ORIENTATION) - .value("WAITING_INITIALPOS", mrpt::obs::gnss::nv_oem6_ins_status_type::WAITING_INITIALPOS) + // mrpt::obs::gnss::nv_oem6_solution_status::nv_solution_status_t file: line:126 + pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_solution_status"), "nv_solution_status_t", pybind11::arithmetic(), "Novatel OEM6 firmware reference, table 85 ") + .value("SOL_COMPUTED", mrpt::obs::gnss::nv_oem6_solution_status::SOL_COMPUTED) + .value("INSUFFICIENT_OBS", mrpt::obs::gnss::nv_oem6_solution_status::INSUFFICIENT_OBS) + .value("NO_CONVERGENCE", mrpt::obs::gnss::nv_oem6_solution_status::NO_CONVERGENCE) + .value("SINGULARITY", mrpt::obs::gnss::nv_oem6_solution_status::SINGULARITY) + .value("COV_TRACE", mrpt::obs::gnss::nv_oem6_solution_status::COV_TRACE) + .value("TEST_DIST", mrpt::obs::gnss::nv_oem6_solution_status::TEST_DIST) + .value("COLD_START", mrpt::obs::gnss::nv_oem6_solution_status::COLD_START) + .value("V_H_LIMIT", mrpt::obs::gnss::nv_oem6_solution_status::V_H_LIMIT) + .value("VARIANCE", mrpt::obs::gnss::nv_oem6_solution_status::VARIANCE) + .value("RESIDUALS", mrpt::obs::gnss::nv_oem6_solution_status::RESIDUALS) + .value("DELTA_POS", mrpt::obs::gnss::nv_oem6_solution_status::DELTA_POS) + .value("NEGATIVE_VAR", mrpt::obs::gnss::nv_oem6_solution_status::NEGATIVE_VAR) + .value("INTEGRITY_WARNING", mrpt::obs::gnss::nv_oem6_solution_status::INTEGRITY_WARNING) + .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_solution_status::INS_INACTIVE) + .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_solution_status::INS_ALIGNING) + .value("INS_BAD", mrpt::obs::gnss::nv_oem6_solution_status::INS_BAD) + .value("IMU_UNPLUGGED", mrpt::obs::gnss::nv_oem6_solution_status::IMU_UNPLUGGED) + .value("PENDING", mrpt::obs::gnss::nv_oem6_solution_status::PENDING) + .value("INVALID_FIX", mrpt::obs::gnss::nv_oem6_solution_status::INVALID_FIX) .export_values(); ; - // mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) file: line:198 - M("mrpt::obs::gnss::nv_oem6_ins_status_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str, "for nv_ins_status_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); + // mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) file: line:170 + M("mrpt::obs::gnss::nv_oem6_solution_status").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_solution_status::enum2str, "for nv_solution_status_t \n\nC++: mrpt::obs::gnss::nv_oem6_solution_status::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); } diff --git a/python/generated-sources-pybind/unknown/unknown_5.cpp b/python/generated-sources-pybind/unknown/unknown_5.cpp index c4fa51f236..ef17857269 100644 --- a/python/generated-sources-pybind/unknown/unknown_5.cpp +++ b/python/generated-sources-pybind/unknown/unknown_5.cpp @@ -1,16 +1,7 @@ -#include #include #include -#include -#include -#include -#include -#include -#include -#include // __str__ -#include +#include #include -#include #include #include @@ -25,408 +16,23 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME { - using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::Message_NV_OEM6_GENERIC_FRAME; - - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_FRAME::fixEndianness(); - } - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_FRAME::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_FRAME::internal_readFromStream(a0); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME { - using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::Message_NV_OEM6_GENERIC_SHORT_FRAME; - - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness(); - } - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_readFromStream(a0); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:150 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss::Message_NV_OEM6_BESTPOS { - using mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::Message_NV_OEM6_BESTPOS; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_BESTPOS::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_BESTPOS::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_BESTPOS::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:5 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss::Message_NV_OEM6_INSPVAS { - using mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::Message_NV_OEM6_INSPVAS; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_INSPVAS::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_INSPVAS::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_INSPVAS::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:11 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss::Message_NV_OEM6_INSCOVS { - using mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::Message_NV_OEM6_INSCOVS; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_INSCOVS::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_INSCOVS::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_INSCOVS::fixEndianness(); - } -}; - -// mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gnss::Message_NV_OEM6_RANGECMP { - using mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::Message_NV_OEM6_RANGECMP; - - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_RANGECMP::internal_writeToStream(a0); - } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); - if (overload) { - auto o = overload.operator()(a0); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return Message_NV_OEM6_RANGECMP::internal_readFromStream(a0); - } - void fixEndianness() override { - pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); - if (overload) { - auto o = overload.operator()(); - if (pybind11::detail::cast_is_temporary_value_reference::value) { - static pybind11::detail::override_caster_t caster; - return pybind11::detail::cast_ref(std::move(o), caster); - } - else return pybind11::detail::cast_safe(std::move(o)); - } - return gnss_message::fixEndianness(); - } -}; - void bind_unknown_unknown_5(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_FRAME", "Novatel generic frame (to store frames without a parser at the present\n time). \n\n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::header); - cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::msg_body); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_SHORT_FRAME", "Novatel generic short-header frame (to store frames without a parser at the\n present time). \n\n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::header); - cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::msg_body); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:150 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_BESTPOS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::header); - cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::solution_stat); - cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::position_type); - cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat); - cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon); - cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt); - cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::undulation); - cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::datum_id); - cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat_sigma); - cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon_sigma); - cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt_sigma); - cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::diff_age); - cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::sol_age); - cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_tracked); - cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol); - cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_L1); - cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_multi); - cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::reserved); - cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::ext_sol_stat); - cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::galileo_beidou_mask); - cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::gps_glonass_mask); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:5 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSPVAS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::week); - cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::seconds_in_week); - cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lat); - cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lon); - cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::hgt); - cl.def_readwrite("vel_north", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_north); - cl.def_readwrite("vel_east", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_east); - cl.def_readwrite("vel_up", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_up); - cl.def_readwrite("roll", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::roll); - cl.def_readwrite("pitch", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::pitch); - cl.def_readwrite("azimuth", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::azimuth); - cl.def_readwrite("ins_status", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::ins_status); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:11 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSCOVS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::week); - cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::seconds_in_week); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - - } - { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RANGECMP", "Novatel frame: NV_OEM6_RANGECMP. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RANGECMP const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::header); - cl.def_readwrite("num_obs", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::num_obs); - cl.def_readwrite("obs_data", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::obs_data); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP & (mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &)) &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog file: line:385 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "TCompressedRangeLog", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog(); } ) ); - } + // mrpt::obs::gnss::nv_oem6_ins_status_type::nv_ins_status_type_t file: line:175 + pybind11::enum_(M("mrpt::obs::gnss::nv_oem6_ins_status_type"), "nv_ins_status_type_t", pybind11::arithmetic(), "Novatel SPAN on OEM6 firmware reference, table 33 ") + .value("INS_INACTIVE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_INACTIVE) + .value("INS_ALIGNING", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNING) + .value("INS_HIGH_VARIANCE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_HIGH_VARIANCE) + .value("INS_SOLUTION_GOOD", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_GOOD) + .value("INS_SOLUTION_FREE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_SOLUTION_FREE) + .value("INS_ALIGNMENT_COMPLETE", mrpt::obs::gnss::nv_oem6_ins_status_type::INS_ALIGNMENT_COMPLETE) + .value("DETERMINING_ORIENTATION", mrpt::obs::gnss::nv_oem6_ins_status_type::DETERMINING_ORIENTATION) + .value("WAITING_INITIALPOS", mrpt::obs::gnss::nv_oem6_ins_status_type::WAITING_INITIALPOS) + .export_values(); + +; + + // mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) file: line:198 + M("mrpt::obs::gnss::nv_oem6_ins_status_type").def("enum2str", (const std::string & (*)(int)) &mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str, "for nv_ins_status_type_t \n\nC++: mrpt::obs::gnss::nv_oem6_ins_status_type::enum2str(int) --> const std::string &", pybind11::return_value_policy::automatic, pybind11::arg("val")); - } } diff --git a/python/generated-sources-pybind/unknown/unknown_6.cpp b/python/generated-sources-pybind/unknown/unknown_6.cpp index 7b06649f8f..aa8c004367 100644 --- a/python/generated-sources-pybind/unknown/unknown_6.cpp +++ b/python/generated-sources-pybind/unknown/unknown_6.cpp @@ -25,13 +25,26 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:17 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS { - using mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::Message_NV_OEM6_RXSTATUS; +// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME { + using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::Message_NV_OEM6_GENERIC_FRAME; + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_FRAME::fixEndianness(); + } void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -40,11 +53,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RXSTATUS::internal_writeToStream(a0); + return Message_NV_OEM6_GENERIC_FRAME::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -53,11 +66,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RXSTATUS::internal_readFromStream(a0); + return Message_NV_OEM6_GENERIC_FRAME::internal_readFromStream(a0); } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME : public mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME { + using mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::Message_NV_OEM6_GENERIC_SHORT_FRAME; + void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -66,17 +85,43 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RXSTATUS::fixEndianness(); + return Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness(); + } + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_GENERIC_SHORT_FRAME::internal_readFromStream(a0); } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:23 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM { - using mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::Message_NV_OEM6_RAWEPHEM; +// mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:150 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS : public mrpt::obs::gnss::Message_NV_OEM6_BESTPOS { + using mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::Message_NV_OEM6_BESTPOS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -85,11 +130,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWEPHEM::internal_writeToStream(a0); + return Message_NV_OEM6_BESTPOS::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -98,11 +143,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWEPHEM::internal_readFromStream(a0); + return Message_NV_OEM6_BESTPOS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -111,30 +156,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWEPHEM::fixEndianness(); + return Message_NV_OEM6_BESTPOS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss::Message_NV_OEM6_VERSION { - using mrpt::obs::gnss::Message_NV_OEM6_VERSION::Message_NV_OEM6_VERSION; +// mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:5 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS : public mrpt::obs::gnss::Message_NV_OEM6_INSPVAS { + using mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::Message_NV_OEM6_INSPVAS; - void fixEndianness() override { + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { - auto o = overload.operator()(); + auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_VERSION::fixEndianness(); + return Message_NV_OEM6_INSPVAS::internal_writeToStream(a0); } - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -143,30 +188,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_VERSION::internal_writeToStream(a0); + return Message_NV_OEM6_INSPVAS::internal_readFromStream(a0); } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { - auto o = overload.operator()(a0); + auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_VERSION::internal_readFromStream(a0); + return Message_NV_OEM6_INSPVAS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:29 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS { - using mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::Message_NV_OEM6_RAWIMUS; +// mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:11 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS : public mrpt::obs::gnss::Message_NV_OEM6_INSCOVS { + using mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::Message_NV_OEM6_INSCOVS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -175,11 +220,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWIMUS::internal_writeToStream(a0); + return Message_NV_OEM6_INSCOVS::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -188,11 +233,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWIMUS::internal_readFromStream(a0); + return Message_NV_OEM6_INSCOVS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -201,17 +246,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_RAWIMUS::fixEndianness(); + return Message_NV_OEM6_INSCOVS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:35 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss::Message_NV_OEM6_MARKPOS { - using mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::Message_NV_OEM6_MARKPOS; +// mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP : public mrpt::obs::gnss::Message_NV_OEM6_RANGECMP { + using mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::Message_NV_OEM6_RANGECMP; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -220,11 +265,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKPOS::internal_writeToStream(a0); + return Message_NV_OEM6_RANGECMP::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -233,11 +278,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKPOS::internal_readFromStream(a0); + return Message_NV_OEM6_RANGECMP::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -246,159 +291,141 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKPOS::fixEndianness(); + return gnss_message::fixEndianness(); } }; void bind_unknown_unknown_6(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:17 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RXSTATUS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t file: line:172 - auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::header); - cl.def_readwrite("error", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::error); - cl.def_readwrite("num_stats", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::num_stats); - cl.def_readwrite("rxstat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat); - cl.def_readwrite("rxstat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_pri); - cl.def_readwrite("rxstat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_set); - cl.def_readwrite("rxstat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_clear); - cl.def_readwrite("aux1stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat); - cl.def_readwrite("aux1stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_pri); - cl.def_readwrite("aux1stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_set); - cl.def_readwrite("aux1stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_clear); - cl.def_readwrite("aux2stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat); - cl.def_readwrite("aux2stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_pri); - cl.def_readwrite("aux2stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_set); - cl.def_readwrite("aux2stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_clear); - cl.def_readwrite("aux3stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat); - cl.def_readwrite("aux3stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_pri); - cl.def_readwrite("aux3stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_set); - cl.def_readwrite("aux3stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_clear); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - + { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME file: line:203 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_FRAME", "Novatel generic frame (to store frames without a parser at the present\n time). \n\n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_FRAME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::header); + cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::msg_body); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME file: line:224 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_GENERIC_SHORT_FRAME", "Novatel generic short-header frame (to store frames without a parser at the\n present time). \n\n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::header); + cl.def_readwrite("msg_body", &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::msg_body); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME & (mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &)) &mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_GENERIC_SHORT_FRAME &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:23 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWEPHEM", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS file: line:150 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_BESTPOS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_BESTPOS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t file: line:172 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::header); - cl.def_readwrite("sat_prn", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::sat_prn); - cl.def_readwrite("ref_week", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_week); - cl.def_readwrite("ref_secs", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_secs); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::header); + cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::solution_stat); + cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::position_type); + cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat); + cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon); + cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt); + cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::undulation); + cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::datum_id); + cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lat_sigma); + cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::lon_sigma); + cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::hgt_sigma); + cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::diff_age); + cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::sol_age); + cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_tracked); + cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol); + cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_L1); + cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::num_sats_sol_multi); + cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::reserved); + cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::ext_sol_stat); + cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::galileo_beidou_mask); + cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::gps_glonass_mask); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_BESTPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_VERSION", "Novatel frame: NV_OEM6_VERSION. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_VERSION const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::header); - cl.def_readwrite("num_comps", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::num_comps); - cl.def_readwrite("components", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::components); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::crc); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)()) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_VERSION & (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &)) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &) --> struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS file: line:5 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSPVAS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSPVAS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion file: line:468 + { // mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t file: line:172 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "TComponentVersion", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion(); } ) ); - cl.def_readwrite("type", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion::type); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::week); + cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::seconds_in_week); + cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lat); + cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::lon); + cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::hgt); + cl.def_readwrite("vel_north", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_north); + cl.def_readwrite("vel_east", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_east); + cl.def_readwrite("vel_up", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::vel_up); + cl.def_readwrite("roll", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::roll); + cl.def_readwrite("pitch", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::pitch); + cl.def_readwrite("azimuth", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::azimuth); + cl.def_readwrite("ins_status", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::ins_status); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSPVAS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:29 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWIMUS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS file: line:11 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_INSCOVS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_INSCOVS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t file: line:172 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week); - cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week_seconds); - cl.def_readwrite("imu_status", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::imu_status); - cl.def_readwrite("accel_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_z); - cl.def_readwrite("accel_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_y_neg); - cl.def_readwrite("accel_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_x); - cl.def_readwrite("gyro_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_z); - cl.def_readwrite("gyro_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_y_neg); - cl.def_readwrite("gyro_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_x); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::week); + cl.def_readwrite("seconds_in_week", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::seconds_in_week); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_INSCOVS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:35 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKPOS", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP file: line:379 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RANGECMP", "Novatel frame: NV_OEM6_RANGECMP. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RANGECMP(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RANGECMP const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::header); + cl.def_readwrite("num_obs", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::num_obs); + cl.def_readwrite("obs_data", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::obs_data); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP & (mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &)) &mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RANGECMP &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog file: line:385 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::header); - cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::solution_stat); - cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::position_type); - cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat); - cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon); - cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt); - cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::undulation); - cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::datum_id); - cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat_sigma); - cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon_sigma); - cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt_sigma); - cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::diff_age); - cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::sol_age); - cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_tracked); - cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol); - cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_L1); - cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_multi); - cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::reserved); - cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::ext_sol_stat); - cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::galileo_beidou_mask); - cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::gps_glonass_mask); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "TCompressedRangeLog", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RANGECMP::TCompressedRangeLog(); } ) ); } } diff --git a/python/generated-sources-pybind/unknown/unknown_7.cpp b/python/generated-sources-pybind/unknown/unknown_7.cpp index 47990d96e3..cda5bec602 100644 --- a/python/generated-sources-pybind/unknown/unknown_7.cpp +++ b/python/generated-sources-pybind/unknown/unknown_7.cpp @@ -25,13 +25,13 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:41 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gnss::Message_NV_OEM6_MARKTIME { - using mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::Message_NV_OEM6_MARKTIME; +// mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:17 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS : public mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS { + using mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::Message_NV_OEM6_RXSTATUS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -40,11 +40,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKTIME::internal_writeToStream(a0); + return Message_NV_OEM6_RXSTATUS::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -53,11 +53,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKTIME::internal_readFromStream(a0); + return Message_NV_OEM6_RXSTATUS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -66,17 +66,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gns } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARKTIME::fixEndianness(); + return Message_NV_OEM6_RXSTATUS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:47 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME { - using mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::Message_NV_OEM6_MARK2TIME; +// mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:23 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM : public mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM { + using mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::Message_NV_OEM6_RAWEPHEM; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -85,11 +85,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gn } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARK2TIME::internal_writeToStream(a0); + return Message_NV_OEM6_RAWEPHEM::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -98,11 +98,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gn } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARK2TIME::internal_readFromStream(a0); + return Message_NV_OEM6_RAWEPHEM::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -111,30 +111,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gn } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_MARK2TIME::fixEndianness(); + return Message_NV_OEM6_RAWEPHEM::fixEndianness(); } }; -// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:53 -struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss::Message_NV_OEM6_IONUTC { - using mrpt::obs::gnss::Message_NV_OEM6_IONUTC::Message_NV_OEM6_IONUTC; +// mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION : public mrpt::obs::gnss::Message_NV_OEM6_VERSION { + using mrpt::obs::gnss::Message_NV_OEM6_VERSION::Message_NV_OEM6_VERSION; - void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { - auto o = overload.operator()(a0); + auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_IONUTC::internal_writeToStream(a0); + return Message_NV_OEM6_VERSION::fixEndianness(); } - void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -143,30 +143,30 @@ struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss: } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_IONUTC::internal_readFromStream(a0); + return Message_NV_OEM6_VERSION::internal_writeToStream(a0); } - void fixEndianness() override { + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { - auto o = overload.operator()(); + auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { static pybind11::detail::override_caster_t caster; return pybind11::detail::cast_ref(std::move(o), caster); } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_NV_OEM6_IONUTC::fixEndianness(); + return Message_NV_OEM6_VERSION::internal_readFromStream(a0); } }; -// mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 -struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Message_TOPCON_PZS { - using mrpt::obs::gnss::Message_TOPCON_PZS::Message_TOPCON_PZS; +// mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:29 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS : public mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS { + using mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::Message_NV_OEM6_RAWIMUS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -175,11 +175,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Mes } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_TOPCON_PZS::internal_writeToStream(a0); + return Message_NV_OEM6_RAWIMUS::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -188,11 +188,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Mes } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_TOPCON_PZS::internal_readFromStream(a0); + return Message_NV_OEM6_RAWIMUS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -201,17 +201,17 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Mes } else return pybind11::detail::cast_safe(std::move(o)); } - return gnss_message::fixEndianness(); + return Message_NV_OEM6_RAWIMUS::fixEndianness(); } }; -// mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 -struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Message_TOPCON_SATS { - using mrpt::obs::gnss::Message_TOPCON_SATS::Message_TOPCON_SATS; +// mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:35 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS : public mrpt::obs::gnss::Message_NV_OEM6_MARKPOS { + using mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::Message_NV_OEM6_MARKPOS; void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -220,11 +220,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Me } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_TOPCON_SATS::internal_writeToStream(a0); + return Message_NV_OEM6_MARKPOS::internal_writeToStream(a0); } void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); if (overload) { auto o = overload.operator()(a0); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -233,11 +233,11 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Me } else return pybind11::detail::cast_safe(std::move(o)); } - return Message_TOPCON_SATS::internal_readFromStream(a0); + return Message_NV_OEM6_MARKPOS::internal_readFromStream(a0); } void fixEndianness() override { pybind11::gil_scoped_acquire gil; - pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); if (overload) { auto o = overload.operator()(); if (pybind11::detail::cast_is_temporary_value_reference::value) { @@ -246,142 +246,160 @@ struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Me } else return pybind11::detail::cast_safe(std::move(o)); } - return gnss_message::fixEndianness(); + return Message_NV_OEM6_MARKPOS::fixEndianness(); } }; void bind_unknown_unknown_7(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:41 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKTIME", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS file: line:17 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RXSTATUS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RXSTATUS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t file: line:172 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week); - cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week_seconds); - cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset); - cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset_std); - cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::utc_offset); - cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_status); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::header); + cl.def_readwrite("error", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::error); + cl.def_readwrite("num_stats", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::num_stats); + cl.def_readwrite("rxstat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat); + cl.def_readwrite("rxstat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_pri); + cl.def_readwrite("rxstat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_set); + cl.def_readwrite("rxstat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::rxstat_clear); + cl.def_readwrite("aux1stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat); + cl.def_readwrite("aux1stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_pri); + cl.def_readwrite("aux1stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_set); + cl.def_readwrite("aux1stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux1stat_clear); + cl.def_readwrite("aux2stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat); + cl.def_readwrite("aux2stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_pri); + cl.def_readwrite("aux2stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_set); + cl.def_readwrite("aux2stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux2stat_clear); + cl.def_readwrite("aux3stat", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat); + cl.def_readwrite("aux3stat_pri", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_pri); + cl.def_readwrite("aux3stat_set", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_set); + cl.def_readwrite("aux3stat_clear", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::aux3stat_clear); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RXSTATUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:47 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARK2TIME", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM file: line:23 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWEPHEM", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWEPHEM(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t file: line:172 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::header); - cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week); - cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week_seconds); - cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset); - cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset_std); - cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::utc_offset); - cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_status); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::header); + cl.def_readwrite("sat_prn", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::sat_prn); + cl.def_readwrite("ref_week", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_week); + cl.def_readwrite("ref_secs", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::ref_secs); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWEPHEM::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } - { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:53 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_IONUTC", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(o); } ) ); - cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fields); - cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)()) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness() --> void"); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_VERSION file: line:462 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_VERSION", "Novatel frame: NV_OEM6_VERSION. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_VERSION(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_VERSION const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::header); + cl.def_readwrite("num_comps", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::num_comps); + cl.def_readwrite("components", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::components); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::crc); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)()) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_VERSION & (mrpt::obs::gnss::Message_NV_OEM6_VERSION::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &)) &mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_VERSION::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &) --> struct mrpt::obs::gnss::Message_NV_OEM6_VERSION &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t file: line:172 + { // mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion file: line:468 auto & enclosing_class = cl; - pybind11::class_> cl(enclosing_class, "content_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(o); } ) ); - cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::header); - cl.def_readwrite("a0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a0); - cl.def_readwrite("a1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a1); - cl.def_readwrite("a2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a2); - cl.def_readwrite("a3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a3); - cl.def_readwrite("b0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b0); - cl.def_readwrite("b1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b1); - cl.def_readwrite("b2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b2); - cl.def_readwrite("b3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b3); - cl.def_readwrite("utc_wn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::utc_wn); - cl.def_readwrite("tot", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::tot); - cl.def_readwrite("A0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A0); - cl.def_readwrite("A1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A1); - cl.def_readwrite("wn_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::wn_lsf); - cl.def_readwrite("dn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::dn); - cl.def_readwrite("deltat_ls", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_ls); - cl.def_readwrite("deltat_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_lsf); - cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::reserved); - cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::crc); - cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + pybind11::class_> cl(enclosing_class, "TComponentVersion", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion(); } ) ); + cl.def_readwrite("type", &mrpt::obs::gnss::Message_NV_OEM6_VERSION::TComponentVersion::type); } } - { // mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_PZS", "GPS datum for TopCon's mmGPS devices: PZS. \n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_PZS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_PZS const &o){ return new mrpt::obs::gnss::Message_TOPCON_PZS(o); } ) ); - cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::latitude_degrees); - cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::longitude_degrees); - cl.def_readwrite("height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::height_meters); - cl.def_readwrite("RTK_height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::RTK_height_meters); - cl.def_readwrite("PSigma", &mrpt::obs::gnss::Message_TOPCON_PZS::PSigma); - cl.def_readwrite("angle_transmitter", &mrpt::obs::gnss::Message_TOPCON_PZS::angle_transmitter); - cl.def_readwrite("nId", &mrpt::obs::gnss::Message_TOPCON_PZS::nId); - cl.def_readwrite("Fix", &mrpt::obs::gnss::Message_TOPCON_PZS::Fix); - cl.def_readwrite("TXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::TXBattery); - cl.def_readwrite("RXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::RXBattery); - cl.def_readwrite("error", &mrpt::obs::gnss::Message_TOPCON_PZS::error); - cl.def_readwrite("hasCartesianPosVel", &mrpt::obs::gnss::Message_TOPCON_PZS::hasCartesianPosVel); - cl.def_readwrite("cartesian_x", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_x); - cl.def_readwrite("cartesian_y", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_y); - cl.def_readwrite("cartesian_z", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_z); - cl.def_readwrite("cartesian_vx", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vx); - cl.def_readwrite("cartesian_vy", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vy); - cl.def_readwrite("cartesian_vz", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vz); - cl.def_readwrite("hasPosCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasPosCov); - cl.def_readwrite("pos_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::pos_covariance); - cl.def_readwrite("hasVelCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasVelCov); - cl.def_readwrite("vel_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::vel_covariance); - cl.def_readwrite("hasStats", &mrpt::obs::gnss::Message_TOPCON_PZS::hasStats); - cl.def_readwrite("stats_GPS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GPS_sats_used); - cl.def_readwrite("stats_GLONASS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GLONASS_sats_used); - cl.def_readwrite("stats_rtk_fix_progress", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_rtk_fix_progress); - cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_PZS & (mrpt::obs::gnss::Message_TOPCON_PZS::*)(const struct mrpt::obs::gnss::Message_TOPCON_PZS &)) &mrpt::obs::gnss::Message_TOPCON_PZS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_PZS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_PZS &) --> struct mrpt::obs::gnss::Message_TOPCON_PZS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS file: line:29 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_RAWIMUS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_RAWIMUS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t file: line:172 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week); + cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::week_seconds); + cl.def_readwrite("imu_status", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::imu_status); + cl.def_readwrite("accel_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_z); + cl.def_readwrite("accel_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_y_neg); + cl.def_readwrite("accel_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::accel_x); + cl.def_readwrite("gyro_z", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_z); + cl.def_readwrite("gyro_y_neg", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_y_neg); + cl.def_readwrite("gyro_x", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::gyro_x); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_RAWIMUS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + } - { // mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 - pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_SATS", "TopCon mmGPS devices: SATS, a generic structure for statistics about tracked\n satelites and their positions. \n\n mrpt::obs::CObservationGPS "); - cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_SATS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(); } ) ); - cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(o); } ) ); - cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_SATS const &o){ return new mrpt::obs::gnss::Message_TOPCON_SATS(o); } ) ); - cl.def_readwrite("USIs", &mrpt::obs::gnss::Message_TOPCON_SATS::USIs); - cl.def_readwrite("ELs", &mrpt::obs::gnss::Message_TOPCON_SATS::ELs); - cl.def_readwrite("AZs", &mrpt::obs::gnss::Message_TOPCON_SATS::AZs); - cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_SATS & (mrpt::obs::gnss::Message_TOPCON_SATS::*)(const struct mrpt::obs::gnss::Message_TOPCON_SATS &)) &mrpt::obs::gnss::Message_TOPCON_SATS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_SATS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_SATS &) --> struct mrpt::obs::gnss::Message_TOPCON_SATS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS file: line:35 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKPOS", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKPOS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t file: line:172 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::header); + cl.def_readwrite("solution_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::solution_stat); + cl.def_readwrite("position_type", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::position_type); + cl.def_readwrite("lat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat); + cl.def_readwrite("lon", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon); + cl.def_readwrite("hgt", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt); + cl.def_readwrite("undulation", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::undulation); + cl.def_readwrite("datum_id", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::datum_id); + cl.def_readwrite("lat_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lat_sigma); + cl.def_readwrite("lon_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::lon_sigma); + cl.def_readwrite("hgt_sigma", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::hgt_sigma); + cl.def_readwrite("diff_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::diff_age); + cl.def_readwrite("sol_age", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::sol_age); + cl.def_readwrite("num_sats_tracked", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_tracked); + cl.def_readwrite("num_sats_sol", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol); + cl.def_readwrite("num_sats_sol_L1", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_L1); + cl.def_readwrite("num_sats_sol_multi", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::num_sats_sol_multi); + cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::reserved); + cl.def_readwrite("ext_sol_stat", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::ext_sol_stat); + cl.def_readwrite("galileo_beidou_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::galileo_beidou_mask); + cl.def_readwrite("gps_glonass_mask", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::gps_glonass_mask); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKPOS::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + } } diff --git a/python/generated-sources-pybind/unknown/unknown_8.cpp b/python/generated-sources-pybind/unknown/unknown_8.cpp new file mode 100644 index 0000000000..ac47575fa8 --- /dev/null +++ b/python/generated-sources-pybind/unknown/unknown_8.cpp @@ -0,0 +1,387 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include // __str__ +#include +#include +#include + +#include +#include +#include +#include + + +#ifndef BINDER_PYBIND11_TYPE_CASTER + #define BINDER_PYBIND11_TYPE_CASTER + PYBIND11_DECLARE_HOLDER_TYPE(T, std::shared_ptr) + PYBIND11_DECLARE_HOLDER_TYPE(T, T*) + PYBIND11_MAKE_OPAQUE(std::shared_ptr) +#endif + +// mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:41 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME : public mrpt::obs::gnss::Message_NV_OEM6_MARKTIME { + using mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::Message_NV_OEM6_MARKTIME; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_MARKTIME::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_MARKTIME::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_MARKTIME::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:47 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME : public mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME { + using mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::Message_NV_OEM6_MARK2TIME; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_MARK2TIME::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_MARK2TIME::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_MARK2TIME::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:53 +struct PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC : public mrpt::obs::gnss::Message_NV_OEM6_IONUTC { + using mrpt::obs::gnss::Message_NV_OEM6_IONUTC::Message_NV_OEM6_IONUTC; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_IONUTC::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_IONUTC::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_NV_OEM6_IONUTC::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 +struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS : public mrpt::obs::gnss::Message_TOPCON_PZS { + using mrpt::obs::gnss::Message_TOPCON_PZS::Message_TOPCON_PZS; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_TOPCON_PZS::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_TOPCON_PZS::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + +// mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 +struct PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS : public mrpt::obs::gnss::Message_TOPCON_SATS { + using mrpt::obs::gnss::Message_TOPCON_SATS::Message_TOPCON_SATS; + + void internal_writeToStream(class mrpt::serialization::CArchive & a0) const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_writeToStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_TOPCON_SATS::internal_writeToStream(a0); + } + void internal_readFromStream(class mrpt::serialization::CArchive & a0) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "internal_readFromStream"); + if (overload) { + auto o = overload.operator()(a0); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return Message_TOPCON_SATS::internal_readFromStream(a0); + } + void fixEndianness() override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "fixEndianness"); + if (overload) { + auto o = overload.operator()(); + if (pybind11::detail::cast_is_temporary_value_reference::value) { + static pybind11::detail::override_caster_t caster; + return pybind11::detail::cast_ref(std::move(o), caster); + } + else return pybind11::detail::cast_safe(std::move(o)); + } + return gnss_message::fixEndianness(); + } +}; + +void bind_unknown_unknown_8(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME file: line:41 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARKTIME", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARKTIME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t file: line:172 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week); + cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::week_seconds); + cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset); + cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_offset_std); + cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::utc_offset); + cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::clock_status); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARKTIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME file: line:47 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_MARK2TIME", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_MARK2TIME(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)()) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t file: line:172 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::header); + cl.def_readwrite("week", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week); + cl.def_readwrite("week_seconds", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::week_seconds); + cl.def_readwrite("clock_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset); + cl.def_readwrite("clock_offset_std", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_offset_std); + cl.def_readwrite("utc_offset", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::utc_offset); + cl.def_readwrite("clock_status", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::clock_status); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t & (mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_MARK2TIME::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC file: line:53 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_NV_OEM6_IONUTC", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC const &o){ return new PyCallBack_mrpt_obs_gnss_Message_NV_OEM6_IONUTC(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC(o); } ) ); + cl.def_readwrite("fields", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fields); + cl.def("fixEndianness", (void (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)()) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::fixEndianness() --> void"); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + { // mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t file: line:172 + auto & enclosing_class = cl; + pybind11::class_> cl(enclosing_class, "content_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t const &o){ return new mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t(o); } ) ); + cl.def_readwrite("header", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::header); + cl.def_readwrite("a0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a0); + cl.def_readwrite("a1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a1); + cl.def_readwrite("a2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a2); + cl.def_readwrite("a3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::a3); + cl.def_readwrite("b0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b0); + cl.def_readwrite("b1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b1); + cl.def_readwrite("b2", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b2); + cl.def_readwrite("b3", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::b3); + cl.def_readwrite("utc_wn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::utc_wn); + cl.def_readwrite("tot", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::tot); + cl.def_readwrite("A0", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A0); + cl.def_readwrite("A1", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::A1); + cl.def_readwrite("wn_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::wn_lsf); + cl.def_readwrite("dn", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::dn); + cl.def_readwrite("deltat_ls", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_ls); + cl.def_readwrite("deltat_lsf", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::deltat_lsf); + cl.def_readwrite("reserved", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::reserved); + cl.def_readwrite("crc", &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::crc); + cl.def("assign", (struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t & (mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::*)(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &)) &mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=, "C++: mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t::operator=(const struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &) --> struct mrpt::obs::gnss::Message_NV_OEM6_IONUTC::content_t &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + + } + { // mrpt::obs::gnss::Message_TOPCON_PZS file: line:18 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_PZS", "GPS datum for TopCon's mmGPS devices: PZS. \n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_PZS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_PZS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_PZS const &o){ return new mrpt::obs::gnss::Message_TOPCON_PZS(o); } ) ); + cl.def_readwrite("latitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::latitude_degrees); + cl.def_readwrite("longitude_degrees", &mrpt::obs::gnss::Message_TOPCON_PZS::longitude_degrees); + cl.def_readwrite("height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::height_meters); + cl.def_readwrite("RTK_height_meters", &mrpt::obs::gnss::Message_TOPCON_PZS::RTK_height_meters); + cl.def_readwrite("PSigma", &mrpt::obs::gnss::Message_TOPCON_PZS::PSigma); + cl.def_readwrite("angle_transmitter", &mrpt::obs::gnss::Message_TOPCON_PZS::angle_transmitter); + cl.def_readwrite("nId", &mrpt::obs::gnss::Message_TOPCON_PZS::nId); + cl.def_readwrite("Fix", &mrpt::obs::gnss::Message_TOPCON_PZS::Fix); + cl.def_readwrite("TXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::TXBattery); + cl.def_readwrite("RXBattery", &mrpt::obs::gnss::Message_TOPCON_PZS::RXBattery); + cl.def_readwrite("error", &mrpt::obs::gnss::Message_TOPCON_PZS::error); + cl.def_readwrite("hasCartesianPosVel", &mrpt::obs::gnss::Message_TOPCON_PZS::hasCartesianPosVel); + cl.def_readwrite("cartesian_x", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_x); + cl.def_readwrite("cartesian_y", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_y); + cl.def_readwrite("cartesian_z", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_z); + cl.def_readwrite("cartesian_vx", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vx); + cl.def_readwrite("cartesian_vy", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vy); + cl.def_readwrite("cartesian_vz", &mrpt::obs::gnss::Message_TOPCON_PZS::cartesian_vz); + cl.def_readwrite("hasPosCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasPosCov); + cl.def_readwrite("pos_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::pos_covariance); + cl.def_readwrite("hasVelCov", &mrpt::obs::gnss::Message_TOPCON_PZS::hasVelCov); + cl.def_readwrite("vel_covariance", &mrpt::obs::gnss::Message_TOPCON_PZS::vel_covariance); + cl.def_readwrite("hasStats", &mrpt::obs::gnss::Message_TOPCON_PZS::hasStats); + cl.def_readwrite("stats_GPS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GPS_sats_used); + cl.def_readwrite("stats_GLONASS_sats_used", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_GLONASS_sats_used); + cl.def_readwrite("stats_rtk_fix_progress", &mrpt::obs::gnss::Message_TOPCON_PZS::stats_rtk_fix_progress); + cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_PZS & (mrpt::obs::gnss::Message_TOPCON_PZS::*)(const struct mrpt::obs::gnss::Message_TOPCON_PZS &)) &mrpt::obs::gnss::Message_TOPCON_PZS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_PZS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_PZS &) --> struct mrpt::obs::gnss::Message_TOPCON_PZS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::obs::gnss::Message_TOPCON_SATS file: line:90 + pybind11::class_, PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS, mrpt::obs::gnss::gnss_message> cl(M("mrpt::obs::gnss"), "Message_TOPCON_SATS", "TopCon mmGPS devices: SATS, a generic structure for statistics about tracked\n satelites and their positions. \n\n mrpt::obs::CObservationGPS "); + cl.def( pybind11::init( [](){ return new mrpt::obs::gnss::Message_TOPCON_SATS(); }, [](){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(); } ) ); + cl.def( pybind11::init( [](PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS const &o){ return new PyCallBack_mrpt_obs_gnss_Message_TOPCON_SATS(o); } ) ); + cl.def( pybind11::init( [](mrpt::obs::gnss::Message_TOPCON_SATS const &o){ return new mrpt::obs::gnss::Message_TOPCON_SATS(o); } ) ); + cl.def_readwrite("USIs", &mrpt::obs::gnss::Message_TOPCON_SATS::USIs); + cl.def_readwrite("ELs", &mrpt::obs::gnss::Message_TOPCON_SATS::ELs); + cl.def_readwrite("AZs", &mrpt::obs::gnss::Message_TOPCON_SATS::AZs); + cl.def("assign", (struct mrpt::obs::gnss::Message_TOPCON_SATS & (mrpt::obs::gnss::Message_TOPCON_SATS::*)(const struct mrpt::obs::gnss::Message_TOPCON_SATS &)) &mrpt::obs::gnss::Message_TOPCON_SATS::operator=, "C++: mrpt::obs::gnss::Message_TOPCON_SATS::operator=(const struct mrpt::obs::gnss::Message_TOPCON_SATS &) --> struct mrpt::obs::gnss::Message_TOPCON_SATS &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/serialization-python-instances.h b/python/serialization-python-instances.h new file mode 100644 index 0000000000..4fccf59829 --- /dev/null +++ b/python/serialization-python-instances.h @@ -0,0 +1,37 @@ +#pragma once + +#include +#include +#include +#include +#include + +namespace mrpt +{ +namespace serialization +{ + +// Manual instantiations: pybind11 / binder do not generate this automatically: +inline CArchiveStreamBase archiveFrom(mrpt::io::CFileGZInputStream& s) +{ + return CArchiveStreamBase(s); +} + +inline CArchiveStreamBase archiveFrom(mrpt::io::CFileGZOutputStream& s) +{ + return CArchiveStreamBase(s); +} + +inline CArchiveStreamBase archiveFrom(mrpt::io::CFileInputStream& s) +{ + return CArchiveStreamBase(s); +} + +inline CArchiveStreamBase archiveFrom(mrpt::io::CFileOutputStream& s) +{ + return CArchiveStreamBase(s); +} + + +} +} \ No newline at end of file