diff --git a/apps/SceneViewer3D/_DSceneViewerMain.cpp b/apps/SceneViewer3D/_DSceneViewerMain.cpp index 8556673ce4..0e571cad18 100644 --- a/apps/SceneViewer3D/_DSceneViewerMain.cpp +++ b/apps/SceneViewer3D/_DSceneViewerMain.cpp @@ -320,6 +320,7 @@ const long _DSceneViewerFrame::ID_BUTTON5 = wxNewId(); const long _DSceneViewerFrame::ID_STATICLINE2 = wxNewId(); const long _DSceneViewerFrame::ID_BUTTON6 = wxNewId(); const long _DSceneViewerFrame::ID_BUTTON7 = wxNewId(); +const long _DSceneViewerFrame::ID_BUTTON_SHADOWS = wxNewId(); const long _DSceneViewerFrame::ID_BUTTON8 = wxNewId(); const long _DSceneViewerFrame::ID_BUTTON9 = wxNewId(); const long _DSceneViewerFrame::ID_STATICLINE3 = wxNewId(); @@ -480,6 +481,17 @@ _DSceneViewerFrame::_DSceneViewerFrame(wxWindow* parent, wxWindowID id) : maxv(0 wxArtProvider::GetBitmap(wxART_MAKE_ART_ID_FROM_STR(_T("wxART_TICK_MARK")), wxART_TOOLBAR)); btnOrtho->SetMargins(wxSize(5, 5)); FlexGridSizer2->Add(btnOrtho, 1, wxEXPAND, 1); + + btnShadows = new wxCustomButton( + this, ID_BUTTON_SHADOWS, _(" Shadows "), + wxArtProvider::GetBitmap(wxART_MAKE_ART_ID_FROM_STR(_T("wxART_TICK_MARK")), wxART_TOOLBAR), + wxDefaultPosition, wxDefaultSize, wxCUSTBUT_TOGGLE | wxCUSTBUT_BOTTOM, wxDefaultValidator, + _T("ID_BUTTON_SHADOWS")); + btnShadows->SetBitmapDisabled( + wxArtProvider::GetBitmap(wxART_MAKE_ART_ID_FROM_STR(_T("wxART_TICK_MARK")), wxART_TOOLBAR)); + btnShadows->SetMargins(wxSize(5, 5)); + FlexGridSizer2->Add(btnShadows, 1, wxEXPAND, 1); + btnAutoplay = new wxCustomButton( this, ID_BUTTON8, _(" Autoplay "), wxArtProvider::GetBitmap(wxART_MAKE_ART_ID_FROM_STR(_T("wxART_REMOVABLE")), wxART_TOOLBAR), @@ -657,6 +669,7 @@ _DSceneViewerFrame::_DSceneViewerFrame(wxWindow* parent, wxWindowID id) : maxv(0 Bind(wxEVT_BUTTON, &svf::OnReload, this, ID_BUTTON5); Bind(wxEVT_BUTTON, &svf::OnMenuOptions, this, ID_BUTTON6); Bind(wxEVT_COMMAND_TOGGLEBUTTON_CLICKED, &svf::OnbtnOrthoClicked, this, ID_BUTTON7); + Bind(wxEVT_COMMAND_TOGGLEBUTTON_CLICKED, &svf::OnbtnShadowsClicked, this, ID_BUTTON_SHADOWS); Bind(wxEVT_COMMAND_TOGGLEBUTTON_CLICKED, &svf::OnbtnAutoplayClicked, this, ID_BUTTON8); Bind(wxEVT_COMMAND_TOGGLEBUTTON_CLICKED, &svf::OnBtnRecordClicked, this, ID_BUTTON9); Bind(wxEVT_BUTTON, &svf::OnAbout, this, ID_BUTTON10); @@ -891,34 +904,39 @@ void _DSceneViewerFrame::OntimLoadFileCmdLineTrigger(wxTimerEvent&) { timLoadFileCmdLine.Stop(); // One shot only. // Open file if passed by the command line: - if (!global_fileToOpen.empty()) + if (global_fileToOpen.empty()) return; + + if (mrpt::system::strCmpI( + "3Dscene", mrpt::system::extractFileExtension(global_fileToOpen, true /*ignore .gz*/))) { - if (mrpt::system::strCmpI( - "3Dscene", mrpt::system::extractFileExtension(global_fileToOpen, true /*ignore .gz*/))) + loadFromFile(global_fileToOpen); + } + else + { + std::cout << "Filename extension does not match `3Dscene`, " + "importing as an ASSIMP model...\n"; + try { - loadFromFile(global_fileToOpen); + auto obj3D = mrpt::opengl::CAssimpModel::Create(); + obj3D->loadScene(global_fileToOpen); + // obj3D->setPose(mrpt::math::TPose3D(0, 0, 0, .0_deg, + // 0._deg, 90.0_deg)); + m_canvas->getOpenGLSceneRef()->insert(obj3D); + + // TODO: make optional? + obj3D->split_triangles_rendering_bbox(0.25); + + m_canvas->Refresh(); } - else + catch (const std::exception& e) { - std::cout << "Filename extension does not match `3Dscene`, " - "importing as an ASSIMP model...\n"; - try - { - auto obj3D = mrpt::opengl::CAssimpModel::Create(); - obj3D->loadScene(global_fileToOpen); - // obj3D->setPose(mrpt::math::TPose3D(0, 0, 0, .0_deg, - // 0._deg, 90.0_deg)); - m_canvas->getOpenGLSceneRef()->insert(obj3D); - - m_canvas->Refresh(); - } - catch (const std::exception& e) - { - std::cerr << mrpt::exception_to_str(e) << std::endl; - wxMessageBox(mrpt::exception_to_str(e), _("Exception"), wxOK, this); - } + std::cerr << mrpt::exception_to_str(e) << std::endl; + wxMessageBox(mrpt::exception_to_str(e), _("Exception"), wxOK, this); } } + + // Enable shadows? + applyShadowsOptions(); } void _DSceneViewerFrame::OnbtnAutoplayClicked(wxCommandEvent& event) @@ -1037,6 +1055,24 @@ void _DSceneViewerFrame::OnbtnOrthoClicked(wxCommandEvent& event) m_canvas->Refresh(false); } +void _DSceneViewerFrame::OnbtnShadowsClicked(wxCommandEvent& event) +{ + applyShadowsOptions(); + m_canvas->Refresh(false); +} + +void _DSceneViewerFrame::applyShadowsOptions() +{ + bool shadowsEnabled = btnShadows->GetValue(); + auto scene = m_canvas->getOpenGLSceneRef(); + if (!scene) return; + + auto vw = scene->getViewport(); + if (!vw) return; + + vw->enableShadowCasting(shadowsEnabled); +} + void _DSceneViewerFrame::OnReload(wxCommandEvent& event) { if (fileExists(loadedFileName)) loadFromFile(loadedFileName); diff --git a/apps/SceneViewer3D/_DSceneViewerMain.h b/apps/SceneViewer3D/_DSceneViewerMain.h index 3fc110ab8a..23dfae6d9d 100644 --- a/apps/SceneViewer3D/_DSceneViewerMain.h +++ b/apps/SceneViewer3D/_DSceneViewerMain.h @@ -76,6 +76,7 @@ class _DSceneViewerFrame : public wxFrame void OnClose(wxCloseEvent& event); void OnBtnRecordClicked(wxCommandEvent& event); void OnbtnOrthoClicked(wxCommandEvent& event); + void OnbtnShadowsClicked(wxCommandEvent& event); void OnReload(wxCommandEvent& event); void OnInsert3DS(wxCommandEvent& event); void OnMenuSave(wxCommandEvent& event); @@ -104,6 +105,8 @@ class _DSceneViewerFrame : public wxFrame void OntimAutoplay(wxTimerEvent& event); + void applyShadowsOptions(); + //(*Identifiers(_DSceneViewerFrame) static const long ID_BUTTON1; static const long ID_BUTTON2; @@ -114,6 +117,7 @@ class _DSceneViewerFrame : public wxFrame static const long ID_STATICLINE2; static const long ID_BUTTON6; static const long ID_BUTTON7; + static const long ID_BUTTON_SHADOWS; static const long ID_BUTTON8; static const long ID_BUTTON9; static const long ID_STATICLINE3; @@ -187,6 +191,7 @@ class _DSceneViewerFrame : public wxFrame wxMenuItem* mnuSelectionScale; wxMenuItem* mnuImportLAS; wxCustomButton* btnOrtho; + wxCustomButton* btnShadows; wxStatusBar* StatusBar1; wxMenuItem* MenuItem6; wxStaticLine* StaticLine3; diff --git a/appveyor.yml b/appveyor.yml index 89a4f73fd7..47c724b195 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 2.14.0-{branch}-build{build} +version: 2.14.1-{branch}-build{build} os: Visual Studio 2019 diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 2c7c66dc99..10e8b54790 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,5 +1,16 @@ \page changelog Change Log +# Version 2.14.1: Released Sep 24th, 2024 +- Changes in apps: + - SceneViewer3D: New button to enable shadow casting. +- Changes in libraries: + - \ref mrpt_opengl_grp: + - New method mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox() to enable a new feature in Assimp 3D models: splitting into smaller triangle sets for correct z-ordering of semitransparent objects; e.g. required for trees with masked leaves. + - SkyBox shader changed its internal ID so it gets rendered before potentially transparent elements, fixing render artifacts. + - mrpt::opengl::Texture: Wrapped OpenGL options for texture coordinate wrapping. + - \ref mrpt_ros2bridge_grp: + - Handle PointCloud2 with uint32 timestamps, interpreted as nanoseconds. + # Version 2.14.0: Released Sep 15th, 2024 - Changes in libraries: - \ref mrpt_slam_grp: diff --git a/libs/maps/include/mrpt/maps/CVoxelMapBase.h b/libs/maps/include/mrpt/maps/CVoxelMapBase.h index 4397d762d6..2d06443659 100644 --- a/libs/maps/include/mrpt/maps/CVoxelMapBase.h +++ b/libs/maps/include/mrpt/maps/CVoxelMapBase.h @@ -10,6 +10,8 @@ #pragma once #include +#include // required by pymrpt +#include // required by pymrpt #include #include #include diff --git a/libs/opengl/include/mrpt/opengl/CAssimpModel.h b/libs/opengl/include/mrpt/opengl/CAssimpModel.h index a5e1c1f0bd..b5b9d68e79 100644 --- a/libs/opengl/include/mrpt/opengl/CAssimpModel.h +++ b/libs/opengl/include/mrpt/opengl/CAssimpModel.h @@ -120,6 +120,16 @@ class CAssimpModel : mrpt::math::TBoundingBoxf internalBoundingBoxLocal() const override; + /** Enable (or disable if set to .0f) a feature in which textured triangles + * are split into different renderizable smaller objects. + * This is required only for semitransparent objects with overlaping regions. + */ + void split_triangles_rendering_bbox(const float bbox_size); + [[nodiscard]] float split_triangles_rendering_bbox() const + { + return m_split_triangles_rendering_bbox; + } + struct TInfoPerTexture { // indices in \a m_texturedObjects. string::npos for non-initialized @@ -152,6 +162,7 @@ class CAssimpModel : mutable std::vector m_texturedObjects; bool m_verboseLoad = false; bool m_ignoreMaterialColor = false; + float m_split_triangles_rendering_bbox = .0f; void recursive_render( const aiScene* sc, diff --git a/libs/opengl/include/mrpt/opengl/DefaultShaders.h b/libs/opengl/include/mrpt/opengl/DefaultShaders.h index e42d9a05ab..1e77a53b21 100644 --- a/libs/opengl/include/mrpt/opengl/DefaultShaders.h +++ b/libs/opengl/include/mrpt/opengl/DefaultShaders.h @@ -26,19 +26,19 @@ struct DefaultShaderID static constexpr shader_id_t POINTS = 0; static constexpr shader_id_t WIREFRAME = 1; static constexpr shader_id_t TEXT = 2; - static constexpr shader_id_t TRIANGLES_LIGHT = 3; - static constexpr shader_id_t TEXTURED_TRIANGLES_LIGHT = 4; - static constexpr shader_id_t TRIANGLES_NO_LIGHT = 5; - static constexpr shader_id_t TEXTURED_TRIANGLES_NO_LIGHT = 6; + static constexpr shader_id_t TRIANGLES_LIGHT = 10; + static constexpr shader_id_t TEXTURED_TRIANGLES_LIGHT = 11; + static constexpr shader_id_t TRIANGLES_NO_LIGHT = 12; + static constexpr shader_id_t TEXTURED_TRIANGLES_NO_LIGHT = 13; // Shadow generation 1st/2nd pass shaders: - static constexpr shader_id_t TRIANGLES_SHADOW_1ST = 10; - static constexpr shader_id_t TRIANGLES_SHADOW_2ND = 11; - static constexpr shader_id_t TEXTURED_TRIANGLES_SHADOW_1ST = 12; - static constexpr shader_id_t TEXTURED_TRIANGLES_SHADOW_2ND = 13; + static constexpr shader_id_t TRIANGLES_SHADOW_1ST = 20; + static constexpr shader_id_t TRIANGLES_SHADOW_2ND = 21; + static constexpr shader_id_t TEXTURED_TRIANGLES_SHADOW_1ST = 22; + static constexpr shader_id_t TEXTURED_TRIANGLES_SHADOW_2ND = 23; // Special effects: - static constexpr shader_id_t SKYBOX = 20; + static constexpr shader_id_t SKYBOX = 5; // render *before* potentially transparent triangles static constexpr shader_id_t DEBUG_TEXTURE_TO_SCREEN = 30; static constexpr shader_id_t NONE = 31; //!< Skip rendering }; diff --git a/libs/opengl/include/mrpt/opengl/Texture.h b/libs/opengl/include/mrpt/opengl/Texture.h index ad0ba0796d..d521f6e29f 100644 --- a/libs/opengl/include/mrpt/opengl/Texture.h +++ b/libs/opengl/include/mrpt/opengl/Texture.h @@ -43,6 +43,14 @@ class Texture Texture() = default; ~Texture() = default; + enum class Wrapping : uint8_t + { + Repeat = 0, + MirroredRepeat, + ClampToEdge, + ClapToBorder + }; + /// Options while creating a texture from an image. struct Options { @@ -57,6 +65,12 @@ class Texture bool magnifyLinearFilter = true; bool enableTransparency = false; + + /** How to repeat texture coordinate "S" */ + Wrapping wrappingModeS = Wrapping::Repeat; + + /** How to repeat texture coordinate "T" */ + Wrapping wrappingModeT = Wrapping::Repeat; }; /** This is how an 2D texture image is loaded into this object, and a diff --git a/libs/opengl/src/CAssimpModel.cpp b/libs/opengl/src/CAssimpModel.cpp index bb5fea53e4..64505cef26 100644 --- a/libs/opengl/src/CAssimpModel.cpp +++ b/libs/opengl/src/CAssimpModel.cpp @@ -33,6 +33,7 @@ #endif #include +#include #include #include #include @@ -273,8 +274,65 @@ void CAssimpModel::onUpdateBuffers_all() process_textures(m_assimp_scene->scene); + // Model -> 3D primitives: const auto transf = mrpt::poses::CPose3D(); recursive_render(m_assimp_scene->scene, m_assimp_scene->scene->mRootNode, transf, re); + + // Handle split: + if (m_split_triangles_rendering_bbox > .0f) + { + const float voxel = m_split_triangles_rendering_bbox; + + ASSERT_EQUAL_(m_texturedObjects.size(), m_textureIdMap.size()); + const std::vector origTexturedObjects = m_texturedObjects; + m_texturedObjects.clear(); + + std::unordered_map> + newTextObjs; + + for (size_t textId = 0; textId < m_textureIdMap.size(); textId++) + { + const auto& glTris = origTexturedObjects.at(textId); + const std::vector& iTris = glTris->shaderTexturedTrianglesBuffer(); + for (const auto& t : iTris) + { + const auto midPt = 0.333f * (t.vertices[0].xyzrgba.pt + t.vertices[1].xyzrgba.pt + + t.vertices[2].xyzrgba.pt); + // hash for "voxels": + const int64_t vxlCoord = mrpt::round(midPt.x / voxel) + // + mrpt::round(midPt.y / voxel) * 10'000 + // + mrpt::round(midPt.z / voxel) * 100'000'000; + + auto& trgObj = newTextObjs[vxlCoord][textId]; + if (!trgObj) + { + // Create + trgObj = CSetOfTexturedTriangles::Create(); + + // Set representative point: the MOST FUNDAMENTAL property + // to ensure proper z ordering for transparent rendering: + trgObj->setLocalRepresentativePoint(midPt); + + // copy texture + const auto& texRGB = glTris->getTextureImage(); + const auto& texAlpha = glTris->getTextureAlphaImage(); + if (!texAlpha.isEmpty()) + trgObj->assignImage(texRGB, texAlpha); + else + trgObj->assignImage(texRGB); + } + // Add triangle: + trgObj->insertTriangle(t); + } + } + + // replace list of objects: + m_texturedObjects.clear(); + for (const auto& m : newTextObjs) + for (const auto& [k, v] : m.second) // + m_texturedObjects.push_back(v); + } // end: split into subobjects: + #endif } @@ -297,14 +355,15 @@ void CAssimpModel::enqueueForRenderRecursive( mrpt::opengl::enqueueForRendering(lst, state, rq, wholeInView, is1stShadowMapPass); } -uint8_t CAssimpModel::serializeGetVersion() const { return 2; } +uint8_t CAssimpModel::serializeGetVersion() const { return 3; } void CAssimpModel::serializeTo(mrpt::serialization::CArchive& out) const { writeToStreamRender(out); #if (MRPT_HAS_OPENGL_GLUT || MRPT_HAS_EGL) && MRPT_HAS_ASSIMP const bool empty = m_assimp_scene->scene == nullptr; out << empty; - out << m_modelPath; // v2 + out << m_modelPath; // v2 + out << m_split_triangles_rendering_bbox; // v3 if (!empty) { #if 0 @@ -348,6 +407,8 @@ void CAssimpModel::serializeFrom(mrpt::serialization::CArchive& in, uint8_t vers { const bool empty = in.ReadAs(); in >> m_modelPath; + if (version >= 3) in >> m_split_triangles_rendering_bbox; + if (!empty) { const auto blobSize = in.ReadAs(); @@ -439,6 +500,7 @@ void CAssimpModel::after_load_model() // Evaluate overall bbox: { aiVector3D scene_min, scene_max; + ASSERT_(m_assimp_scene->scene); get_bounding_box(m_assimp_scene->scene, &scene_min, &scene_max); m_bbox_min.x = scene_min.x; m_bbox_min.y = scene_min.y; @@ -460,6 +522,16 @@ auto CAssimpModel::internalBoundingBoxLocal() const -> mrpt::math::TBoundingBoxf return mrpt::math::TBoundingBoxf::FromUnsortedPoints(m_bbox_min, m_bbox_max); } +void CAssimpModel::split_triangles_rendering_bbox(const float bbox_size) +{ + m_split_triangles_rendering_bbox = bbox_size; + +#if (MRPT_HAS_OPENGL_GLUT || MRPT_HAS_EGL) && MRPT_HAS_ASSIMP + CRenderizable::notifyChange(); + if (m_assimp_scene->scene) after_load_model(); +#endif +} + bool CAssimpModel::traceRay( [[maybe_unused]] const mrpt::poses::CPose3D& o, [[maybe_unused]] double& dist) const { diff --git a/libs/opengl/src/Texture.cpp b/libs/opengl/src/Texture.cpp index dfe2e784a2..7fe4bb0fd1 100644 --- a/libs/opengl/src/Texture.cpp +++ b/libs/opengl/src/Texture.cpp @@ -276,14 +276,28 @@ void Texture::internalAssignImage_2D( GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, o.magnifyLinearFilter ? GL_LINEAR : GL_NEAREST); CHECK_OPENGL_ERROR_IN_DEBUG(); + const auto lmbdWrapMap = [](const Wrapping w) + { + // clang-format off + switch (w) + { + case Wrapping::Repeat: return GL_REPEAT; + case Wrapping::MirroredRepeat: return GL_MIRRORED_REPEAT; + case Wrapping::ClampToEdge: return GL_CLAMP_TO_EDGE; + case Wrapping::ClapToBorder: return GL_CLAMP_TO_BORDER; + default: + THROW_EXCEPTION_FMT("Invalid texture wrapping value: %i", static_cast(w)); + }; + // clang-format on + }; + // if wrap is true, the texture wraps over at the edges (repeat) // ... false, the texture ends at the edges (clamp) - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_REPEAT); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, lmbdWrapMap(o.wrappingModeS)); CHECK_OPENGL_ERROR_IN_DEBUG(); - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_REPEAT); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, lmbdWrapMap(o.wrappingModeT)); CHECK_OPENGL_ERROR_IN_DEBUG(); - MRPT_TODO("wrap options?"); // Assure that the images do not overpass the maximum dimensions allowed // by OpenGL: @@ -296,7 +310,7 @@ void Texture::internalAssignImage_2D( if (!warningEmitted) { warningEmitted = true; - std::cerr << "[mrpt::opengl::CRenderizableShaderTexturedTriangles] " + std::cerr << "[mrpt::opengl::Texture] " "**PERFORMACE WARNING**:\n" << " Downsampling texture image of size " << rgb.getWidth() << "x" << rgb.getHeight() diff --git a/libs/ros1bridge/src/point_cloud2.cpp b/libs/ros1bridge/src/point_cloud2.cpp index 0ca9a7e763..cc3de959dc 100644 --- a/libs/ros1bridge/src/point_cloud2.cpp +++ b/libs/ros1bridge/src/point_cloud2.cpp @@ -93,7 +93,7 @@ std::set mrpt::ros1bridge::extractFields(const sensor_msgs::PointCl /** Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap * - * \return true on sucessful conversion, false on any error. + * \return true on successful conversion, false on any error. */ bool mrpt::ros1bridge::fromROS(const sensor_msgs::PointCloud2& msg, CSimplePointsMap& obj) { @@ -243,7 +243,7 @@ bool mrpt::ros1bridge::fromROS(const sensor_msgs::PointCloud2& msg, CPointsMapXY // Convention: // I only found one case (NTU Viral dataset) using uint32_t for time, // and times ranged from 0 to ~99822766 = 100,000,000 = 1e8 - // so they seems to be nanoseconds: + // so they seem to be nanoseconds: obj.setPointTime(idx, t * 1e-9); } diff --git a/libs/ros2bridge/src/point_cloud2.cpp b/libs/ros2bridge/src/point_cloud2.cpp index a7de829f25..4f2e906d9c 100644 --- a/libs/ros2bridge/src/point_cloud2.cpp +++ b/libs/ros2bridge/src/point_cloud2.cpp @@ -22,7 +22,9 @@ using namespace mrpt::maps; -static bool check_field( +namespace +{ +bool check_field( const sensor_msgs::msg::PointField& input_field, std::string check_name, const sensor_msgs::msg::PointField** output) @@ -33,6 +35,7 @@ static bool check_field( if (input_field.datatype != sensor_msgs::msg::PointField::FLOAT32 && input_field.datatype != sensor_msgs::msg::PointField::FLOAT64 && input_field.datatype != sensor_msgs::msg::PointField::UINT16 && + input_field.datatype != sensor_msgs::msg::PointField::UINT32 && input_field.datatype != sensor_msgs::msg::PointField::UINT8) { *output = nullptr; @@ -46,7 +49,7 @@ static bool check_field( return coherence_error; } -static void get_float_from_field( +void get_float_from_field( const sensor_msgs::msg::PointField* field, const unsigned char* data, float& output) { if (field != nullptr) @@ -60,7 +63,7 @@ static void get_float_from_field( output = 0.0; } -static void get_double_from_field( +void get_double_from_field( const sensor_msgs::msg::PointField* field, const unsigned char* data, double& output) { if (field != nullptr) @@ -74,7 +77,7 @@ static void get_double_from_field( output = 0.0; } -static void get_uint16_from_field( +void get_uint16_from_field( const sensor_msgs::msg::PointField* field, const unsigned char* data, uint16_t& output) { if (field != nullptr) @@ -87,6 +90,18 @@ static void get_uint16_from_field( else output = 0; } +void get_uint32_from_field( + const sensor_msgs::msg::PointField* field, const unsigned char* data, uint32_t& output) +{ + if (field != nullptr) + { + if (field->datatype == sensor_msgs::msg::PointField::UINT32) + output = *(reinterpret_cast(&data[field->offset])); + } + else + output = 0; +} +} // namespace std::set mrpt::ros2bridge::extractFields(const sensor_msgs::msg::PointCloud2& msg) { @@ -97,7 +112,7 @@ std::set mrpt::ros2bridge::extractFields(const sensor_msgs::msg::Po /** Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap * - * \return true on sucessful conversion, false on any error. + * \return true on successful conversion, false on any error. */ bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, CSimplePointsMap& obj) { @@ -126,7 +141,7 @@ bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, CSimple { const unsigned char* msg_data = row_data + col * msg.point_step; - float x, y, z; + float x = 0, y = 0, z = 0; get_float_from_field(x_field, msg_data, x); get_float_from_field(y_field, msg_data, y); get_float_from_field(z_field, msg_data, z); @@ -165,7 +180,7 @@ bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, CPoints { const unsigned char* msg_data = row_data + col * msg.point_step; - float x, y, z, i; + float x = 0, y = 0, z = 0, i = 0; get_float_from_field(x_field, msg_data, x); get_float_from_field(y_field, msg_data, y); get_float_from_field(z_field, msg_data, z); @@ -212,7 +227,7 @@ bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, CPoints { const unsigned char* msg_data = row_data + col * msg.point_step; - float x, y, z; + float x = 0, y = 0, z = 0; get_float_from_field(x_field, msg_data, x); get_float_from_field(y_field, msg_data, y); get_float_from_field(z_field, msg_data, z); @@ -220,7 +235,7 @@ bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, CPoints if (i_field) { - float i; + float i = 0; get_float_from_field(i_field, msg_data, i); obj.setPointIntensity(idx, i); } @@ -233,7 +248,21 @@ bool mrpt::ros2bridge::fromROS(const sensor_msgs::msg::PointCloud2& msg, CPoints if (t_field) { double t = 0; - get_double_from_field(t_field, msg_data, t); + + if (t_field->datatype == sensor_msgs::msg::PointField::FLOAT32 || + t_field->datatype == sensor_msgs::msg::PointField::FLOAT64) + { + get_double_from_field(t_field, msg_data, t); + } + else + { + uint32_t tim = 0; + + get_uint32_from_field(t_field, msg_data, tim); + + // Convention: they seem to be nanoseconds: + t = tim * 1e-9; + } // If the sensor uses absolute timestamp, convert them to relative // since otherwise precision is lost in the double->float conversion: diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 08ddd51049..323b8562c4 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -18,16 +18,12 @@ if (NOT CMAKE_MRPT_HAS_PYTHON_BINDINGS) return() endif() -set(PY_SRCS_DIR ${CMAKE_CURRENT_LIST_DIR}/src) - -# these "all" files can be generated like: -# ls -1 src/nanogui/*.cpp | xargs -I FIL echo "#include \"FIL\"" > all_nanogui.cpp - -#file(GLOB_RECURSE PY_ALL_SRCS ${PY_SRCS_DIR}/all_*.cpp) -file(GLOB_RECURSE PY_ALL_SRCS all_*.cpp) +# Take list of sources: +file(READ ${CMAKE_CURRENT_LIST_DIR}/src/pymrpt.sources PY_ALL_SRCS) +string(REPLACE "\n" ";" PY_ALL_SRCS "${PY_ALL_SRCS}") # string -> list of strings +list(TRANSFORM PY_ALL_SRCS PREPEND "src/") pybind11_add_module(pymrpt - ${PY_SRCS_DIR}/pymrpt.cpp ${PY_ALL_SRCS} # -- manually crafted files -- pymrpt_internals.cpp diff --git a/python/all_mrpt_apps.cpp b/python/all_mrpt_apps.cpp deleted file mode 100644 index fd8be5070c..0000000000 --- a/python/all_mrpt_apps.cpp +++ /dev/null @@ -1,4 +0,0 @@ -#include "src/mrpt/apps/BaseAppDataSource.cpp" -#include "src/mrpt/apps/ICP_SLAM_App.cpp" -#include "src/mrpt/apps/MonteCarloLocalization_App.cpp" -#include "src/mrpt/apps/RBPF_SLAM_App.cpp" diff --git a/python/all_mrpt_bayes.cpp b/python/all_mrpt_bayes.cpp deleted file mode 100644 index 5a5e2a3776..0000000000 --- a/python/all_mrpt_bayes.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include "src/mrpt/bayes/CKalmanFilterCapable.cpp" -#include "src/mrpt/bayes/CParticleFilterCapable.cpp" -#include "src/mrpt/bayes/CParticleFilter.cpp" -#include "src/mrpt/bayes/CParticleFilterData_1.cpp" -#include "src/mrpt/bayes/CParticleFilterData.cpp" -#include "src/mrpt/bayes/CProbabilityParticle_1.cpp" -#include "src/mrpt/bayes/CProbabilityParticle.cpp" -#include "src/mrpt/bayes/CRejectionSamplingCapable.cpp" diff --git a/python/all_mrpt_comms.cpp b/python/all_mrpt_comms.cpp deleted file mode 100644 index 4f4162c074..0000000000 --- a/python/all_mrpt_comms.cpp +++ /dev/null @@ -1,4 +0,0 @@ -#include "src/mrpt/comms/CClientTCPSocket.cpp" -#include "src/mrpt/comms/CInterfaceFTDI.cpp" -#include "src/mrpt/comms/CServerTCPSocket.cpp" -#include "src/mrpt/comms/net_utils.cpp" diff --git a/python/all_mrpt_config.cpp b/python/all_mrpt_config.cpp deleted file mode 100644 index 246b1eea1b..0000000000 --- a/python/all_mrpt_config.cpp +++ /dev/null @@ -1,3 +0,0 @@ -#include "src/mrpt/config/CConfigFileBase.cpp" -#include "src/mrpt/config/CConfigFile.cpp" -#include "src/mrpt/config/CLoadableOptions.cpp" diff --git a/python/all_mrpt_containers.cpp b/python/all_mrpt_containers.cpp deleted file mode 100644 index 20faa8a5da..0000000000 --- a/python/all_mrpt_containers.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include "src/mrpt/containers/bimap.cpp" -#include "src/mrpt/containers/CDynamicGrid_1.cpp" -#include "src/mrpt/containers/CDynamicGrid_2.cpp" -#include "src/mrpt/containers/CDynamicGrid3D.cpp" -#include "src/mrpt/containers/CDynamicGrid.cpp" -#include "src/mrpt/containers/circular_buffer.cpp" -#include "src/mrpt/containers/CommentPosition.cpp" -#include "src/mrpt/containers/MT_buffer.cpp" -#include "src/mrpt/containers/traits_map.cpp" -#include "src/mrpt/containers/yaml.cpp" diff --git a/python/all_mrpt_core.cpp b/python/all_mrpt_core.cpp deleted file mode 100644 index ddf8dea7f7..0000000000 --- a/python/all_mrpt_core.cpp +++ /dev/null @@ -1,15 +0,0 @@ -#include "src/mrpt/core/aligned_allocator.cpp" -#include "src/mrpt/core/backtrace.cpp" -#include "src/mrpt/core/bits_math_1.cpp" -#include "src/mrpt/core/bits_math.cpp" -#include "src/mrpt/core/Clock.cpp" -#include "src/mrpt/core/cpu_1.cpp" -#include "src/mrpt/core/cpu.cpp" -#include "src/mrpt/core/format.cpp" -#include "src/mrpt/core/integer_select.cpp" -#include "src/mrpt/core/reverse_bytes.cpp" -#include "src/mrpt/core/round.cpp" -#include "src/mrpt/core/safe_pointers_1.cpp" -#include "src/mrpt/core/safe_pointers.cpp" -#include "src/mrpt/core/Stringifyable.cpp" -#include "src/mrpt/core/WorkerThreadsPool.cpp" diff --git a/python/all_mrpt_expr.cpp b/python/all_mrpt_expr.cpp deleted file mode 100644 index 45f8d4b88e..0000000000 --- a/python/all_mrpt_expr.cpp +++ /dev/null @@ -1 +0,0 @@ -#include "src/mrpt/expr/CRuntimeCompiledExpression.cpp" diff --git a/python/all_mrpt_graphs.cpp b/python/all_mrpt_graphs.cpp deleted file mode 100644 index 8857360f35..0000000000 --- a/python/all_mrpt_graphs.cpp +++ /dev/null @@ -1,2 +0,0 @@ -#include "src/mrpt/graphs/CDirectedTree.cpp" -#include "src/mrpt/graphs/ScalarFactorGraph.cpp" diff --git a/python/all_mrpt_gui.cpp b/python/all_mrpt_gui.cpp deleted file mode 100644 index e783e5b8cd..0000000000 --- a/python/all_mrpt_gui.cpp +++ /dev/null @@ -1,7 +0,0 @@ -#include "src/mrpt/gui/CBaseGUIWindow.cpp" -#include "src/mrpt/gui/CDisplayWindow3D_1.cpp" -#include "src/mrpt/gui/CDisplayWindow3D.cpp" -#include "src/mrpt/gui/CDisplayWindow.cpp" -#include "src/mrpt/gui/CGlCanvasBase.cpp" -#include "src/mrpt/gui/keycodes.cpp" -#include "src/mrpt/gui/MRPT2NanoguiGLCanvas.cpp" diff --git a/python/all_mrpt_hwdrivers1.cpp b/python/all_mrpt_hwdrivers1.cpp deleted file mode 100644 index 9f6640aae7..0000000000 --- a/python/all_mrpt_hwdrivers1.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/hwdrivers/C2DRangeFinderAbstract.cpp" -#include "src/mrpt/hwdrivers/CCameraSensor.cpp" -#include "src/mrpt/hwdrivers/CCANBusReader.cpp" -#include "src/mrpt/hwdrivers/CEnoseModular.cpp" -#include "src/mrpt/hwdrivers/CGenericSensor.cpp" -#include "src/mrpt/hwdrivers/CGillAnemometer.cpp" -#include "src/mrpt/hwdrivers/CGPSInterface.cpp" -#include "src/mrpt/hwdrivers/CImageGrabber_dc1394.cpp" -#include "src/mrpt/hwdrivers/CImageGrabber_FlyCapture2.cpp" -#include "src/mrpt/hwdrivers/CImpinjRFID.cpp" -#include "src/mrpt/hwdrivers/CIMUXSens_MT4.cpp" -#include "src/mrpt/hwdrivers/CKinect.cpp" diff --git a/python/all_mrpt_hwdrivers2.cpp b/python/all_mrpt_hwdrivers2.cpp deleted file mode 100644 index 80140de1f4..0000000000 --- a/python/all_mrpt_hwdrivers2.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include "src/mrpt/hwdrivers/CMyntEyeCamera.cpp" -#include "src/mrpt/hwdrivers/CNationalInstrumentsDAQ.cpp" -#include "src/mrpt/hwdrivers/CNTRIPClient.cpp" -#include "src/mrpt/hwdrivers/COpenNI2_RGBD360.cpp" -#include "src/mrpt/hwdrivers/CPhidgetInterfaceKitProximitySensors.cpp" -#include "src/mrpt/hwdrivers/CSickLaserUSB.cpp" -#include "src/mrpt/hwdrivers/CSkeletonTracker.cpp" -#include "src/mrpt/hwdrivers/CStereoGrabber_Bumblebee_libdc1394.cpp" -#include "src/mrpt/hwdrivers/CVelodyneScanner.cpp" -#include "src/mrpt/hwdrivers/CWirelessPower.cpp" diff --git a/python/all_mrpt_img.cpp b/python/all_mrpt_img.cpp deleted file mode 100644 index 80fd5fe769..0000000000 --- a/python/all_mrpt_img.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include "src/mrpt/img/CCanvas.cpp" -#include "src/mrpt/img/CImage.cpp" -#include "src/mrpt/img/color_maps.cpp" -#include "src/mrpt/img/DistortionModel.cpp" -#include "src/mrpt/img/TCamera.cpp" -#include "src/mrpt/img/TColor.cpp" -#include "src/mrpt/img/TPixelCoord.cpp" -#include "src/mrpt/img/TStereoCamera.cpp" diff --git a/python/all_mrpt_io.cpp b/python/all_mrpt_io.cpp deleted file mode 100644 index dd5abc40b5..0000000000 --- a/python/all_mrpt_io.cpp +++ /dev/null @@ -1,7 +0,0 @@ -#include "src/mrpt/io/CFileInputStream.cpp" -#include "src/mrpt/io/CFileStream.cpp" -#include "src/mrpt/io/CMemoryStream.cpp" -#include "src/mrpt/io/CPipe.cpp" -#include "src/mrpt/io/CStream.cpp" -#include "src/mrpt/io/CTextFileLinesParser.cpp" -#include "src/mrpt/io/zip.cpp" diff --git a/python/all_mrpt_kinematics.cpp b/python/all_mrpt_kinematics.cpp deleted file mode 100644 index fcf252067c..0000000000 --- a/python/all_mrpt_kinematics.cpp +++ /dev/null @@ -1,3 +0,0 @@ -#include "src/mrpt/kinematics/CKinematicChain.cpp" -#include "src/mrpt/kinematics/CVehicleVelCmd.cpp" -#include "src/mrpt/kinematics/CVehicleVelCmd_DiffDriven.cpp" diff --git a/python/all_mrpt_maps1.cpp b/python/all_mrpt_maps1.cpp deleted file mode 100644 index 0f58b9999e..0000000000 --- a/python/all_mrpt_maps1.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/maps/CBeacon.cpp" -#include "src/mrpt/maps/CColouredOctoMap.cpp" -#include "src/mrpt/maps/CColouredPointsMap.cpp" -#include "src/mrpt/maps/CGasConcentrationGridMap2D.cpp" -#include "src/mrpt/maps/CHeightGridMap2D_Base.cpp" -#include "src/mrpt/maps/CHeightGridMap2D.cpp" -#include "src/mrpt/maps/CHeightGridMap2D_MRF.cpp" -#include "src/mrpt/maps/CLandmark.cpp" -#include "src/mrpt/maps/CLandmarksMap.cpp" -#include "src/mrpt/maps/CLogOddsGridMap3D.cpp" -#include "src/mrpt/maps/CLogOddsGridMapLUT.cpp" -#include "src/mrpt/maps/NearestNeighborsCapable.cpp" \ No newline at end of file diff --git a/python/all_mrpt_maps2.cpp b/python/all_mrpt_maps2.cpp deleted file mode 100644 index 08f8e95e2f..0000000000 --- a/python/all_mrpt_maps2.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "src/mrpt/maps/CMetricMap_1.cpp" -#include "src/mrpt/maps/CMetricMap.cpp" -#include "src/mrpt/maps/CMetricMapEvents.cpp" -#include "src/mrpt/maps/CMultiMetricMap.cpp" -#include "src/mrpt/maps/CMultiMetricMapPDF.cpp" -#include "src/mrpt/maps/COccupancyGridMap2D.cpp" -#include "src/mrpt/maps/COccupancyGridMap3D.cpp" -#include "src/mrpt/maps/COctoMapBase_1.cpp" -#include "src/mrpt/maps/COctoMapBase.cpp" -#include "src/mrpt/maps/COctoMap.cpp" -#include "src/mrpt/maps/CPointCloudFilterByDistance.cpp" diff --git a/python/all_mrpt_maps3.cpp b/python/all_mrpt_maps3.cpp deleted file mode 100644 index f4d3c42c54..0000000000 --- a/python/all_mrpt_maps3.cpp +++ /dev/null @@ -1,17 +0,0 @@ -#include "src/mrpt/maps/CPointsMap_1.cpp" -#include "src/mrpt/maps/CPointsMap.cpp" -#include "src/mrpt/maps/CPointsMapXYZI.cpp" -#include "src/mrpt/maps/CRandomFieldGridMap2D.cpp" -#include "src/mrpt/maps/CRandomFieldGridMap3D.cpp" -#include "src/mrpt/maps/CReflectivityGridMap2D.cpp" -#include "src/mrpt/maps/CSimpleMap.cpp" -#include "src/mrpt/maps/CSimplePointsMap.cpp" -#include "src/mrpt/maps/CWeightedPointsMap.cpp" -#include "src/mrpt/maps/CWirelessPowerGridMap2D.cpp" -#include "src/mrpt/maps/metric_map_types.cpp" -#include "src/mrpt/maps/CVoxelMap.cpp" -#include "src/mrpt/maps/CVoxelMapBase.cpp" -#include "src/mrpt/maps/CVoxelMapOccupancyBase.cpp" -#include "src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp" -#include "src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp" - diff --git a/python/all_mrpt_math1.cpp b/python/all_mrpt_math1.cpp deleted file mode 100644 index e433f637e0..0000000000 --- a/python/all_mrpt_math1.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/math/CAtan2LookUpTable.cpp" -#include "src/mrpt/math/CMatrixB.cpp" -#include "src/mrpt/math/CMatrixDynamic_2.cpp" -#include "src/mrpt/math/CMatrixDynamic_1.cpp" -#include "src/mrpt/math/CMatrixDynamic.cpp" -#include "src/mrpt/math/CMatrixF.cpp" -#include "src/mrpt/math/CMatrixFixed_1.cpp" -#include "src/mrpt/math/CMatrixFixed_2.cpp" -#include "src/mrpt/math/CMatrixFixed_3.cpp" -#include "src/mrpt/math/CMatrixFixed.cpp" -#include "src/mrpt/math/MatrixVectorBase.cpp" -#include "src/mrpt/math/CPolygon.cpp" diff --git a/python/all_mrpt_math2.cpp b/python/all_mrpt_math2.cpp deleted file mode 100644 index d7915c0d0b..0000000000 --- a/python/all_mrpt_math2.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/math/CProbabilityDensityFunction_1.cpp" -#include "src/mrpt/math/CProbabilityDensityFunction.cpp" -#include "src/mrpt/math/CQuaternion.cpp" -#include "src/mrpt/math/CVectorDynamic.cpp" -#include "src/mrpt/math/data_utils.cpp" -#include "src/mrpt/math/epsilon.cpp" -#include "src/mrpt/math/fresnel.cpp" -#include "src/mrpt/math/geometry_1.cpp" -#include "src/mrpt/math/geometry_2.cpp" -#include "src/mrpt/math/geometry.cpp" -#include "src/mrpt/math/homog_matrices.cpp" -#include "src/mrpt/math/math_frwds.cpp" diff --git a/python/all_mrpt_math3.cpp b/python/all_mrpt_math3.cpp deleted file mode 100644 index dadc86253f..0000000000 --- a/python/all_mrpt_math3.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include "src/mrpt/math/ops_containers.cpp" -#include "src/mrpt/math/TBoundingBox.cpp" -#include "src/mrpt/math/TLine3D.cpp" -#include "src/mrpt/math/TObject3D.cpp" -#include "src/mrpt/math/TPlane.cpp" -#include "src/mrpt/math/TPoint2D.cpp" -#include "src/mrpt/math/TPoint3D_1.cpp" -#include "src/mrpt/math/TPoint3D.cpp" diff --git a/python/all_mrpt_math4.cpp b/python/all_mrpt_math4.cpp deleted file mode 100644 index 8188eecac5..0000000000 --- a/python/all_mrpt_math4.cpp +++ /dev/null @@ -1,11 +0,0 @@ -#include "src/mrpt/math/TPolygon2D.cpp" -#include "src/mrpt/math/TPolygon3D.cpp" -#include "src/mrpt/math/TPolygonWithPlane.cpp" -#include "src/mrpt/math/TPose2D.cpp" -#include "src/mrpt/math/TPose3DQuat.cpp" -#include "src/mrpt/math/TPoseOrPoint.cpp" -#include "src/mrpt/math/TSegment2D.cpp" -#include "src/mrpt/math/TSegment3D.cpp" -#include "src/mrpt/math/TTwist2D.cpp" -#include "src/mrpt/math/TTwist3D.cpp" -#include "src/mrpt/math/wrap2pi.cpp" diff --git a/python/all_mrpt_nav.cpp b/python/all_mrpt_nav.cpp deleted file mode 100644 index 73f18e9905..0000000000 --- a/python/all_mrpt_nav.cpp +++ /dev/null @@ -1,14 +0,0 @@ -#include "src/mrpt/nav/holonomic/CHolonomicFullEval.cpp" -#include "src/mrpt/nav/holonomic/CHolonomicND.cpp" -#include "src/mrpt/nav/holonomic/CHolonomicVFF.cpp" -#include "src/mrpt/nav/holonomic/ClearanceDiagram.cpp" -#include "src/mrpt/nav/planners/TMoveTree.cpp" -#include "src/mrpt/nav/reactive/CAbstractNavigator.cpp" -#include "src/mrpt/nav/reactive/CAbstractPTGBasedReactive.cpp" -#include "src/mrpt/nav/reactive/CLogFileRecord.cpp" -#include "src/mrpt/nav/reactive/CMultiObjMotionOpt_Scalarization.cpp" -#include "src/mrpt/nav/reactive/CReactiveNavigationSystem3D.cpp" -#include "src/mrpt/nav/reactive/TWaypoint.cpp" -#include "src/mrpt/nav/tpspace/CParameterizedTrajectoryGenerator.cpp" -#include "src/mrpt/nav/tpspace/CPTG_DiffDrive_alpha.cpp" -#include "src/mrpt/nav/tpspace/CPTG_DiffDrive_C.cpp" diff --git a/python/all_mrpt_obs.cpp b/python/all_mrpt_obs.cpp deleted file mode 100644 index 4ddd98d84c..0000000000 --- a/python/all_mrpt_obs.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include "src/mrpt/obs/CActionCollection.cpp" -#include "src/mrpt/obs/CAction.cpp" -#include "src/mrpt/obs/CActionRobotMovement2D.cpp" -#include "src/mrpt/obs/CActionRobotMovement3D.cpp" -#include "src/mrpt/obs/CObservation2DRangeScan.cpp" -#include "src/mrpt/obs/CObservation2DRangeScanWithUncertainty.cpp" -#include "src/mrpt/obs/CObservation3DRangeScan.cpp" -#include "src/mrpt/obs/CObservationCANBusJ1939.cpp" -#include "src/mrpt/obs/CObservation.cpp" -#include "src/mrpt/obs/CObservationGasSensors.cpp" diff --git a/python/all_mrpt_obs2.cpp b/python/all_mrpt_obs2.cpp deleted file mode 100644 index 9f9be38f78..0000000000 --- a/python/all_mrpt_obs2.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/obs/CObservationGPS.cpp" -#include "src/mrpt/obs/CObservationImage.cpp" -#include "src/mrpt/obs/CObservationIMU.cpp" -#include "src/mrpt/obs/CObservationPointCloud.cpp" -#include "src/mrpt/obs/CObservationRange.cpp" -#include "src/mrpt/obs/CObservationRawDAQ.cpp" -#include "src/mrpt/obs/CObservationRFID.cpp" -#include "src/mrpt/obs/CObservationRGBD360.cpp" -#include "src/mrpt/obs/CObservationSkeleton.cpp" -#include "src/mrpt/obs/CObservationStereoImages.cpp" -#include "src/mrpt/obs/CObservation3DScene.cpp" -#include "src/mrpt/obs/CObservationBearingRange.cpp" \ No newline at end of file diff --git a/python/all_mrpt_obs3.cpp b/python/all_mrpt_obs3.cpp deleted file mode 100644 index f5fd0addf9..0000000000 --- a/python/all_mrpt_obs3.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/obs/CObservationWindSensor.cpp" -#include "src/mrpt/obs/CObservationWirelessPower.cpp" -#include "src/mrpt/obs/CSensoryFrame.cpp" -#include "src/mrpt/obs/customizable_obs_viz.cpp" -#include "src/mrpt/obs/format_externals_filename.cpp" -#include "src/mrpt/obs/gnss_messages_type_list.cpp" -#include "src/mrpt/obs/stock_observations.cpp" -#include "src/mrpt/obs/T2DScanProperties.cpp" -#include "src/mrpt/obs/T3DPointsProjectionParams.cpp" -#include "src/mrpt/obs/TPixelLabelInfo.cpp" -#include "src/mrpt/obs/VelodyneCalibration.cpp" -#include "src/mrpt/obs/CObservationRobotPose.cpp" diff --git a/python/all_mrpt_opengl1.cpp b/python/all_mrpt_opengl1.cpp deleted file mode 100644 index 946ffd8031..0000000000 --- a/python/all_mrpt_opengl1.cpp +++ /dev/null @@ -1,15 +0,0 @@ -#include "src/mrpt/opengl/Buffer.cpp" -#include "src/mrpt/opengl/CArrow.cpp" -#include "src/mrpt/opengl/CAxis.cpp" -#include "src/mrpt/opengl/CBox.cpp" -#include "src/mrpt/opengl/CCamera.cpp" -#include "src/mrpt/opengl/CEllipsoidRangeBearing2D.cpp" -#include "src/mrpt/opengl/CGeneralizedEllipsoidTemplate.cpp" -#include "src/mrpt/opengl/CGridPlaneXY.cpp" -#include "src/mrpt/opengl/CGridPlaneXZ.cpp" -#include "src/mrpt/opengl/CMesh3D.cpp" -#include "src/mrpt/opengl/COctoMapVoxels.cpp" -#include "src/mrpt/opengl/COctreePointRenderer.cpp" -#include "src/mrpt/opengl/CPlanarLaserScan.cpp" -#include "src/mrpt/opengl/CPointCloudColoured.cpp" -#include "src/mrpt/opengl/CPointCloud.cpp" \ No newline at end of file diff --git a/python/all_mrpt_opengl2.cpp b/python/all_mrpt_opengl2.cpp deleted file mode 100644 index eb1150d766..0000000000 --- a/python/all_mrpt_opengl2.cpp +++ /dev/null @@ -1,14 +0,0 @@ -#include "src/mrpt/opengl/CRenderizable.cpp" -#include "src/mrpt/opengl/CSetOfObjects.cpp" -#include "src/mrpt/opengl/CSetOfTriangles.cpp" -#include "src/mrpt/opengl/CSphere.cpp" -#include "src/mrpt/opengl/CTexturedPlane.cpp" -#include "src/mrpt/opengl/CUBE_TEXTURE_FACE.cpp" -#include "src/mrpt/opengl/CVectorField3D.cpp" -#include "src/mrpt/opengl/DefaultShaders.cpp" -#include "src/mrpt/opengl/PLY_import_export.cpp" -#include "src/mrpt/opengl/stock_objects.cpp" -#include "src/mrpt/opengl/Texture.cpp" -#include "src/mrpt/opengl/TTriangle.cpp" -#include "src/mrpt/opengl/Viewport.cpp" -#include "src/mrpt/opengl/Visualizable.cpp" diff --git a/python/all_mrpt_poses1.cpp b/python/all_mrpt_poses1.cpp deleted file mode 100644 index d8fe5879c5..0000000000 --- a/python/all_mrpt_poses1.cpp +++ /dev/null @@ -1,13 +0,0 @@ -#include "src/mrpt/poses/CPoint2D.cpp" -#include "src/mrpt/poses/CPoint.cpp" -#include "src/mrpt/poses/CPointPDF.cpp" -#include "src/mrpt/poses/CPointPDFSOG.cpp" -#include "src/mrpt/poses/CPose2D.cpp" -#include "src/mrpt/poses/CPose2DGridTemplate.cpp" -#include "src/mrpt/poses/CPose2DInterpolator.cpp" -#include "src/mrpt/poses/CPose3D.cpp" -#include "src/mrpt/poses/CPose3DPDF.cpp" -#include "src/mrpt/poses/CPose3DPDFGaussian.cpp" -#include "src/mrpt/poses/CPose3DPDFGaussianInf.cpp" -#include "src/mrpt/poses/CPose3DPDFParticles.cpp" -#include "src/mrpt/poses/CPose3DPDFSOG.cpp" diff --git a/python/all_mrpt_poses2.cpp b/python/all_mrpt_poses2.cpp deleted file mode 100644 index 0ab7f14551..0000000000 --- a/python/all_mrpt_poses2.cpp +++ /dev/null @@ -1,16 +0,0 @@ -#include "src/mrpt/poses/CPose3DQuat.cpp" -#include "src/mrpt/poses/CPose3DQuatPDFGaussian.cpp" -#include "src/mrpt/poses/CPose3DQuatPDFGaussianInf.cpp" -#include "src/mrpt/poses/CPoseInterpolatorBase.cpp" -#include "src/mrpt/poses/CPoseOrPoint_1.cpp" -#include "src/mrpt/poses/CPoseOrPoint_2.cpp" -#include "src/mrpt/poses/CPoseOrPoint.cpp" -#include "src/mrpt/poses/CPosePDF.cpp" -#include "src/mrpt/poses/CPosePDFGaussian.cpp" -#include "src/mrpt/poses/CPosePDFGrid.cpp" -#include "src/mrpt/poses/CPoses2DSequence.cpp" -#include "src/mrpt/poses/FrameTransformer.cpp" -#include "src/mrpt/poses/SO_SE_average.cpp" -#include "src/mrpt/poses/Lie/Euclidean.cpp" -#include "src/mrpt/poses/Lie/SE.cpp" -#include "src/mrpt/poses/Lie/SO.cpp" diff --git a/python/all_mrpt_random.cpp b/python/all_mrpt_random.cpp deleted file mode 100644 index a588840b55..0000000000 --- a/python/all_mrpt_random.cpp +++ /dev/null @@ -1 +0,0 @@ -#include "src/mrpt/random/RandomGenerators.cpp" diff --git a/python/all_mrpt_rtti.cpp b/python/all_mrpt_rtti.cpp deleted file mode 100644 index 8f33bf4adb..0000000000 --- a/python/all_mrpt_rtti.cpp +++ /dev/null @@ -1,6 +0,0 @@ -#include "src/mrpt/rtti/CListOfClasses.cpp" -#include "src/mrpt/rtti/CObject_1.cpp" -#include "src/mrpt/rtti/CObject_2.cpp" -#include "src/mrpt/rtti/CObject_3.cpp" -#include "src/mrpt/rtti/CObject_4.cpp" -#include "src/mrpt/rtti/CObject.cpp" diff --git a/python/all_mrpt_serialization.cpp b/python/all_mrpt_serialization.cpp deleted file mode 100644 index f78ceec7cd..0000000000 --- a/python/all_mrpt_serialization.cpp +++ /dev/null @@ -1,3 +0,0 @@ -#include "src/mrpt/serialization/CArchive_1.cpp" -#include "src/mrpt/serialization/CArchive.cpp" -#include "src/mrpt/serialization/CSerializable.cpp" diff --git a/python/all_mrpt_slam.cpp b/python/all_mrpt_slam.cpp deleted file mode 100644 index b41fc7b920..0000000000 --- a/python/all_mrpt_slam.cpp +++ /dev/null @@ -1,10 +0,0 @@ -#include "src/mrpt/slam/CIncrementalMapPartitioner.cpp" -#include "src/mrpt/slam/CMetricMapBuilder.cpp" -#include "src/mrpt/slam/CMetricMapBuilderICP.cpp" -#include "src/mrpt/slam/CMetricMapsAlignmentAlgorithm.cpp" -#include "src/mrpt/slam/CMonteCarloLocalization3D.cpp" -#include "src/mrpt/slam/COccupancyGridMapFeatureExtractor.cpp" -#include "src/mrpt/slam/CRangeBearingKFSLAM.cpp" -#include "src/mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp" -#include "src/mrpt/slam/data_association.cpp" -#include "src/mrpt/slam/TKLDParams.cpp" diff --git a/python/all_mrpt_system.cpp b/python/all_mrpt_system.cpp deleted file mode 100644 index 76078c887f..0000000000 --- a/python/all_mrpt_system.cpp +++ /dev/null @@ -1,12 +0,0 @@ -#include "src/mrpt/system/CObservable.cpp" -#include "src/mrpt/system/CObserver.cpp" -#include "src/mrpt/system/CRateTimer.cpp" -#include "src/mrpt/system/crc.cpp" -#include "src/mrpt/system/CTicTac.cpp" -#include "src/mrpt/system/CTimeLogger.cpp" -#include "src/mrpt/system/datetime.cpp" -#include "src/mrpt/system/mrptEvent.cpp" -#include "src/mrpt/system/os_1.cpp" -#include "src/mrpt/system/os.cpp" -#include "src/mrpt/system/scheduler.cpp" -#include "src/mrpt/system/string_utils.cpp" diff --git a/python/all_mrpt_tfest.cpp b/python/all_mrpt_tfest.cpp deleted file mode 100644 index add3f48961..0000000000 --- a/python/all_mrpt_tfest.cpp +++ /dev/null @@ -1,2 +0,0 @@ -#include "src/mrpt/tfest/indivcompatdecls.cpp" -#include "src/mrpt/tfest/TMatchingPair.cpp" diff --git a/python/all_mrpt_topography.cpp b/python/all_mrpt_topography.cpp deleted file mode 100644 index c95617b47f..0000000000 --- a/python/all_mrpt_topography.cpp +++ /dev/null @@ -1,3 +0,0 @@ -#include "src/mrpt/topography/conversions.cpp" -#include "src/mrpt/topography/data_types_1.cpp" -#include "src/mrpt/topography/data_types.cpp" diff --git a/python/all_mrpt_typemeta.cpp b/python/all_mrpt_typemeta.cpp deleted file mode 100644 index e1542404ed..0000000000 --- a/python/all_mrpt_typemeta.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "src/mrpt/typemeta/static_string.cpp" -#include "src/mrpt/typemeta/TEnumType_1.cpp" -#include "src/mrpt/typemeta/TEnumType_2.cpp" -#include "src/mrpt/typemeta/TEnumType_3.cpp" -#include "src/mrpt/typemeta/TEnumType_4.cpp" -#include "src/mrpt/typemeta/TEnumType_5.cpp" -#include "src/mrpt/typemeta/TEnumType_6.cpp" -#include "src/mrpt/typemeta/TEnumType_7.cpp" -#include "src/mrpt/typemeta/TEnumType.cpp" diff --git a/python/all_mrpt_vision.cpp b/python/all_mrpt_vision.cpp deleted file mode 100644 index 9cebf3ef8b..0000000000 --- a/python/all_mrpt_vision.cpp +++ /dev/null @@ -1,4 +0,0 @@ -#include "src/mrpt/vision/chessboard_camera_calib.cpp" -#include "src/mrpt/vision/TKeyPoint.cpp" -#include "src/mrpt/vision/types_1.cpp" -#include "src/mrpt/vision/types.cpp" diff --git a/python/all_nanogui.cpp b/python/all_nanogui.cpp deleted file mode 100644 index 63ab285d0b..0000000000 --- a/python/all_nanogui.cpp +++ /dev/null @@ -1,3 +0,0 @@ -#include "src/nanogui/common_1.cpp" -#include "src/nanogui/common.cpp" -#include "src/nanogui/glcanvas.cpp" diff --git a/python/all_std.cpp b/python/all_std.cpp deleted file mode 100644 index 960237142b..0000000000 --- a/python/all_std.cpp +++ /dev/null @@ -1,9 +0,0 @@ -#include "src/std/array.cpp" -#include "src/std/chrono.cpp" -#include "src/std/stl_deque_1.cpp" -#include "src/std/stl_deque_2.cpp" -#include "src/std/stl_deque.cpp" -#include "src/std/stl_map.cpp" -#include "src/std/stl_multimap.cpp" -#include "src/std/stl_vector.cpp" - diff --git a/python/all_unknown.cpp b/python/all_unknown.cpp deleted file mode 100644 index 1a7e68d7c5..0000000000 --- a/python/all_unknown.cpp +++ /dev/null @@ -1,8 +0,0 @@ -#include "src/unknown/unknown_1.cpp" -#include "src/unknown/unknown_2.cpp" -#include "src/unknown/unknown_3.cpp" -#include "src/unknown/unknown_4.cpp" -#include "src/unknown/unknown_5.cpp" -#include "src/unknown/unknown_6.cpp" -#include "src/unknown/unknown_7.cpp" -#include "src/unknown/unknown.cpp" diff --git a/python/src/mrpt/obs/CObservation2DRangeScan.cpp b/python/src/mrpt/obs/CObservation2DRangeScan.cpp index 176239989d..9da392383e 100644 --- a/python/src/mrpt/obs/CObservation2DRangeScan.cpp +++ b/python/src/mrpt/obs/CObservation2DRangeScan.cpp @@ -51,7 +51,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:55 +// mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:59 struct PyCallBack_mrpt_obs_CObservation2DRangeScan : public mrpt::obs::CObservation2DRangeScan { using mrpt::obs::CObservation2DRangeScan::CObservation2DRangeScan; @@ -242,7 +242,7 @@ struct PyCallBack_mrpt_obs_CObservation2DRangeScan : public mrpt::obs::CObservat void bind_mrpt_obs_CObservation2DRangeScan(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:55 + { // mrpt::obs::CObservation2DRangeScan file:mrpt/obs/CObservation2DRangeScan.h line:59 pybind11::class_, PyCallBack_mrpt_obs_CObservation2DRangeScan, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservation2DRangeScan", "A \"CObservation\"-derived class that represents a 2D range scan measurement\n (typically from a laser scanner).\n The data structures are generic enough to hold a wide variety of 2D\n scanners and \"3D\" planar rotating 2D lasers.\n\n These are the most important data fields:\n - Scan ranges: A vector of float values with all the range measurements\n [meters]. Access via `CObservation2DRangeScan::getScanRange()` and\n `CObservation2DRangeScan::setScanRange()`.\n - Range validity: A vector (of identical size to scan), it holds\n `true` for those ranges than are valid (i.e. will be zero for non-reflected\n rays, etc.), `false` for scan rays without a valid lidar return.\n - Reflection intensity: A vector (of identical size to scan) a\n unitless int values representing the relative strength of each return. Higher\n values indicate a more intense return. This is useful for filtering out low\n intensity (noisy) returns or detecting intense landmarks.\n - CObservation2DRangeScan::aperture: The field-of-view of the scanner,\n in radians (typically, M_PI = 180deg).\n - CObservation2DRangeScan::sensorPose: The 6D location of the sensor on\n the robot reference frame (default=at the origin), i.e. wrt `base_link`\n following ROS conventions.\n - CObservation2DRangeScan::rightToLeft: The scanning direction:\n true=counterclockwise (default), false=clockwise.\n\n Note that the *angle of each range* in the vectors above is implicitly\n defined by the index within the vector.\n \n\n CObservation, CPointsMap, T2DScanProperties\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::obs::CObservation2DRangeScan(); }, [](){ return new PyCallBack_mrpt_obs_CObservation2DRangeScan(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservation2DRangeScan const &o){ return new PyCallBack_mrpt_obs_CObservation2DRangeScan(o); } ) ); diff --git a/python/src/mrpt/opengl/CArrow.cpp b/python/src/mrpt/opengl/CArrow.cpp index a34a67d0f6..75520c83aa 100644 --- a/python/src/mrpt/opengl/CArrow.cpp +++ b/python/src/mrpt/opengl/CArrow.cpp @@ -848,6 +848,8 @@ void bind_mrpt_opengl_CArrow(std::function< pybind11::module &(std::string const cl.def("clear", (void (mrpt::opengl::CAssimpModel::*)()) &mrpt::opengl::CAssimpModel::clear, "Empty the object \n\nC++: mrpt::opengl::CAssimpModel::clear() --> void"); cl.def("traceRay", (bool (mrpt::opengl::CAssimpModel::*)(const class mrpt::poses::CPose3D &, double &) const) &mrpt::opengl::CAssimpModel::traceRay, "C++: mrpt::opengl::CAssimpModel::traceRay(const class mrpt::poses::CPose3D &, double &) const --> bool", pybind11::arg("o"), pybind11::arg("dist")); cl.def("internalBoundingBoxLocal", (struct mrpt::math::TBoundingBox_ (mrpt::opengl::CAssimpModel::*)() const) &mrpt::opengl::CAssimpModel::internalBoundingBoxLocal, "C++: mrpt::opengl::CAssimpModel::internalBoundingBoxLocal() const --> struct mrpt::math::TBoundingBox_"); + cl.def("split_triangles_rendering_bbox", (void (mrpt::opengl::CAssimpModel::*)(const float)) &mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox, "Enable (or disable if set to .0f) a feature in which textured triangles\n are split into different renderizable smaller objects.\n This is required only for semitransparent objects with overlaping regions.\n\nC++: mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox(const float) --> void", pybind11::arg("bbox_size")); + cl.def("split_triangles_rendering_bbox", (float (mrpt::opengl::CAssimpModel::*)() const) &mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox, "C++: mrpt::opengl::CAssimpModel::split_triangles_rendering_bbox() const --> float"); cl.def("assign", (class mrpt::opengl::CAssimpModel & (mrpt::opengl::CAssimpModel::*)(const class mrpt::opengl::CAssimpModel &)) &mrpt::opengl::CAssimpModel::operator=, "C++: mrpt::opengl::CAssimpModel::operator=(const class mrpt::opengl::CAssimpModel &) --> class mrpt::opengl::CAssimpModel &", pybind11::return_value_policy::automatic, pybind11::arg("")); { // mrpt::opengl::CAssimpModel::LoadFlags file:mrpt/opengl/CAssimpModel.h line:84 @@ -866,7 +868,7 @@ void bind_mrpt_opengl_CArrow(std::function< pybind11::module &(std::string const } - { // mrpt::opengl::CAssimpModel::TInfoPerTexture file:mrpt/opengl/CAssimpModel.h line:123 + { // mrpt::opengl::CAssimpModel::TInfoPerTexture file:mrpt/opengl/CAssimpModel.h line:133 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TInfoPerTexture", ""); cl.def( pybind11::init( [](){ return new mrpt::opengl::CAssimpModel::TInfoPerTexture(); } ) ); diff --git a/python/src/mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp b/python/src/mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp index 652f4fa3d2..f62244b01a 100644 --- a/python/src/mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp +++ b/python/src/mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp @@ -1,24 +1,16 @@ -#include -#include #include #include -#include #include #include -#include -#include #include #include #include #include #include -#include -#include #include #include #include #include -#include #include #include #include @@ -27,7 +19,6 @@ #include #include #include -#include #include #include #include @@ -37,15 +28,12 @@ #include #include #include -#include #include #include #include #include #include -#include #include // __str__ -#include #include #include @@ -106,20 +94,4 @@ void bind_mrpt_slam_CRejectionSamplingRangeOnlyLocalization(std::function< pybin cl.def("setParams", (bool (mrpt::slam::CRejectionSamplingRangeOnlyLocalization::*)(const class mrpt::maps::CLandmarksMap &, const class mrpt::obs::CObservationBeaconRanges &, float, const class mrpt::poses::CPose2D &, float, bool)) &mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams, "The parameters used in the generation of random samples:\n \n\n The map containing the N beacons (indexed by their\n \"beacon ID\"s). Only the mean 3D position of the beacons is used, the\n covariance is ignored.\n \n\n An observation with, at least ONE range measurement.\n \n\n The standard deviation of the \"range measurement\n noise\".\n \n\n The height of the robot on the floor (default=0). Note\n that the beacon sensor on the robot may be at a different height,\n according to data within the observation object.\n \n\n Whether to make a simple check for potential\n good angles from the beacons to generate samples (disable to speed-up the\n preparation vs. making slower the drawn).\n This method fills out the member \"m_dataPerBeacon\".\n \n\n true if at least ONE beacon has been successfully loaded, false\n otherwise. In this case do not call \"rejectionSampling\" or an exception\n will be launch, since there is no information to generate samples.\n\nC++: mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(const class mrpt::maps::CLandmarksMap &, const class mrpt::obs::CObservationBeaconRanges &, float, const class mrpt::poses::CPose2D &, float, bool) --> bool", pybind11::arg("beaconsMap"), pybind11::arg("observation"), pybind11::arg("sigmaRanges"), pybind11::arg("oldPose"), pybind11::arg("robot_z"), pybind11::arg("autoCheckAngleRanges")); cl.def("assign", (class mrpt::slam::CRejectionSamplingRangeOnlyLocalization & (mrpt::slam::CRejectionSamplingRangeOnlyLocalization::*)(const class mrpt::slam::CRejectionSamplingRangeOnlyLocalization &)) &mrpt::slam::CRejectionSamplingRangeOnlyLocalization::operator=, "C++: mrpt::slam::CRejectionSamplingRangeOnlyLocalization::operator=(const class mrpt::slam::CRejectionSamplingRangeOnlyLocalization &) --> class mrpt::slam::CRejectionSamplingRangeOnlyLocalization &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - // mrpt::slam::observationsOverlap(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:26 - M("mrpt::slam").def("observationsOverlap", [](const class mrpt::obs::CObservation * a0, const class mrpt::obs::CObservation * a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("o1"), pybind11::arg("o2")); - M("mrpt::slam").def("observationsOverlap", (double (*)(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two observations (range\n [0,1]), possibly taking into account their relative positions.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("o1"), pybind11::arg("o2"), pybind11::arg("pose_o2_wrt_o1")); - - // mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:35 - M("mrpt::slam").def("observationsOverlap", [](const class std::shared_ptr & a0, const class std::shared_ptr & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("o1"), pybind11::arg("o2")); - M("mrpt::slam").def("observationsOverlap", (double (*)(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two observations (range\n [0,1]), possibly taking into account their relative positions.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("o1"), pybind11::arg("o2"), pybind11::arg("pose_o2_wrt_o1")); - - // mrpt::slam::observationsOverlap(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:49 - M("mrpt::slam").def("observationsOverlap", [](const class mrpt::obs::CSensoryFrame & a0, const class mrpt::obs::CSensoryFrame & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("sf1"), pybind11::arg("sf2")); - M("mrpt::slam").def("observationsOverlap", (double (*)(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two set of observations\n (range [0,1]), possibly taking into account their relative positions.\n This method computes the average between each of the observations in each\n SF.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("sf1"), pybind11::arg("sf2"), pybind11::arg("pose_sf2_wrt_sf1")); - - // mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:60 - M("mrpt::slam").def("observationsOverlap", [](const class std::shared_ptr & a0, const class std::shared_ptr & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("sf1"), pybind11::arg("sf2")); - M("mrpt::slam").def("observationsOverlap", (double (*)(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two set of observations\n (range [0,1]), possibly taking into account their relative positions.\n This method computes the average between each of the observations in each\n SF.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("sf1"), pybind11::arg("sf2"), pybind11::arg("pose_sf2_wrt_sf1")); - } diff --git a/python/src/mrpt/slam/observations_overlap.cpp b/python/src/mrpt/slam/observations_overlap.cpp new file mode 100644 index 0000000000..56aedfc383 --- /dev/null +++ b/python/src/mrpt/slam/observations_overlap.cpp @@ -0,0 +1,71 @@ +#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 +#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_slam_observations_overlap(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::slam::observationsOverlap(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:26 + M("mrpt::slam").def("observationsOverlap", [](const class mrpt::obs::CObservation * a0, const class mrpt::obs::CObservation * a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("o1"), pybind11::arg("o2")); + M("mrpt::slam").def("observationsOverlap", (double (*)(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two observations (range\n [0,1]), possibly taking into account their relative positions.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class mrpt::obs::CObservation *, const class mrpt::obs::CObservation *, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("o1"), pybind11::arg("o2"), pybind11::arg("pose_o2_wrt_o1")); + + // mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:35 + M("mrpt::slam").def("observationsOverlap", [](const class std::shared_ptr & a0, const class std::shared_ptr & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("o1"), pybind11::arg("o2")); + M("mrpt::slam").def("observationsOverlap", (double (*)(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two observations (range\n [0,1]), possibly taking into account their relative positions.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("o1"), pybind11::arg("o2"), pybind11::arg("pose_o2_wrt_o1")); + + // mrpt::slam::observationsOverlap(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:49 + M("mrpt::slam").def("observationsOverlap", [](const class mrpt::obs::CSensoryFrame & a0, const class mrpt::obs::CSensoryFrame & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("sf1"), pybind11::arg("sf2")); + M("mrpt::slam").def("observationsOverlap", (double (*)(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two set of observations\n (range [0,1]), possibly taking into account their relative positions.\n This method computes the average between each of the observations in each\n SF.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class mrpt::obs::CSensoryFrame &, const class mrpt::obs::CSensoryFrame &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("sf1"), pybind11::arg("sf2"), pybind11::arg("pose_sf2_wrt_sf1")); + + // mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) file:mrpt/slam/observations_overlap.h line:60 + M("mrpt::slam").def("observationsOverlap", [](const class std::shared_ptr & a0, const class std::shared_ptr & a1) -> double { return mrpt::slam::observationsOverlap(a0, a1); }, "", pybind11::arg("sf1"), pybind11::arg("sf2")); + M("mrpt::slam").def("observationsOverlap", (double (*)(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *)) &mrpt::slam::observationsOverlap, "Estimates the \"overlap\" or \"matching ratio\" of two set of observations\n (range [0,1]), possibly taking into account their relative positions.\n This method computes the average between each of the observations in each\n SF.\n \n\n This is used in mrpt::slam::CIncrementalMapPartitioner\n\nC++: mrpt::slam::observationsOverlap(const class std::shared_ptr &, const class std::shared_ptr &, const class mrpt::poses::CPose3D *) --> double", pybind11::arg("sf1"), pybind11::arg("sf2"), pybind11::arg("pose_sf2_wrt_sf1")); + +} diff --git a/python/src/pymrpt.cpp b/python/src/pymrpt.cpp index a2511e0eb6..097227d3db 100644 --- a/python/src/pymrpt.cpp +++ b/python/src/pymrpt.cpp @@ -349,6 +349,7 @@ void bind_mrpt_slam_data_association(std::function< pybind11::module &(std::stri void bind_mrpt_slam_CRangeBearingKFSLAM(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_bayes_CRejectionSamplingCapable(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_slam_CRejectionSamplingRangeOnlyLocalization(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_slam_observations_overlap(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_system_CRateTimer(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_system_crc(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_system_scheduler(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -775,6 +776,7 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_slam_CRangeBearingKFSLAM(M); bind_mrpt_bayes_CRejectionSamplingCapable(M); bind_mrpt_slam_CRejectionSamplingRangeOnlyLocalization(M); + bind_mrpt_slam_observations_overlap(M); bind_mrpt_system_CRateTimer(M); bind_mrpt_system_crc(M); bind_mrpt_system_scheduler(M); diff --git a/python/src/pymrpt.sources b/python/src/pymrpt.sources index f0cffc5a58..4524fc28cc 100644 --- a/python/src/pymrpt.sources +++ b/python/src/pymrpt.sources @@ -339,6 +339,7 @@ mrpt/slam/data_association.cpp mrpt/slam/CRangeBearingKFSLAM.cpp mrpt/bayes/CRejectionSamplingCapable.cpp mrpt/slam/CRejectionSamplingRangeOnlyLocalization.cpp +mrpt/slam/observations_overlap.cpp mrpt/system/CRateTimer.cpp mrpt/system/crc.cpp mrpt/system/scheduler.cpp diff --git a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi index 834566e71f..136283fa61 100644 --- a/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi +++ b/python/stubs-out/mrpt/pymrpt/mrpt/opengl/__init__.pyi @@ -368,6 +368,14 @@ class CAssimpModel(CRenderizableShaderTriangles, CRenderizableShaderWireFrame, C def renderUpdateBuffers(self) -> None: ... @overload def renderUpdateBuffers() -> void: ... + @overload + def split_triangles_rendering_bbox(self, bbox_size: float) -> None: ... + @overload + def split_triangles_rendering_bbox(constfloat) -> void: ... + @overload + def split_triangles_rendering_bbox(self) -> float: ... + @overload + def split_triangles_rendering_bbox() -> float: ... def traceRay(self, o: mrpt.pymrpt.mrpt.poses.CPose3D, dist: float) -> bool: ... class CAxis(CRenderizableShaderWireFrame): diff --git a/version_prefix.txt b/version_prefix.txt index eb11d714d8..0979147215 100644 --- a/version_prefix.txt +++ b/version_prefix.txt @@ -1,4 +1,4 @@ -2.14.0 +2.14.1 # IMPORTANT: This file is parsed by CMake, don't add any comment to # the first line. # This file is used in both Windows and Linux scripts to automatically