diff --git a/3rdparty/nanoflann b/3rdparty/nanoflann index a5ff746caa..37b31cb554 160000 --- a/3rdparty/nanoflann +++ b/3rdparty/nanoflann @@ -1 +1 @@ -Subproject commit a5ff746caa415f75577a2bca22b83411c268114f +Subproject commit 37b31cb554688a51a1f773420aa1b2c94c99237b diff --git a/3rdparty/nanogui b/3rdparty/nanogui index eb8b089f56..0e53d96e37 160000 --- a/3rdparty/nanogui +++ b/3rdparty/nanogui @@ -1 +1 @@ -Subproject commit eb8b089f56af06c0423b45213d25bf8201a1c2ba +Subproject commit 0e53d96e376396e3b2b8952b181ecc09fa203d46 diff --git a/apps/RawLogViewer/CScanAnimation.cpp b/apps/RawLogViewer/CScanAnimation.cpp index 0d608a5e07..3c1cd79649 100644 --- a/apps/RawLogViewer/CScanAnimation.cpp +++ b/apps/RawLogViewer/CScanAnimation.cpp @@ -464,9 +464,6 @@ bool CScanAnimation::update_opengl_viz(const CSensoryFrame& sf) CSetOfObjects::Ptr gl_objs; - CColouredPointsMap pointMap; - pointMap.loadFromVelodyneScan(*obs); - // Already in the map with the same sensor label? auto it_gl = m_gl_objects.find(sNameInMap); if (it_gl != m_gl_objects.end()) @@ -496,6 +493,46 @@ bool CScanAnimation::update_opengl_viz(const CSensoryFrame& sf) obs->point_cloud.clear_deep(); obs->unload(); } + else if (IS_CLASS(*it, CObservationRotatingScan)) + { + CObservationRotatingScan::Ptr obs = + std::dynamic_pointer_cast(it); + obs->load(); + + hasToRefreshViz = true; + if (tim_last == INVALID_TIMESTAMP || tim_last < obs->timestamp) + tim_last = obs->timestamp; + + CSetOfObjects::Ptr gl_objs; + + // Already in the map with the same sensor label? + auto it_gl = m_gl_objects.find(sNameInMap); + if (it_gl != m_gl_objects.end()) + { + // Update existing object: + TRenderObject& ro = it_gl->second; + gl_objs = std::dynamic_pointer_cast(ro.obj); + ro.timestamp = obs->timestamp; + } + else + { + // Create object: + gl_objs = CSetOfObjects::Create(); + + TRenderObject ro; + ro.obj = gl_objs; + ro.timestamp = obs->timestamp; + m_gl_objects[sNameInMap] = ro; + m_plot3D->getOpenGLSceneRef()->insert(gl_objs); + } + + auto& p = theMainWindow->getViewOptions()->m_params; + + // convert to viz object: + obsRotatingScan_to_viz(obs, p, *gl_objs); + + obs->unload(); + } else if (IS_CLASS(*it, CObservationPointCloud)) { auto obs = std::dynamic_pointer_cast(it); diff --git a/apps/RawLogViewer/main_show_selected_object.cpp b/apps/RawLogViewer/main_show_selected_object.cpp index faf279b7e4..7865d3b0cf 100644 --- a/apps/RawLogViewer/main_show_selected_object.cpp +++ b/apps/RawLogViewer/main_show_selected_object.cpp @@ -37,12 +37,21 @@ using namespace mrpt::poses; using namespace mrpt::rtti; using namespace std; -static void showImageInGLView(CMyGLCanvas& canvas, const mrpt::img::CImage& im) +namespace +{ +void showImageInGLView( + mrpt::opengl::Viewport& view, const mrpt::img::CImage& im) +{ + view.setImageView(im, true); +} + +void showImageInGLView(CMyGLCanvas& canvas, const mrpt::img::CImage& im) { auto scene = canvas.getOpenGLSceneRef(); - scene->getViewport()->setImageView(im); + showImageInGLView(*scene->getViewport(), im); canvas.Refresh(); } +} // Update selected item display: void xRawLogViewerFrame::SelectObjectInTreeView( @@ -157,6 +166,10 @@ void xRawLogViewerFrame::SelectObjectInTreeView( Notebook1->ChangeSelection(8); auto obs = std::dynamic_pointer_cast(sel_obj); + // Hide unused viewports: + bmp3Dobs_depth->setViewportVisibility(false); + bmp3Dobs_int->setViewportVisibility(false); + // Additional text description: This is not within // getDescriptionAsTextValue() because mrpt-maps is not available within // mrpt-obs: @@ -184,8 +197,8 @@ void xRawLogViewerFrame::SelectObjectInTreeView( // Update 3D view ========== #if RAWLOGVIEWER_HAS_3D auto openGLSceneRef = m_gl3DRangeScan->getOpenGLSceneRef(); - openGLSceneRef->clear(); - openGLSceneRef->insert(glPts); + openGLSceneRef->getViewport()->clear(); + openGLSceneRef->getViewport()->insert(glPts); m_gl3DRangeScan->Refresh(); #endif @@ -339,6 +352,10 @@ void xRawLogViewerFrame::SelectObjectInTreeView( obs->load(); // Make sure the 3D point cloud, etc... are all // loaded in memory. + // Hide unused viewports: + bmp3Dobs_depth->setViewportVisibility(false); + bmp3Dobs_int->setViewportVisibility(false); + // Render options // -------------------------------- const auto& p = pnViewOptions->m_params; @@ -347,15 +364,6 @@ void xRawLogViewerFrame::SelectObjectInTreeView( obs3Dscan_to_viz(obs, p, *glPts); -// Update 3D view ========== -#if RAWLOGVIEWER_HAS_3D - auto openGLSceneRef = m_gl3DRangeScan->getOpenGLSceneRef(); - openGLSceneRef->clear(); - openGLSceneRef->insert(glPts); - - m_gl3DRangeScan->Refresh(); -#endif - // Update intensity image ====== { CImage im; @@ -387,6 +395,15 @@ void xRawLogViewerFrame::SelectObjectInTreeView( obs->confidenceImage.unload(); // For externally-stored datasets } + +// Update 3D view ========== +#if RAWLOGVIEWER_HAS_3D + auto openGLSceneRef = m_gl3DRangeScan->getOpenGLSceneRef(); + openGLSceneRef->getViewport()->clear(); + openGLSceneRef->getViewport()->insert(glPts); + + m_gl3DRangeScan->Refresh(); +#endif obs->unload(); } @@ -398,6 +415,10 @@ void xRawLogViewerFrame::SelectObjectInTreeView( Notebook1->ChangeSelection(8); auto obs = std::dynamic_pointer_cast(sel_obj); + // Hide unused viewports: + bmp3Dobs_depth->setViewportVisibility(false); + bmp3Dobs_int->setViewportVisibility(false); + obs->generatePointCloud(); const auto& p = pnViewOptions->m_params; @@ -407,8 +428,8 @@ void xRawLogViewerFrame::SelectObjectInTreeView( // Update 3D view ========== #if RAWLOGVIEWER_HAS_3D auto openGLSceneRef = m_gl3DRangeScan->getOpenGLSceneRef(); - openGLSceneRef->clear(); - openGLSceneRef->insert(glPts); + openGLSceneRef->getViewport()->clear(); + openGLSceneRef->getViewport()->insert(glPts); this->m_gl3DRangeScan->Refresh(); @@ -425,6 +446,10 @@ void xRawLogViewerFrame::SelectObjectInTreeView( Notebook1->ChangeSelection(8); auto obs = std::dynamic_pointer_cast(sel_obj); + // Hide unused viewports: + bmp3Dobs_depth->setViewportVisibility(false); + bmp3Dobs_int->setViewportVisibility(false); + const auto& p = pnViewOptions->m_params; auto glPts = mrpt::opengl::CSetOfObjects::Create(); @@ -433,8 +458,8 @@ void xRawLogViewerFrame::SelectObjectInTreeView( // Update 3D view ========== #if RAWLOGVIEWER_HAS_3D auto openGLSceneRef = m_gl3DRangeScan->getOpenGLSceneRef(); - openGLSceneRef->clear(); - openGLSceneRef->insert(glPts); + openGLSceneRef->getViewport()->clear(); + openGLSceneRef->getViewport()->insert(glPts); this->m_gl3DRangeScan->Refresh(); #endif @@ -450,12 +475,16 @@ void xRawLogViewerFrame::SelectObjectInTreeView( // ---------------------------------------------------------------------- Notebook1->ChangeSelection(8); + // Hide unused viewports: + bmp3Dobs_depth->setViewportVisibility(false); + bmp3Dobs_int->setViewportVisibility(false); + // Update 3D view ========== #if RAWLOGVIEWER_HAS_3D auto openGLSceneRef = m_gl3DRangeScan->getOpenGLSceneRef(); - openGLSceneRef->clear(); - openGLSceneRef->insert(viz->getVisualization()); + openGLSceneRef->getViewport()->clear(); + openGLSceneRef->getViewport()->insert(viz->getVisualization()); this->m_gl3DRangeScan->Refresh(); #endif @@ -466,20 +495,68 @@ void xRawLogViewerFrame::SelectObjectInTreeView( // ---------------------------------------------------------------------- // CObservationRotatingScan // ---------------------------------------------------------------------- - Notebook1->ChangeSelection(3); + Notebook1->ChangeSelection(8); auto obs = std::dynamic_pointer_cast(sel_obj); + // Show viewports: + bmp3Dobs_depth->setViewportVisibility(true); + bmp3Dobs_int->setViewportVisibility(true); + // Get range image as bitmap: // --------------------------- - mrpt::img::CImage img_range; - img_range.setFromMatrix(obs->rangeImage, false); + int rangeHeight = 40; + { + mrpt::img::CImage img_range; + + float maxActualRange = obs->rangeImage.maxCoeff(); + if (maxActualRange == 0) maxActualRange = 1.0f; + + img_range.setFromMatrix( + obs->rangeImage.asEigen().cast() * + (1.0f / maxActualRange), + true /*already in [0,1]*/, true /*flip_vertical*/); + + showImageInGLView(*bmp3Dobs_depth, img_range); + + rangeHeight = img_range.getHeight(); + bmp3Dobs_depth->setViewportPosition( + 50, -2 - rangeHeight, -30, rangeHeight); + } - showImageInGLView(*bmpObsStereoLeft, img_range); + int intensityHeight = 40; - mrpt::img::CImage img_intensity; - img_intensity.setFromMatrix(obs->intensityImage, false); + if (!obs->intensityImage.empty()) + { + mrpt::img::CImage img_intensity; + + float maxActualInt = obs->intensityImage.maxCoeff(); + if (maxActualInt == 0) maxActualInt = 1.0f; + + img_intensity.setFromMatrix( + obs->intensityImage.asEigen().cast() * + (1.0f / maxActualInt), + true /*already in [0,1]*/, true /*flip_vertical*/); + + showImageInGLView(*bmp3Dobs_int, img_intensity); + + intensityHeight = img_intensity.getHeight(); + bmp3Dobs_int->setViewportPosition( + 50, -2 - rangeHeight - 2 - intensityHeight, -30, + intensityHeight); + } + + bmp3Dobs_3dcloud->addTextMessage(2, -2 - rangeHeight / 2, "Range", 0); + bmp3Dobs_3dcloud->addTextMessage( + 2, -2 - rangeHeight - 2 - intensityHeight / 2, "Intensity", 1); + + // 3D points: + const auto& p = pnViewOptions->m_params; + + auto glPts = mrpt::opengl::CSetOfObjects::Create(); + obsRotatingScan_to_viz(obs, p, *glPts); - showImageInGLView(*bmpObsStereoRight, img_intensity); + bmp3Dobs_3dcloud->clear(); + bmp3Dobs_3dcloud->insert(glPts); } if (classID->derivedFrom(CLASS_ID(CObservation))) diff --git a/apps/RawLogViewer/xRawLogViewerMain.cpp b/apps/RawLogViewer/xRawLogViewerMain.cpp index 149f0311a7..72914a531b 100644 --- a/apps/RawLogViewer/xRawLogViewerMain.cpp +++ b/apps/RawLogViewer/xRawLogViewerMain.cpp @@ -363,7 +363,6 @@ xRawLogViewerFrame::xRawLogViewerFrame(wxWindow* parent, wxWindowID id) wxMenuItem* MenuItem26; wxMenuItem* MenuItem25; wxMenuItem* MenuItem2; - wxFlexGridSizer* FlexGridSizer10; wxFlexGridSizer* FlexGridSizer3; wxMenuItem* MenuItem55; wxMenuItem* MenuItem1; @@ -394,7 +393,6 @@ xRawLogViewerFrame::xRawLogViewerFrame(wxWindow* parent, wxWindowID id) wxMenuBar* MenuBar1; wxFlexGridSizer* FlexGridSizer6; wxFlexGridSizer* fgzMain; - wxFlexGridSizer* FlexGridSizer11; wxMenuItem* MenuItem43; wxMenu* Menu2; wxMenuItem* MenuItem18; @@ -809,51 +807,54 @@ xRawLogViewerFrame::xRawLogViewerFrame(wxWindow* parent, wxWindowID id) pn_CObservationBearingRange->SetSizer(BoxSizer4); BoxSizer4->Fit(pn_CObservationBearingRange); BoxSizer4->SetSizeHints(pn_CObservationBearingRange); + + // Panel[8]: pn_CObservation3DRangeScan pn_CObservation3DRangeScan = new wxPanel( Notebook1, ID_PANEL19, wxDefaultPosition, wxDefaultSize, wxTAB_TRAVERSAL, _T("ID_PANEL19")); FlexGridSizer8 = new wxFlexGridSizer(1, 1, 0, 0); FlexGridSizer8->AddGrowableCol(0); FlexGridSizer8->AddGrowableRow(0); + + // Tabs for 3D observations channels & options: nb_3DObsChannels = new wxNotebook( pn_CObservation3DRangeScan, ID_NOTEBOOK_3DOBS, wxDefaultPosition, wxDefaultSize, 0, _T("ID_NOTEBOOK_3DOBS")); + // Tab: 3D view + range + intensity: pn3Dobs_3D = new wxPanel( nb_3DObsChannels, ID_PANEL20, wxDefaultPosition, wxDefaultSize, wxTAB_TRAVERSAL, _T("ID_PANEL20")); FlexGridSizer9 = new wxFlexGridSizer(1, 1, 0, 0); FlexGridSizer9->AddGrowableCol(0); FlexGridSizer9->AddGrowableRow(0); + m_gl3DRangeScan = new CMyGLCanvas( pn3Dobs_3D, ID_XY_GLCANVAS, wxDefaultPosition, wxDefaultSize, wxTAB_TRAVERSAL, _T("ID_XY_GLCANVAS")); - FlexGridSizer9->Add(m_gl3DRangeScan, 1, wxEXPAND, 0); + FlexGridSizer9->Add(m_gl3DRangeScan, 1, wxEXPAND, 2); + + // OpenGL Views: + bmp3Dobs_depth = + m_gl3DRangeScan->getOpenGLSceneRef()->createViewport("depth"); + bmp3Dobs_depth->setCustomBackgroundColor({.0f, .0f, .0f}); + + bmp3Dobs_int = + m_gl3DRangeScan->getOpenGLSceneRef()->createViewport("intensity"); + bmp3Dobs_int->setCustomBackgroundColor({.0f, .0f, .0f}); + + bmp3Dobs_3dcloud = + m_gl3DRangeScan->getOpenGLSceneRef()->getViewport("main"); + + // The correct sizes will be updated anyway in SelectObjectInTreeView() + bmp3Dobs_depth->setViewportPosition(2, -50 - 2, 1.0, 50); + bmp3Dobs_int->setViewportPosition(2, -100 - 2 * 2, 1.0, 50); + + // panel done: pn3Dobs_3D->SetSizer(FlexGridSizer9); FlexGridSizer9->Fit(pn3Dobs_3D); FlexGridSizer9->SetSizeHints(pn3Dobs_3D); - pn3Dobs_Depth = new wxPanel( - nb_3DObsChannels, ID_PANEL21, wxDefaultPosition, wxDefaultSize, - wxTAB_TRAVERSAL, _T("ID_PANEL21")); - FlexGridSizer10 = new wxFlexGridSizer(1, 1, 0, 0); - FlexGridSizer10->AddGrowableCol(0); - FlexGridSizer10->AddGrowableRow(0); - bmp3Dobs_depth = new CMyGLCanvas(pn3Dobs_Depth, ID_STATICBITMAP4); - FlexGridSizer10->Add(bmp3Dobs_depth, 1, wxEXPAND, 0); - pn3Dobs_Depth->SetSizer(FlexGridSizer10); - FlexGridSizer10->Fit(pn3Dobs_Depth); - FlexGridSizer10->SetSizeHints(pn3Dobs_Depth); - pn3Dobs_Int = new wxPanel( - nb_3DObsChannels, ID_PANEL22, wxDefaultPosition, wxDefaultSize, - wxTAB_TRAVERSAL, _T("ID_PANEL22")); - FlexGridSizer11 = new wxFlexGridSizer(1, 1, 0, 0); - FlexGridSizer11->AddGrowableCol(0); - FlexGridSizer11->AddGrowableRow(0); - bmp3Dobs_int = new CMyGLCanvas(pn3Dobs_Int, ID_STATICBITMAP5); - FlexGridSizer11->Add(bmp3Dobs_int, 1, wxEXPAND, 0); - pn3Dobs_Int->SetSizer(FlexGridSizer11); - FlexGridSizer11->Fit(pn3Dobs_Int); - FlexGridSizer11->SetSizeHints(pn3Dobs_Int); + pn3Dobs_Conf = new wxPanel( nb_3DObsChannels, ID_PANEL23, wxDefaultPosition, wxDefaultSize, wxTAB_TRAVERSAL, _T("ID_PANEL23")); @@ -869,9 +870,7 @@ xRawLogViewerFrame::xRawLogViewerFrame(wxWindow* parent, wxWindowID id) pnViewOptions = new ViewOptions3DPoints( nb_3DObsChannels, ID_PANEL_VIEW_3D_POINT_OPTIONS); - nb_3DObsChannels->AddPage(pn3Dobs_3D, _("3D view"), false); - nb_3DObsChannels->AddPage(pn3Dobs_Depth, _("Depth"), false); - nb_3DObsChannels->AddPage(pn3Dobs_Int, _("Intensity"), false); + nb_3DObsChannels->AddPage(pn3Dobs_3D, _("3D/Range/Intensity"), true); nb_3DObsChannels->AddPage(pn3Dobs_Conf, _("Confidence"), false); nb_3DObsChannels->AddPage(pnViewOptions, _("Visualization options"), false); diff --git a/apps/RawLogViewer/xRawLogViewerMain.h b/apps/RawLogViewer/xRawLogViewerMain.h index d39c2ea502..b87f923417 100644 --- a/apps/RawLogViewer/xRawLogViewerMain.h +++ b/apps/RawLogViewer/xRawLogViewerMain.h @@ -282,7 +282,6 @@ class xRawLogViewerFrame : public wxFrame wxMenuItem* MenuItem50; wxMenuItem* MenuItem68; wxMenu* Menu14; - CMyGLCanvas* bmp3Dobs_depth; wxMenu* Menu3; wxCustomButton* Button6; wxMenu* Menu20; @@ -343,14 +342,12 @@ class xRawLogViewerFrame : public wxFrame wxCustomButton* Button3; CRawlogTreeView* m_treeView; wxMenuItem* MenuItem64; - CMyGLCanvas* bmp3Dobs_int; wxTextCtrl* memo; wxMenuItem* MenuItem28; wxMenuItem* MenuItem63; CMyGLCanvas* m_gl3DRangeScan; wxPanel* Panel7; wxMenuItem* MenuItem78; - wxPanel* pn3Dobs_Depth; wxMenuItem* mnuCreateAVI; wxMenuItem* MenuItem83; wxMenu* MenuItem45; @@ -365,7 +362,6 @@ class xRawLogViewerFrame : public wxFrame wxBoxSizer* BoxSizer1; CMyGLCanvas* bmp3Dobs_conf; wxMenuItem* MenuItem58; - wxPanel* pn3Dobs_Int; wxTextCtrl* memStats; wxPanel* pn_CObservationStereoImage; wxPanel* Panel2; @@ -400,6 +396,10 @@ class xRawLogViewerFrame : public wxFrame wxTextCtrl* edSelectedTimeInfo = nullptr; CMyGLCanvas* m_glTimeLine = nullptr; + mrpt::opengl::Viewport::Ptr bmp3Dobs_depth; + mrpt::opengl::Viewport::Ptr bmp3Dobs_int; + mrpt::opengl::Viewport::Ptr bmp3Dobs_3dcloud; + void OnComboImageDirsChange(wxCommandEvent& event); void On3DObsPagesChange(wxBookCtrlEvent& event); diff --git a/apps/SceneViewer3D/_DSceneViewerMain.cpp b/apps/SceneViewer3D/_DSceneViewerMain.cpp index ec959ec61b..36728c63ba 100644 --- a/apps/SceneViewer3D/_DSceneViewerMain.cpp +++ b/apps/SceneViewer3D/_DSceneViewerMain.cpp @@ -1698,12 +1698,12 @@ void _DSceneViewerFrame::OnMenuItemImportPLYPointCloud(wxCommandEvent& event) if (!res) { wxMessageBox( - _("Error loading or parsing the PLY file"), _("Exception"), - wxOK, this); + ply_obj->getLoadPLYErrorString(), + "Error loading or parsing the PLY file", wxOK, this); } else { - auto openGLSceneRef = m_canvas->getOpenGLSceneRef(); + auto& openGLSceneRef = m_canvas->getOpenGLSceneRef(); // Set the point cloud as the only object in scene: openGLSceneRef = std::make_shared(); diff --git a/apps/observations2map/observations2map_main.cpp b/apps/observations2map/observations2map_main.cpp index 30ad1cb4ca..bbdc98c09d 100644 --- a/apps/observations2map/observations2map_main.cpp +++ b/apps/observations2map/observations2map_main.cpp @@ -79,9 +79,12 @@ int main(int argc, char** argv) cout << "done: " << simplemap.size() << " observations." << endl; // Create metric maps: + CConfigFile cfg(configFile); + + ASSERT_(cfg.sectionExists(METRIC_MAP_CONFIG_SECTION)); + TSetOfMetricMapInitializers mapCfg; - mapCfg.loadFromConfigFile( - CConfigFile(configFile), METRIC_MAP_CONFIG_SECTION); + mapCfg.loadFromConfigFile(cfg, METRIC_MAP_CONFIG_SECTION); CMultiMetricMap metricMap; metricMap.setListOfMaps(mapCfg); diff --git a/apps/rosbag2rawlog/CMakeLists.txt b/apps/rosbag2rawlog/CMakeLists.txt index fef7f92997..546afa8b87 100644 --- a/apps/rosbag2rawlog/CMakeLists.txt +++ b/apps/rosbag2rawlog/CMakeLists.txt @@ -6,7 +6,7 @@ endif() project(rosbag2rawlog) # ================================================ -# TARGET: gps2rawlog +# TARGET: rosbag2rawlog # ================================================ # Define the executable target: add_executable(${PROJECT_NAME} diff --git a/appveyor.yml b/appveyor.yml index 75ca0852f7..8cd367a213 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 2.11.3-{branch}-build{build} +version: 2.11.4-{branch}-build{build} os: Visual Studio 2019 diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 4c67f704f0..315252e79c 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,5 +1,28 @@ \page changelog Change Log +# Version 2.11.4: Released Dec 15th, 2023 +- Changes in apps: + - RawLogViewer: visualize mrpt::obs::CObservationRotatingScan as point cloud + range image + intensity image. + - rawlog-edit: `--info` command now also shows the type of each sensor label. +- Changes in libraries: + - \ref mrpt_maps_grp + - Use nanoflann RKNN search in mrpt::maps::CPointsMap::nn_radius_search() + - Added a new point cloud class mrpt::maps::CPointsMapXYZIRT, including its Python and ROS wrappers. + - \ref mrpt_math_grp + - mrpt::math::KDTreeCapable: Add optional argument maximumSearchDistanceSqr in many API methods to exploit the new nanoflann RKNN search method. + - \ref mrpt_opengl_grp + - mrpt::opengl::PLY_Importer: Add support for importing point clouds with the `timestamp` property per point. + - \ref mrpt_obs_grp + - mrpt::obs::CObservationRotatingScan: + - Moved from the library mrpt-maps to mrpt-obs, since it no longer requires any mrpt::maps class. + - Complete its implementation: insertion into point cloud, observation likelihood, visualization in RawLogViewer, etc. +- BUG FIXES: + - Fix missing Threads::Threads downstream due to missing `find_dependency(Threads)` in MRPT cmake config files. + - Fix broken import of PLY files in SceneViewer3D (empty scene even if correctly imported). + - mrpt::math::CMatrixDynamic constructor from (row,col) was not marked explicit, leading to potential problems. + - mrpt::opengl::Viewport::setViewportPosition() did not handle negative width values as expected (i.e. pixel distances from the opposite corner). + + # Version 2.11.3: Released Nov 21st, 2023 - Changes in libraries: - \ref mrpt_core_grp diff --git a/libs/apps/src/rawlog-edit_externalize.cpp b/libs/apps/src/rawlog-edit_externalize.cpp index 1c0763b62e..1e8e780ed4 100644 --- a/libs/apps/src/rawlog-edit_externalize.cpp +++ b/libs/apps/src/rawlog-edit_externalize.cpp @@ -13,6 +13,7 @@ #include #include #include +#include #include #include "rawlog-edit-declarations.h" @@ -161,6 +162,29 @@ DECLARE_OP_FUNCTION(op_externalize) else entries_skipped++; } + else if (IS_CLASS(*obs, CObservationRotatingScan)) + { + auto o = + std::dynamic_pointer_cast(obs); + + if (!o->organizedPoints.empty() && !o->isExternallyStored()) + { + const string fileName = "scan_"s + label_time + + (m_external_txt ? ".txt"s : ".bin"s); + o->setAsExternalStorage( + fileName, + m_external_txt + ? CObservationRotatingScan::ExternalStorageFormat:: + PlainTextFile + : CObservationRotatingScan::ExternalStorageFormat:: + MRPT_Serialization); + + o->unload(); // this actually saves the data to disk + entries_converted++; + } + else + entries_skipped++; + } else if (IS_CLASS(*obs, CObservation3DRangeScan)) { CObservation3DRangeScan::Ptr obs3D = diff --git a/libs/apps/src/rawlog-edit_info.cpp b/libs/apps/src/rawlog-edit_info.cpp index 9be8751559..be1504a896 100644 --- a/libs/apps/src/rawlog-edit_info.cpp +++ b/libs/apps/src/rawlog-edit_info.cpp @@ -159,23 +159,19 @@ DECLARE_OP_FUNCTION(op_info) } cout << "\n"; - for (auto it = proc.infoPerSensorLabel.begin(); - it != proc.infoPerSensorLabel.end(); ++it) + for (auto& [label, ips] : proc.infoPerSensorLabel) { - const TTimeStamp tf = it->second.tim_first; - const TTimeStamp tl = it->second.tim_last; + const TTimeStamp tf = ips.tim_first; + const TTimeStamp tl = ips.tim_last; double Hz = 0, dur = 0; if (tf != INVALID_TIMESTAMP && tl != INVALID_TIMESTAMP) { dur = mrpt::system::timeDifference(tf, tl); - Hz = double( - it->second.occurrences > 1 ? it->second.occurrences - 1 - : 1) / - dur; + Hz = double(ips.occurrences > 1 ? ips.occurrences - 1 : 1) / dur; } cout << "Sensor (Label/Occurs/Rate/Durat.) : " << format( - "%15s /%7u /%5.03f /%.03f\n", it->first.c_str(), - (unsigned)it->second.occurrences, Hz, dur); + "%15s /%7u /%7.03f /%6.03f (%s)\n", label.c_str(), + (unsigned)ips.occurrences, Hz, dur, ips.className.c_str()); } } diff --git a/libs/core/CMakeLists.txt b/libs/core/CMakeLists.txt index b702ac86f4..fb4722eec0 100644 --- a/libs/core/CMakeLists.txt +++ b/libs/core/CMakeLists.txt @@ -5,6 +5,7 @@ define_mrpt_lib( # Lib name core # Dependencies + Threads # invoke find_dependency(Threads) in "*-config.cmake" ) if(BUILD_mrpt-core) diff --git a/libs/img/include/mrpt/img/CImage.h b/libs/img/include/mrpt/img/CImage.h index efa63f7614..bb58738890 100644 --- a/libs/img/include/mrpt/img/CImage.h +++ b/libs/img/include/mrpt/img/CImage.h @@ -830,7 +830,9 @@ class CImage : public mrpt::serialization::CSerializable, public CCanvas * \sa getAsMatrix */ template - void setFromMatrix(const MAT& m, bool matrix_is_normalized = true) + void setFromMatrix( + const MAT& m, bool matrix_is_normalized = true, + bool flip_vertically = false) { MRPT_START const unsigned int lx = m.cols(); @@ -840,7 +842,8 @@ class CImage : public mrpt::serialization::CSerializable, public CCanvas { // Matrix: [0,1] for (unsigned int y = 0; y < ly; y++) { - auto* pixels = ptrLine(y); + auto* pixels = + ptrLine(flip_vertically ? (ly - 1 - y) : y); for (unsigned int x = 0; x < lx; x++) (*pixels++) = static_cast(m.coeff(y, x) * 255); } @@ -849,7 +852,8 @@ class CImage : public mrpt::serialization::CSerializable, public CCanvas { // Matrix: [0,255] for (unsigned int y = 0; y < ly; y++) { - auto* pixels = ptrLine(y); + auto* pixels = + ptrLine(flip_vertically ? (ly - 1 - y) : y); for (unsigned int x = 0; x < lx; x++) (*pixels++) = static_cast(m.coeff(y, x)); } diff --git a/libs/maps/include/mrpt/maps.h b/libs/maps/include/mrpt/maps.h index a634b82d44..2fa39a44b5 100644 --- a/libs/maps/include/mrpt/maps.h +++ b/libs/maps/include/mrpt/maps.h @@ -29,6 +29,7 @@ MRPT_WARNING( #include #include #include +#include #include #include #include diff --git a/libs/maps/include/mrpt/maps/CColouredPointsMap.h b/libs/maps/include/mrpt/maps/CColouredPointsMap.h index d9f36b7bd0..063bcbe01f 100644 --- a/libs/maps/include/mrpt/maps/CColouredPointsMap.h +++ b/libs/maps/include/mrpt/maps/CColouredPointsMap.h @@ -12,6 +12,7 @@ #include #include #include +#include #include #include @@ -337,6 +338,14 @@ class CColouredPointsMap : public CPointsMap /** In a base class, reserve memory to prepare subsequent calls to * PLY_import_set_vertex */ void PLY_import_set_vertex_count(size_t N) override; + + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } + /** @} */ /** @name Redefinition of PLY Export virtual methods from CPointsMap @@ -356,7 +365,6 @@ class CColouredPointsMap : public CPointsMap } // namespace maps -#include namespace opengl { /** Specialization diff --git a/libs/maps/include/mrpt/maps/CPointsMap.h b/libs/maps/include/mrpt/maps/CPointsMap.h index 6fb6c6e42f..58e875cf67 100644 --- a/libs/maps/include/mrpt/maps/CPointsMap.h +++ b/libs/maps/include/mrpt/maps/CPointsMap.h @@ -575,6 +575,43 @@ class CPointsMap : public CMetricMap, { return m_z; } + + virtual auto getPointsBufferRef_intensity() const + -> const mrpt::aligned_std_vector* + { + return nullptr; + } + + virtual auto getPointsBufferRef_ring() const + -> const mrpt::aligned_std_vector* + { + return nullptr; + } + + virtual auto getPointsBufferRef_timestamp() const + -> const mrpt::aligned_std_vector* + { + return nullptr; + } + + virtual auto getPointsBufferRef_intensity() + -> mrpt::aligned_std_vector* + { + return nullptr; + } + + virtual auto getPointsBufferRef_ring() + -> mrpt::aligned_std_vector* + { + return nullptr; + } + + virtual auto getPointsBufferRef_timestamp() + -> mrpt::aligned_std_vector* + { + return nullptr; + } + /** Returns a copy of the 2D/3D points as a std::vector of float * coordinates. * If decimation is greater than 1, only 1 point out of that number will be @@ -1210,6 +1247,12 @@ class CPointsMap : public CMetricMap, void PLY_import_set_vertex( size_t idx, const mrpt::math::TPoint3Df& pt, const mrpt::img::TColorf* pt_color = nullptr) override; + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } /** @} */ /** @name PLY Export virtual methods to implement in base classes diff --git a/libs/maps/include/mrpt/maps/CPointsMapXYZI.h b/libs/maps/include/mrpt/maps/CPointsMapXYZI.h index bb6bad6300..35ad7811e4 100644 --- a/libs/maps/include/mrpt/maps/CPointsMapXYZI.h +++ b/libs/maps/include/mrpt/maps/CPointsMapXYZI.h @@ -9,11 +9,9 @@ #pragma once #include -#include -#include #include +#include #include -#include namespace mrpt { @@ -172,9 +170,14 @@ class CPointsMapXYZI : public CPointsMap /** Provides a direct access to a read-only reference of the internal * intensity point buffer. \sa getPointsBufferRef_x() */ auto getPointsBufferRef_intensity() const - -> const mrpt::aligned_std_vector& + -> const mrpt::aligned_std_vector* override + { + return &m_intensity; + } + auto getPointsBufferRef_intensity() + -> mrpt::aligned_std_vector* override { - return m_intensity; + return &m_intensity; } /** Returns true if the point map has a color field for each point */ @@ -271,6 +274,14 @@ class CPointsMapXYZI : public CPointsMap const mrpt::img::TColorf* pt_color = nullptr) override; void PLY_import_set_vertex_count(size_t N) override; + + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } + /** @} */ /** @name Redefinition of PLY Export virtual methods from CPointsMap @@ -289,7 +300,6 @@ class CPointsMapXYZI : public CPointsMap } // namespace maps -#include namespace opengl { /** Specialization diff --git a/libs/maps/include/mrpt/maps/CPointsMapXYZIRT.h b/libs/maps/include/mrpt/maps/CPointsMapXYZIRT.h new file mode 100644 index 0000000000..556af68a3d --- /dev/null +++ b/libs/maps/include/mrpt/maps/CPointsMapXYZIRT.h @@ -0,0 +1,429 @@ +/* +------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | https://www.mrpt.org/ | + | | + | Copyright (c) 2005-2023, Individual contributors, see AUTHORS file | + | See: https://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See: https://www.mrpt.org/License | + +------------------------------------------------------------------------+ */ +#pragma once + +#include +#include +#include +#include + +namespace mrpt::maps +{ +class CPointsMapXYZI; + +/** A map of 3D points with channels: X,Y,Z,I (intensity), R (ring), T (time). + * + * - `ring` (`uint16_t`) holds the "ring number", or the "row index" for + * organized point clouds. + * - `time` (`float`) uses the convention of time offset **in seconds** since + * the first firing of the cloud. So, for example a 10 Hz LIDAR will produce + * clouds with XYZIRT points with `time` in the range [0, 0.1] seconds. + * + * All three fields I,R,T are optional. Empty vectors are used to represent that + * any of these fields is empty, and trying to read them will silently read + * zeros, but you can check their validity with: + * - `hasIntensityField()` + * - `hasRingField()` + * - `hasTimeField()` + * + * \sa mrpt::maps::CPointsMap, mrpt::maps::CMetricMap + * \ingroup mrpt_maps_grp + */ +class CPointsMapXYZIRT : public CPointsMap +{ + DEFINE_SERIALIZABLE(CPointsMapXYZIRT, mrpt::maps) + + public: + CPointsMapXYZIRT() = default; + + CPointsMapXYZIRT(const CPointsMap& o) { CPointsMap::operator=(o); } + CPointsMapXYZIRT(const CPointsMapXYZIRT& o); + explicit CPointsMapXYZIRT(const CPointsMapXYZI& o); + CPointsMapXYZIRT& operator=(const CPointsMap& o); + CPointsMapXYZIRT& operator=(const CPointsMapXYZIRT& o); + CPointsMapXYZIRT& operator=(const CPointsMapXYZI& o); + + /** @name Pure virtual interfaces to be implemented by any class derived + from CPointsMap + @{ */ + + // By default, these method will grow all fields XYZIRT. See other methods + // below. + void reserve(size_t newLength) override; // See base class docs + void resize(size_t newLength) override; // See base class docs + void setSize(size_t newLength) override; // See base class docs + + /// Like reserve(), but allows selecting which fields are present or not: + void reserve_XYZIRT( + size_t n, bool hasIntensity, bool hasRing, bool hasTime); + + /// Like resize(), but allows selecting which fields are present or not: + void resize_XYZIRT( + size_t newLength, bool hasIntensity, bool hasRing, bool hasTime); + + bool hasIntensityField() const { return !m_intensity.empty(); } + bool hasRingField() const { return !m_ring.empty(); } + bool hasTimeField() const { return !m_time.empty(); } + + /** The virtual method for \a insertPoint() *without* calling + * mark_as_modified() */ + void insertPointFast(float x, float y, float z = 0) override; + + /** Get all the data fields for one point as a vector: [X Y Z I] + * Unlike getPointAllFields(), this method does not check for index out of + * bounds + * \sa getPointAllFields, setPointAllFields, setPointAllFieldsFast + */ + void getPointAllFieldsFast( + size_t index, std::vector& point_data) const override + { + point_data.resize(6); + point_data[0] = m_x[index]; + point_data[1] = m_y[index]; + point_data[2] = m_z[index]; + point_data[3] = hasIntensityField() ? m_intensity[index] : 0; + point_data[4] = hasRingField() ? m_ring[index] : 0; + point_data[5] = hasTimeField() ? m_time[index] : 0; + } + + /** Set all the data fields for one point as a vector: [X Y Z I R T] + * Unlike setPointAllFields(), this method does not check for index out of + * bounds + * \sa setPointAllFields, getPointAllFields, getPointAllFieldsFast + */ + void setPointAllFieldsFast( + size_t index, const std::vector& point_data) override + { + ASSERT_(point_data.size() == 6); + m_x[index] = point_data[0]; + m_y[index] = point_data[1]; + m_z[index] = point_data[2]; + if (hasIntensityField()) m_intensity[index] = point_data[3]; + if (hasRingField()) m_ring[index] = point_data[4]; + if (hasTimeField()) m_time[index] = point_data[5]; + } + + /** See CPointsMap::loadFromRangeScan() */ + void loadFromRangeScan( + const mrpt::obs::CObservation2DRangeScan& rangeScan, + const std::optional& robotPose = + std::nullopt) override; + /** See CPointsMap::loadFromRangeScan() */ + void loadFromRangeScan( + const mrpt::obs::CObservation3DRangeScan& rangeScan, + const std::optional& robotPose = + std::nullopt) override; + + protected: + // See base class + void impl_copyFrom(const CPointsMap& obj) override; + // See base class + void addFrom_classSpecific( + const CPointsMap& anotherMap, size_t nPreviousPoints, + const bool filterOutPointsAtZero) override; + + // Friend methods: + template + friend struct detail::loadFromRangeImpl; + template + friend struct detail::pointmap_traits; + + public: + /** @} */ + + /** Save to a text file. In each line contains `X Y Z I R T` + * Returns false if any error occured, true elsewere. + */ + bool saveXYZIRT_to_text_file(const std::string& file) const; + + /** Loads from a text file, each line having "X Y Z I", I in [0,1]. + * Returns false if any error occured, true elsewere. */ + bool loadXYZIRT_from_text_file(const std::string& file); + + /** Changes a given point from map. First index is 0. + * \exception Throws std::exception on index out of bound. + */ + void setPointRGB( + size_t index, float x, float y, float z, float R_intensity, + float G_ignored, float B_ignored) override; + + /** Adds a new point given its coordinates and color (colors range is [0,1]) + */ + void insertPointRGB( + float x, float y, float z, float R_intensity, float G_ignored, + float B_ignored) override; + + /** Changes the intensity of a given point from the map. First index is 0. + * \exception Throws std::exception on index out of bound. + */ + void setPointIntensity(size_t index, float intensity) + { + ASSERT_LT_(index, m_intensity.size()); + m_intensity[index] = intensity; + // mark_as_modified(); // No need to rebuild KD-trees, etc... + } + + /** Changes the ring of a given point from the map. + * \exception Throws std::exception on index out of bound. + */ + void setPointRing(size_t index, uint16_t ring) + { + ASSERT_LT_(index, m_ring.size()); + m_ring[index] = ring; + // mark_as_modified(); // No need to rebuild KD-trees, etc... + } + + /** Changes the time of a given point from the map. First index is 0. + * \exception Throws std::exception on index out of bound. + */ + void setPointTime(size_t index, float time) + { + ASSERT_LT_(index, m_time.size()); + m_time[index] = time; + // mark_as_modified(); // No need to rebuild KD-trees, etc... + } + + /** Like \c setPointColor but without checking for out-of-index erors */ + inline void setPointColor_fast(size_t index, float R, float G, float B) + { + m_intensity[index] = R; + } + + /** Retrieves a point and its color (colors range is [0,1]) + */ + void getPointRGB( + size_t index, float& x, float& y, float& z, float& R_intensity, + float& G_intensity, float& B_intensity) const override; + + /** Gets point intensity ([0,1]), or 0 if field is not present */ + float getPointIntensity(size_t index) const + { + if (m_intensity.empty()) return 0; + ASSERT_LT_(index, m_intensity.size()); + return m_intensity[index]; + } + /** Gets point ring number, or 0 if field is not present */ + uint16_t getPointRing(size_t index) const + { + if (m_ring.empty()) return 0; + ASSERT_LT_(index, m_ring.size()); + return m_ring[index]; + } + /** Gets point time, or 0 if field is not present */ + float getPointTime(size_t index) const + { + if (m_time.empty()) return 0; + ASSERT_LT_(index, m_time.size()); + return m_time[index]; + } + + /** Like \c getPointColor but without checking for out-of-index erors */ + inline float getPointIntensity_fast(size_t index) const + { + return m_intensity[index]; + } + + auto getPointsBufferRef_intensity() const + -> const mrpt::aligned_std_vector* override + { + return &m_intensity; + } + + auto getPointsBufferRef_ring() const + -> const mrpt::aligned_std_vector* override + { + return &m_ring; + } + + auto getPointsBufferRef_timestamp() const + -> const mrpt::aligned_std_vector* override + { + return &m_time; + } + + auto getPointsBufferRef_intensity() + -> mrpt::aligned_std_vector* override + { + return &m_intensity; + } + + auto getPointsBufferRef_ring() + -> mrpt::aligned_std_vector* override + { + return &m_ring; + } + + auto getPointsBufferRef_timestamp() + -> mrpt::aligned_std_vector* override + { + return &m_time; + } + + /** Returns true if the point map has a color field for each point */ + bool hasColorPoints() const override { return true; } + + /** Override of the default 3D scene builder to account for the individual + * points' color. + */ + void getVisualizationInto( + mrpt::opengl::CSetOfObjects& outObj) const override; + + protected: + /** The intensity/reflectance data */ + mrpt::aligned_std_vector m_intensity; + + /** The ring data */ + mrpt::aligned_std_vector m_ring; + + /** The time data (see description at the beginning of the class) */ + mrpt::aligned_std_vector m_time; + + /** Clear the map, erasing all the points */ + void internal_clear() override; + + /** @name Redefinition of PLY Import virtual methods from CPointsMap + @{ */ + void PLY_import_set_vertex( + size_t idx, const mrpt::math::TPoint3Df& pt, + const mrpt::img::TColorf* pt_color = nullptr) override; + + void PLY_import_set_vertex_count(size_t N) override; + + void PLY_import_set_vertex_timestamp( + size_t idx, const double unixTimestamp) override + { + m_time.at(idx) = unixTimestamp; + } + + /** @} */ + + /** @name Redefinition of PLY Export virtual methods from CPointsMap + @{ */ + void PLY_export_get_vertex( + size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color, + mrpt::img::TColorf& pt_color) const override; + /** @} */ + + MAP_DEFINITION_START(CPointsMapXYZIRT) + mrpt::maps::CPointsMap::TInsertionOptions insertionOpts; + mrpt::maps::CPointsMap::TLikelihoodOptions likelihoodOpts; + MAP_DEFINITION_END(CPointsMapXYZIRT) + +}; // End of class def. + +} // namespace mrpt::maps + +namespace mrpt::opengl +{ +/** Specialization + * mrpt::opengl::PointCloudAdapter + * \ingroup mrpt_adapters_grp */ +template <> +class PointCloudAdapter +{ + private: + mrpt::maps::CPointsMapXYZIRT& m_obj; + + public: + /** The type of each point XYZ coordinates */ + using coords_t = float; + /** Has any color RGB info? */ + static constexpr bool HAS_RGB = true; + /** Has native RGB info (as floats)? */ + static constexpr bool HAS_RGBf = true; + /** Has native RGB info (as uint8_t)? */ + static constexpr bool HAS_RGBu8 = false; + + /** Constructor (accept a const ref for convenience) */ + inline PointCloudAdapter(const mrpt::maps::CPointsMapXYZIRT& obj) + : m_obj(*const_cast(&obj)) + { + } + /** Get number of points */ + inline size_t size() const { return m_obj.size(); } + /** Set number of points (to uninitialized values) */ + inline void resize(size_t N) { m_obj.resize(N); } + /** Does nothing as of now */ + inline void setDimensions(size_t /*height*/, size_t /*width*/) {} + /** Get XYZ coordinates of i'th point */ + template + inline void getPointXYZ(size_t idx, T& x, T& y, T& z) const + { + m_obj.getPointFast(idx, x, y, z); + } + /** Set XYZ coordinates of i'th point */ + inline void setPointXYZ( + size_t idx, const coords_t x, const coords_t y, const coords_t z) + { + m_obj.setPointFast(idx, x, y, z); + } + + /** Get XYZ_RGBf coordinates of i'th point */ + template + inline void getPointXYZ_RGBAf( + size_t idx, T& x, T& y, T& z, float& r, float& g, float& b, + float& a) const + { + m_obj.getPointRGB(idx, x, y, z, r, g, b); + a = 1.0f; + } + /** Set XYZ_RGBf coordinates of i'th point */ + inline void setPointXYZ_RGBAf( + size_t idx, const coords_t x, const coords_t y, const coords_t z, + const float r, const float g, const float b, + [[maybe_unused]] const float a) + { + m_obj.setPointRGB(idx, x, y, z, r, g, b); + } + + /** Get XYZ_RGBu8 coordinates of i'th point */ + template + inline void getPointXYZ_RGBu8( + size_t idx, T& x, T& y, T& z, uint8_t& r, uint8_t& g, uint8_t& b) const + { + float I, Gignrd, Bignrd; + m_obj.getPoint(idx, x, y, z, I, Gignrd, Bignrd); + r = g = b = I * 255; + } + /** Set XYZ_RGBu8 coordinates of i'th point */ + inline void setPointXYZ_RGBu8( + size_t idx, const coords_t x, const coords_t y, const coords_t z, + const uint8_t r, const uint8_t g, const uint8_t b) + { + m_obj.setPointRGB(idx, x, y, z, r / 255.f, g / 255.f, b / 255.f); + } + + /** Get RGBf color of i'th point */ + inline void getPointRGBf(size_t idx, float& r, float& g, float& b) const + { + r = g = b = m_obj.getPointIntensity_fast(idx); + } + /** Set XYZ_RGBf coordinates of i'th point */ + inline void setPointRGBf( + size_t idx, const float r, const float g, const float b) + { + m_obj.setPointColor_fast(idx, r, g, b); + } + + /** Get RGBu8 color of i'th point */ + inline void getPointRGBu8( + size_t idx, uint8_t& r, uint8_t& g, uint8_t& b) const + { + float i = m_obj.getPointIntensity_fast(idx); + r = g = b = i * 255; + } + /** Set RGBu8 coordinates of i'th point */ + inline void setPointRGBu8( + size_t idx, const uint8_t r, const uint8_t g, const uint8_t b) + { + m_obj.setPointColor_fast(idx, r / 255.f, g / 255.f, b / 255.f); + } + +}; // end of PointCloudAdapter +} // namespace mrpt::opengl diff --git a/libs/maps/include/mrpt/maps/CSimplePointsMap.h b/libs/maps/include/mrpt/maps/CSimplePointsMap.h index 0988da2268..ec35f7e422 100644 --- a/libs/maps/include/mrpt/maps/CSimplePointsMap.h +++ b/libs/maps/include/mrpt/maps/CSimplePointsMap.h @@ -133,6 +133,12 @@ class CSimplePointsMap : public CPointsMap /** In a base class, reserve memory to prepare subsequent calls to * PLY_import_set_vertex */ void PLY_import_set_vertex_count(size_t N) override; + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } /** @} */ MAP_DEFINITION_START(CSimplePointsMap) diff --git a/libs/maps/include/mrpt/maps/CWeightedPointsMap.h b/libs/maps/include/mrpt/maps/CWeightedPointsMap.h index 3a2273f0b9..a5623d362a 100644 --- a/libs/maps/include/mrpt/maps/CWeightedPointsMap.h +++ b/libs/maps/include/mrpt/maps/CWeightedPointsMap.h @@ -148,6 +148,12 @@ class CWeightedPointsMap : public CPointsMap /** In a base class, reserve memory to prepare subsequent calls to * PLY_import_set_vertex */ void PLY_import_set_vertex_count(size_t N) override; + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } /** @} */ MAP_DEFINITION_START(CWeightedPointsMap) diff --git a/libs/maps/include/mrpt/obs/customizable_obs_viz.h b/libs/maps/include/mrpt/obs/customizable_obs_viz.h index 6bda95c2b7..f1fcb5b53b 100644 --- a/libs/maps/include/mrpt/obs/customizable_obs_viz.h +++ b/libs/maps/include/mrpt/obs/customizable_obs_viz.h @@ -14,6 +14,7 @@ #include #include #include +#include #include #include #include @@ -102,6 +103,10 @@ void obsPointCloud_to_viz( const mrpt::obs::CObservationPointCloud::Ptr& obs, const VisualizationParameters& p, mrpt::opengl::CSetOfObjects& out); +void obsRotatingScan_to_viz( + const mrpt::obs::CObservationRotatingScan::Ptr& obs, + const VisualizationParameters& p, mrpt::opengl::CSetOfObjects& out); + /// Clears `out` and creates a visualization of the given observation. void obs2Dscan_to_viz( const mrpt::obs::CObservation2DRangeScan::Ptr& obs, @@ -114,4 +119,4 @@ void recolorize3Dpc( /** @} */ -} // namespace mrpt::obs \ No newline at end of file +} // namespace mrpt::obs diff --git a/libs/maps/src/maps/CPointsMap.cpp b/libs/maps/src/maps/CPointsMap.cpp index 98d37051d4..e8e15698e3 100644 --- a/libs/maps/src/maps/CPointsMap.cpp +++ b/libs/maps/src/maps/CPointsMap.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include #include #include @@ -857,41 +858,7 @@ void CPointsMap::getAllPoints( float CPointsMap::squareDistanceToClosestCorrespondence( float x0, float y0) const { - // Just the closest point: - -#if 1 return kdTreeClosestPoint2DsqrError(x0, y0); -#else - // The distance to the line that interpolates the TWO closest points: - float x1, y1, x2, y2, d1, d2; - kdTreeTwoClosestPoint2D( - x0, y0, // The query - x1, y1, // Closest point #1 - x2, y2, // Closest point #2 - d1, d2); - - ASSERT_(d2 >= d1); - - // If the two points are too far, do not interpolate: - float d12 = square(x1 - x2) + square(y1 - y2); - if (d12 > 0.20f * 0.20f || d12 < 0.03f * 0.03f) - { - return square(x1 - x0) + square(y1 - y0); - } - else - { // Interpolate - double interp_x, interp_y; - - // math::closestFromPointToSegment( - math::closestFromPointToLine( - x0, y0, // the point - x1, y1, x2, y2, // The segment - interp_x, interp_y // out - ); - - return square(interp_x - x0) + square(interp_y - y0); - } -#endif } mrpt::math::TBoundingBoxf CPointsMap::boundingBox() const @@ -1477,6 +1444,22 @@ double CPointsMap::internal_computeObservationLikelihood( return internal_computeObservationLikelihoodPointCloud3D( sensorAbsPose, xs, ys, zs, N); } + else if (IS_CLASS(obs, CObservationRotatingScan)) + { + const auto& o = dynamic_cast(obs); + + if (!o.rowCount || !this->size()) return -100; + + mrpt::maps::CSimplePointsMap auxPts; + auxPts.insertObservation(o, takenFrom); + + const auto& xs = auxPts.getPointsBufferRef_x(); + const auto& ys = auxPts.getPointsBufferRef_y(); + const auto& zs = auxPts.getPointsBufferRef_z(); + + return internal_computeObservationLikelihoodPointCloud3D( + takenFrom, xs.data(), ys.data(), zs.data(), xs.size()); + } else if (IS_CLASS(obs, CObservationPointCloud)) { const auto& o = dynamic_cast(obs); @@ -1935,6 +1918,61 @@ bool CPointsMap::internal_insertObservation( } return true; } + else if (IS_CLASS(obs, CObservationRotatingScan)) + { + mark_as_modified(); + + const auto& o = static_cast(obs); + ASSERT_(o.rowCount > 0); + ASSERT_(o.columnCount > 0); + + if (insertionOptions.fuseWithExisting) + { + THROW_EXCEPTION( + "Fuse point cloud not implemented yet for " + "CObservationRotatingScan"); + } + else + { + // Don't fuse: Simply add + + const auto sensorGlobalPose = robotPose3D + o.sensorPose; + + const size_t N_this = size(); + const size_t N_otherMax = o.rowCount * o.columnCount; + + // Set the new size: + this->reserve(N_this + N_otherMax); + + // Optimization: detect the case of no transformation needed and + // avoid the matrix multiplications: + const bool identity_tf = (sensorGlobalPose == CPose3D::Identity()); + + for (size_t r = 0; r < o.rowCount; r++) + { + for (size_t c = 0; c < o.columnCount; c++) + { + if (!o.rangeImage(r, c)) continue; // invalid range + + // Translation: + const auto pt = o.organizedPoints(r, c); + + mrpt::math::TPoint3Df g; + if (!identity_tf) + sensorGlobalPose.composePoint( + pt.x, pt.y, pt.z, g.x, g.y, g.z); + else + g = pt; + + // Add to this map: + this->insertPointFast(g.x, g.y, g.z); + } + } + + mark_as_modified(); + } + return true; + } else { /******************************************************************** @@ -2185,18 +2223,12 @@ void CPointsMap::nn_radius_search( { std::vector idxs; kdTreeNClosestPoint3DIdx( - query.x, query.y, query.z, maxPoints, idxs, out_dists_sqr); + query.x, query.y, query.z, maxPoints, idxs, out_dists_sqr, + search_radius_sqr); results.resize(idxs.size()); resultIndicesOrIDs.resize(idxs.size()); for (size_t i = 0; i < idxs.size(); i++) { - if (out_dists_sqr[i] > search_radius_sqr) // truncate list? - { - results.resize(i); - out_dists_sqr.resize(i); - resultIndicesOrIDs.resize(i); - break; - } getPointFast(idxs[i], results[i].x, results[i].y, results[i].z); resultIndicesOrIDs[i] = idxs[i]; } @@ -2230,19 +2262,13 @@ void CPointsMap::nn_radius_search( { std::vector idxs; kdTreeNClosestPoint2DIdx( - query.x, query.y, maxPoints, idxs, out_dists_sqr); + query.x, query.y, maxPoints, idxs, out_dists_sqr, + search_radius_sqr); results.resize(idxs.size()); resultIndicesOrIDs.resize(idxs.size()); float dummyZ = 0; for (size_t i = 0; i < idxs.size(); i++) { - if (out_dists_sqr[i] > search_radius_sqr) // truncate list? - { - results.resize(i); - out_dists_sqr.resize(i); - resultIndicesOrIDs.resize(i); - break; - } getPointFast(idxs[i], results[i].x, results[i].y, dummyZ); resultIndicesOrIDs[i] = idxs[i]; } diff --git a/libs/maps/src/maps/CPointsMapXYZI.cpp b/libs/maps/src/maps/CPointsMapXYZI.cpp index ad18ee6321..6483c1dacb 100644 --- a/libs/maps/src/maps/CPointsMapXYZI.cpp +++ b/libs/maps/src/maps/CPointsMapXYZI.cpp @@ -86,7 +86,7 @@ void CPointsMapXYZI::resize(size_t newLength) m_x.resize(newLength, 0); m_y.resize(newLength, 0); m_z.resize(newLength, 0); - m_intensity.resize(newLength, 1); + m_intensity.resize(newLength, 0); mark_as_modified(); } diff --git a/libs/maps/src/maps/CPointsMapXYZIRT.cpp b/libs/maps/src/maps/CPointsMapXYZIRT.cpp new file mode 100644 index 0000000000..d19ad241a0 --- /dev/null +++ b/libs/maps/src/maps/CPointsMapXYZIRT.cpp @@ -0,0 +1,543 @@ +/* +------------------------------------------------------------------------+ +| Mobile Robot Programming Toolkit (MRPT) | +| https://www.mrpt.org/ | +| | +| Copyright (c) 2005-2023, Individual contributors, see AUTHORS file | +| See: https://www.mrpt.org/Authors - All rights reserved. | +| Released under BSD License. See: https://www.mrpt.org/License | ++------------------------------------------------------------------------+ */ + +#include "maps-precomp.h" // Precomp header +// +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "CPointsMap_crtp_common.h" + +using namespace std; +using namespace mrpt; +using namespace mrpt::maps; +using namespace mrpt::obs; +using namespace mrpt::img; +using namespace mrpt::poses; +using namespace mrpt::system; +using namespace mrpt::math; +using namespace mrpt::config; + +// =========== Begin of Map definition ============ +MAP_DEFINITION_REGISTER( + "mrpt::maps::CPointsMapXYZIRT", mrpt::maps::CPointsMapXYZIRT) + +CPointsMapXYZIRT::TMapDefinition::TMapDefinition() = default; + +void CPointsMapXYZIRT::TMapDefinition::loadFromConfigFile_map_specific( + const CConfigFileBase& source, const std::string& sectionNamePrefix) +{ + insertionOpts.loadFromConfigFile( + source, sectionNamePrefix + string("_insertOpts")); + likelihoodOpts.loadFromConfigFile( + source, sectionNamePrefix + string("_likelihoodOpts")); +} + +void CPointsMapXYZIRT::TMapDefinition::dumpToTextStream_map_specific( + std::ostream& out) const +{ + this->insertionOpts.dumpToTextStream(out); + this->likelihoodOpts.dumpToTextStream(out); +} + +mrpt::maps::CMetricMap::Ptr CPointsMapXYZIRT::internal_CreateFromMapDefinition( + const mrpt::maps::TMetricMapInitializer& _def) +{ + const CPointsMapXYZIRT::TMapDefinition& def = + *dynamic_cast(&_def); + auto obj = CPointsMapXYZIRT::Create(); + obj->insertionOptions = def.insertionOpts; + obj->likelihoodOptions = def.likelihoodOpts; + return obj; +} +// =========== End of Map definition Block ========= + +IMPLEMENTS_SERIALIZABLE(CPointsMapXYZIRT, CPointsMap, mrpt::maps) + +CPointsMapXYZIRT::CPointsMapXYZIRT(const CPointsMapXYZIRT& o) : CPointsMap() +{ + impl_copyFrom(o); +} +CPointsMapXYZIRT::CPointsMapXYZIRT(const CPointsMapXYZI& o) : CPointsMap() +{ + impl_copyFrom(o); +} +CPointsMapXYZIRT& CPointsMapXYZIRT::operator=(const CPointsMap& o) +{ + impl_copyFrom(o); + return *this; +} +CPointsMapXYZIRT& CPointsMapXYZIRT::operator=(const CPointsMapXYZIRT& o) +{ + impl_copyFrom(o); + return *this; +} +CPointsMapXYZIRT& CPointsMapXYZIRT::operator=(const CPointsMapXYZI& o) +{ + impl_copyFrom(o); + return *this; +} + +void CPointsMapXYZIRT::reserve(size_t newLength) +{ + m_x.reserve(newLength); + m_y.reserve(newLength); + m_z.reserve(newLength); + m_intensity.reserve(newLength); + m_ring.reserve(newLength); + m_time.reserve(newLength); +} + +// Resizes all point buffers so they can hold the given number of points: newly +// created points are set to default values, +// and old contents are not changed. +void CPointsMapXYZIRT::resize(size_t newLength) +{ + m_x.resize(newLength, 0); + m_y.resize(newLength, 0); + m_z.resize(newLength, 0); + m_intensity.resize(newLength, 0); + m_ring.resize(newLength, 0); + m_time.resize(newLength, 0); + mark_as_modified(); +} + +void CPointsMapXYZIRT::resize_XYZIRT( + size_t newLength, bool hasIntensity, bool hasRing, bool hasTime) +{ + m_x.resize(newLength, 0); + m_y.resize(newLength, 0); + m_z.resize(newLength, 0); + m_intensity.resize(hasIntensity ? newLength : 0, 0); + m_ring.resize(hasRing ? newLength : 0, 0); + m_time.resize(hasTime ? newLength : 0, 0); + mark_as_modified(); +} + +void CPointsMapXYZIRT::reserve_XYZIRT( + size_t n, bool hasIntensity, bool hasRing, bool hasTime) +{ + m_x.reserve(n); + m_y.reserve(n); + m_z.reserve(n); + if (hasIntensity) m_intensity.reserve(n); + if (hasRing) m_ring.reserve(n); + if (hasTime) m_time.reserve(n); +} + +// Resizes all point buffers so they can hold the given number of points, +// *erasing* all previous contents +// and leaving all points to default values. +void CPointsMapXYZIRT::setSize(size_t newLength) +{ + m_x.assign(newLength, 0); + m_y.assign(newLength, 0); + m_z.assign(newLength, 0); + m_intensity.assign(newLength, 0); + m_ring.assign(newLength, 0); + m_time.assign(newLength, 0); + mark_as_modified(); +} + +void CPointsMapXYZIRT::impl_copyFrom(const CPointsMap& obj) +{ + // This also does a ::resize(N) of all data fields. + CPointsMap::base_copyFrom(obj); + + const auto* pXYZI = dynamic_cast(&obj); + if (pXYZI) m_intensity = pXYZI->m_intensity; +} + +uint8_t CPointsMapXYZIRT::serializeGetVersion() const { return 0; } +void CPointsMapXYZIRT::serializeTo(mrpt::serialization::CArchive& out) const +{ + // XYZ + uint32_t n = m_x.size(); + out << n; + if (n > 0) + { + out.WriteBufferFixEndianness(m_x.data(), n); + out.WriteBufferFixEndianness(m_y.data(), n); + out.WriteBufferFixEndianness(m_z.data(), n); + } + + // I + n = m_intensity.size(); + out << n; + if (n > 0) out.WriteBufferFixEndianness(m_intensity.data(), n); + + // R + n = m_ring.size(); + out << n; + if (n > 0) out.WriteBufferFixEndianness(m_ring.data(), n); + + // T + n = m_time.size(); + out << n; + if (n > 0) out.WriteBufferFixEndianness(m_time.data(), n); + + insertionOptions.writeToStream(out); + likelihoodOptions.writeToStream(out); +} + +void CPointsMapXYZIRT::serializeFrom( + mrpt::serialization::CArchive& in, uint8_t version) +{ + switch (version) + { + case 0: + { + mark_as_modified(); + + // XYZ + uint32_t n; + in >> n; + m_x.resize(n); + m_y.resize(n); + m_z.resize(n); + if (n > 0) + { + in.ReadBufferFixEndianness(m_x.data(), n); + in.ReadBufferFixEndianness(m_y.data(), n); + in.ReadBufferFixEndianness(m_z.data(), n); + } + // I: + in >> n; + m_intensity.resize(n); + if (n > 0) in.ReadBufferFixEndianness(m_intensity.data(), n); + + // R: + in >> n; + m_ring.resize(n); + if (n > 0) in.ReadBufferFixEndianness(m_ring.data(), n); + + // T: + in >> n; + m_time.resize(n); + if (n > 0) in.ReadBufferFixEndianness(m_time.data(), n); + + insertionOptions.readFromStream(in); + likelihoodOptions.readFromStream(in); + } + break; + default: MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version); + }; +} + +void CPointsMapXYZIRT::internal_clear() +{ + vector_strong_clear(m_x); + vector_strong_clear(m_y); + vector_strong_clear(m_z); + vector_strong_clear(m_intensity); + vector_strong_clear(m_ring); + vector_strong_clear(m_time); + mark_as_modified(); +} + +void CPointsMapXYZIRT::setPointRGB( + size_t index, float x, float y, float z, float R, float G, float B) +{ + if (index >= m_x.size()) THROW_EXCEPTION("Index out of bounds"); + m_x[index] = x; + m_y[index] = y; + m_z[index] = z; + m_intensity[index] = R; + mark_as_modified(); +} + +void CPointsMapXYZIRT::insertPointFast(float x, float y, float z) +{ + m_x.push_back(x); + m_y.push_back(y); + m_z.push_back(z); + // mark_as_modified(); Don't, this is the "XXXFast()" method +} + +void CPointsMapXYZIRT::insertPointRGB( + float x, float y, float z, float R_intensity, float G_ignored, + float B_ignored) +{ + m_x.push_back(x); + m_y.push_back(y); + m_z.push_back(z); + m_intensity.push_back(R_intensity); + mark_as_modified(); +} + +void CPointsMapXYZIRT::getVisualizationInto( + mrpt::opengl::CSetOfObjects& o) const +{ + if (!genericMapParams.enableSaveAs3DObject) return; + + auto obj = mrpt::opengl::CPointCloudColoured::Create(); + + obj->loadFromPointsMap(this); + obj->setColor(1, 1, 1, 1.0); + obj->setPointSize(this->renderOptions.point_size); + + o.insert(obj); +} + +void CPointsMapXYZIRT::getPointRGB( + size_t index, float& x, float& y, float& z, float& R, float& G, + float& B) const +{ + if (index >= m_x.size()) THROW_EXCEPTION("Index out of bounds"); + + x = m_x[index]; + y = m_y[index]; + z = m_z[index]; + R = G = B = m_intensity[index]; +} + +bool CPointsMapXYZIRT::saveXYZIRT_to_text_file(const std::string& file) const +{ + FILE* f = os::fopen(file.c_str(), "wt"); + if (!f) return false; + for (unsigned int i = 0; i < m_x.size(); i++) + os::fprintf( + f, "%f %f %f %f %i %f\n", m_x[i], m_y[i], m_z[i], + getPointIntensity(i), static_cast(getPointRing(i)), + getPointTime(i)); + os::fclose(f); + return true; +} + +bool CPointsMapXYZIRT::loadXYZIRT_from_text_file(const std::string& file) +{ + MRPT_START + + // Clear current map: + mark_as_modified(); + this->clear(); + + std::ifstream f; + f.open(file); + if (!f.is_open()) return false; + + while (!f.eof()) + { + std::string line; + std::getline(f, line); + + std::stringstream ss(line); + + float x, y, z, i, t; + uint16_t r; + if (!(ss >> x >> y >> z >> i >> r >> t)) { break; } + + insertPointFast(x, y, z); + m_intensity.push_back(i); + m_ring.push_back(r); + m_time.push_back(t); + } + + return true; + + MRPT_END +} + +/*--------------------------------------------------------------- +addFrom_classSpecific +---------------------------------------------------------------*/ +void CPointsMapXYZIRT::addFrom_classSpecific( + const CPointsMap& anotherMap, size_t nPreviousPoints, + const bool filterOutPointsAtZero) +{ + const size_t nOther = anotherMap.size(); + + const auto& oxs = anotherMap.getPointsBufferRef_x(); + const auto& oys = anotherMap.getPointsBufferRef_y(); + const auto& ozs = anotherMap.getPointsBufferRef_z(); + + // Specific data for this class: + if (const auto* o = dynamic_cast(&anotherMap); o) + { + bool any = false; + if (o->hasIntensityField()) + { + m_intensity.reserve(nPreviousPoints + nOther); + any = true; + } + if (o->hasRingField()) + { + m_ring.reserve(nPreviousPoints + nOther); + any = true; + } + if (o->hasTimeField()) + { + m_time.reserve(nPreviousPoints + nOther); + any = true; + } + ASSERTMSG_( + any, + "Cannot insert a CPointsMapXYZIRT map without any of IRT fields " + "present."); + + for (size_t i = 0; i < nOther; i++) + { + if (filterOutPointsAtZero && oxs[i] == 0 && oys[i] == 0 && + ozs[i] == 0) + continue; + + if (o->hasIntensityField()) + m_intensity.push_back(o->m_intensity[i]); + if (o->hasRingField()) m_ring.push_back(o->m_ring[i]); + if (o->hasTimeField()) m_time.push_back(o->m_time[i]); + } + } + else if (const auto* oi = dynamic_cast(&anotherMap); + oi) + { + m_intensity.reserve(nPreviousPoints + nOther); + + for (size_t i = 0; i < nOther; i++) + { + if (filterOutPointsAtZero && oxs[i] == 0 && oys[i] == 0 && + ozs[i] == 0) + continue; + + m_intensity.push_back(oi->getPointIntensity_fast(i)); + } + } +} + +namespace mrpt::maps::detail +{ +using mrpt::maps::CPointsMapXYZIRT; + +template <> +struct pointmap_traits +{ + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called only once before inserting + * points - this is the place to reserve memory in lric for extra working + * variables. */ + inline static void internal_loadFromRangeScan2D_init( + CPointsMapXYZIRT& me, + mrpt::maps::CPointsMap::TLaserRange2DInsertContext& lric) + { + // lric.fVars: not needed + } + + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called once per range data */ + inline static void internal_loadFromRangeScan2D_prepareOneRange( + CPointsMapXYZIRT& me, [[maybe_unused]] const float gx, + [[maybe_unused]] const float gy, [[maybe_unused]] const float gz, + mrpt::maps::CPointsMap::TLaserRange2DInsertContext& lric) + { + } + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called after each + * "{x,y,z}.push_back(...);" */ + inline static void internal_loadFromRangeScan2D_postPushBack( + CPointsMapXYZIRT& me, + mrpt::maps::CPointsMap::TLaserRange2DInsertContext& lric) + { + float pI = 1.0f; + me.m_intensity.push_back(pI); + } + + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called only once before inserting + * points - this is the place to reserve memory in lric for extra working + * variables. */ + inline static void internal_loadFromRangeScan3D_init( + CPointsMapXYZIRT& me, + mrpt::maps::CPointsMap::TLaserRange3DInsertContext& lric) + { + // Not used. + } + + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called once per range data */ + inline static void internal_loadFromRangeScan3D_prepareOneRange( + CPointsMapXYZIRT& me, [[maybe_unused]] const float gx, + [[maybe_unused]] const float gy, [[maybe_unused]] const float gz, + mrpt::maps::CPointsMap::TLaserRange3DInsertContext& lric) + { + } + + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called after each + * "{x,y,z}.push_back(...);" */ + inline static void internal_loadFromRangeScan3D_postPushBack( + CPointsMapXYZIRT& me, + mrpt::maps::CPointsMap::TLaserRange3DInsertContext& lric) + { + const float pI = 1.0f; + me.m_intensity.push_back(pI); + } + + /** Helper method fot the generic implementation of + * CPointsMap::loadFromRangeScan(), to be called once per range data, at the + * end */ + inline static void internal_loadFromRangeScan3D_postOneRange( + CPointsMapXYZIRT& me, + mrpt::maps::CPointsMap::TLaserRange3DInsertContext& lric) + { + } +}; +} // namespace mrpt::maps::detail +/** See CPointsMap::loadFromRangeScan() */ +void CPointsMapXYZIRT::loadFromRangeScan( + const CObservation2DRangeScan& rangeScan, + const std::optional& robotPose) +{ + mrpt::maps::detail::loadFromRangeImpl< + CPointsMapXYZIRT>::templ_loadFromRangeScan(*this, rangeScan, robotPose); +} + +/** See CPointsMap::loadFromRangeScan() */ +void CPointsMapXYZIRT::loadFromRangeScan( + const CObservation3DRangeScan& rangeScan, + const std::optional& robotPose) +{ + mrpt::maps::detail::loadFromRangeImpl< + CPointsMapXYZIRT>::templ_loadFromRangeScan(*this, rangeScan, robotPose); +} + +// ====PLY files import & export virtual methods +void CPointsMapXYZIRT::PLY_import_set_vertex_count(size_t N) +{ + this->setSize(N); +} + +void CPointsMapXYZIRT::PLY_import_set_vertex( + size_t idx, const mrpt::math::TPoint3Df& pt, const TColorf* pt_color) +{ + if (pt_color) + this->setPointRGB( + idx, pt.x, pt.y, pt.z, pt_color->R, pt_color->G, pt_color->B); + else + this->setPoint(idx, pt.x, pt.y, pt.z); +} + +void CPointsMapXYZIRT::PLY_export_get_vertex( + size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color, + TColorf& pt_color) const +{ + pt_has_color = true; + + pt.x = m_x[idx]; + pt.y = m_y[idx]; + pt.z = m_z[idx]; + pt_color.R = pt_color.G = pt_color.B = m_intensity[idx]; +} diff --git a/libs/maps/src/obs/CObservationPointCloud.cpp b/libs/maps/src/obs/CObservationPointCloud.cpp index 487ac02d67..9db16a4a15 100644 --- a/libs/maps/src/obs/CObservationPointCloud.cpp +++ b/libs/maps/src/obs/CObservationPointCloud.cpp @@ -200,49 +200,49 @@ void CObservationPointCloud::load() const void CObservationPointCloud::unload() const { MRPT_START - if (isExternallyStored() && pointcloud) - { - // Free memory, saving to the file if it doesn't exist: - const auto abs_filename = - mrpt::io::lazy_load_absolute_path(m_external_file); + if (!isExternallyStored() || !pointcloud) return; - if (!mrpt::system::fileExists(abs_filename)) + // Free memory, saving to the file if it doesn't exist: + const auto abs_filename = + mrpt::io::lazy_load_absolute_path(m_external_file); + + if (!mrpt::system::fileExists(abs_filename)) + { + switch (m_externally_stored) { - switch (m_externally_stored) + case ExternalStorageFormat::None: break; + case ExternalStorageFormat::KittiBinFile: { - case ExternalStorageFormat::None: break; - case ExternalStorageFormat::KittiBinFile: - { - THROW_EXCEPTION("Saving to kitti format not supported."); - } - case ExternalStorageFormat::PlainTextFile: - { - std::ofstream f(abs_filename); - ASSERT_(f.is_open()); - std::vector row; - for (size_t i = 0; i < pointcloud->size(); i++) - { - pointcloud->getPointAllFieldsFast(i, row); - for (const float v : row) - f << v << " "; - f << "\n"; - } - } - break; - case ExternalStorageFormat::MRPT_Serialization: + THROW_EXCEPTION("Saving to kitti format not supported."); + } + case ExternalStorageFormat::PlainTextFile: + { + std::ofstream f(abs_filename); + ASSERT_(f.is_open()); + std::vector row; + for (size_t i = 0; i < pointcloud->size(); i++) { - mrpt::io::CFileGZOutputStream f(abs_filename); - auto ar = mrpt::serialization::archiveFrom(f); - ar << *pointcloud; + pointcloud->getPointAllFieldsFast(i, row); + for (const float v : row) + f << v << " "; + f << "\n"; } - break; - }; - } - - // Now we can safely free the mem: - auto& me = const_cast(*this); - me.pointcloud.reset(); + } + break; + case ExternalStorageFormat::MRPT_Serialization: + { + mrpt::io::CFileGZOutputStream f(abs_filename); + auto ar = mrpt::serialization::archiveFrom(f); + ar << *pointcloud; + } + break; + }; } + + // Now we can safely free the mem: + auto& me = const_cast(*this); + me.pointcloud.reset(); + MRPT_END } diff --git a/libs/maps/src/obs/customizable_obs_viz.cpp b/libs/maps/src/obs/customizable_obs_viz.cpp index 775a37afef..7209b20960 100644 --- a/libs/maps/src/obs/customizable_obs_viz.cpp +++ b/libs/maps/src/obs/customizable_obs_viz.cpp @@ -268,6 +268,29 @@ void mrpt::obs::obsPointCloud_to_viz( if (!p.colorFromRGBimage) recolorize3Dpc(pnts, p); } +void mrpt::obs::obsRotatingScan_to_viz( + const mrpt::obs::CObservationRotatingScan::Ptr& obs, + const VisualizationParameters& p, mrpt::opengl::CSetOfObjects& out) +{ + out.clear(); + + add_common_to_viz(*obs, p, out); + + auto pnts = mrpt::opengl::CPointCloudColoured::Create(); + out.insert(pnts); + + if (!obs->organizedPoints.empty()) + { + for (const auto& pt : obs->organizedPoints) + pnts->insertPoint({pt.x, pt.y, pt.z, 0, 0, 0, 0}); + } + pnts->setPose(obs->sensorPose); + + pnts->setPointSize(p.pointSize); + + if (!p.colorFromRGBimage) recolorize3Dpc(pnts, p); +} + void mrpt::obs::obs2Dscan_to_viz( const CObservation2DRangeScan::Ptr& obs, const VisualizationParameters& p, mrpt::opengl::CSetOfObjects& out) @@ -323,6 +346,13 @@ bool mrpt::obs::obs_to_viz( obsPointCloud_to_viz(oPC, p, out); return true; } + else if (const auto oRS = + std::dynamic_pointer_cast(obs); + oRS) + { + obsRotatingScan_to_viz(oRS, p, out); + return true; + } else if (const auto o2D = std::dynamic_pointer_cast(obs); o2D) diff --git a/libs/maps/src/registerAllClasses.cpp b/libs/maps/src/registerAllClasses.cpp index 44f9b776cf..5c4ceb1cfa 100644 --- a/libs/maps/src/registerAllClasses.cpp +++ b/libs/maps/src/registerAllClasses.cpp @@ -14,7 +14,6 @@ #include #include #include -#include // deps: #include #include @@ -34,6 +33,7 @@ MRPT_INITIALIZER(registerAllClasses_mrpt_maps) registerClass(CLASS_ID(CColouredPointsMap)); registerClass(CLASS_ID(CWeightedPointsMap)); registerClass(CLASS_ID(CPointsMapXYZI)); + registerClass(CLASS_ID(CPointsMapXYZIRT)); registerClass(CLASS_ID(COccupancyGridMap2D)); registerClass(CLASS_ID(COccupancyGridMap3D)); registerClass(CLASS_ID(CGasConcentrationGridMap2D)); @@ -53,7 +53,6 @@ MRPT_INITIALIZER(registerAllClasses_mrpt_maps) registerClass(CLASS_ID(CPlanarLaserScan)); registerClass(CLASS_ID(CObservationPointCloud)); - registerClass(CLASS_ID(CObservationRotatingScan)); registerClass(CLASS_ID(CMultiMetricMap)); diff --git a/libs/math/include/mrpt/math/CMatrixDynamic.h b/libs/math/include/mrpt/math/CMatrixDynamic.h index f5e0dc0758..14f7f4742c 100644 --- a/libs/math/include/mrpt/math/CMatrixDynamic.h +++ b/libs/math/include/mrpt/math/CMatrixDynamic.h @@ -150,7 +150,10 @@ class CMatrixDynamic : public MatrixBase> /** Constructors */ CMatrixDynamic(const CMatrixDynamic& m) { (*this) = m; } - CMatrixDynamic(size_t row = 0, size_t col = 0) { realloc(row, col); } + explicit CMatrixDynamic(size_t row = 0, size_t col = 0) + { + realloc(row, col); + } /** Copy (casting from if needed) from another matrix */ template diff --git a/libs/math/include/mrpt/math/KDTreeCapable.h b/libs/math/include/mrpt/math/KDTreeCapable.h index 1d5706b314..9ef419b784 100644 --- a/libs/math/include/mrpt/math/KDTreeCapable.h +++ b/libs/math/include/mrpt/math/KDTreeCapable.h @@ -19,6 +19,7 @@ #include // unique_ptr #include #include +#include // Smooth transition to nanoflann>=1.5.0 for older versions: namespace nanoflann @@ -291,6 +292,8 @@ class KDTreeCapable *correspondences. * \param out_dist_sqr The vector containing the square distance between *the query and the returned points. + * \param maximumSearchDistanceSqr If provided, only NN up to that given + *squared distance will be returned. * * \return The list of indices * \sa kdTreeClosestPoint2D @@ -298,7 +301,9 @@ class KDTreeCapable */ inline std::vector kdTreeNClosestPoint2D( float x0, float y0, size_t knn, std::vector& out_x, - std::vector& out_y, std::vector& out_dist_sqr) const + std::vector& out_y, std::vector& out_dist_sqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { MRPT_START rebuild_kdTree_2D(); // First: Create the 2D KD-Tree if required @@ -310,11 +315,29 @@ class KDTreeCapable out_y.resize(knn); out_dist_sqr.resize(knn); - nanoflann::KNNResultSet resultSet(knn); - resultSet.init(&ret_indexes[0], &out_dist_sqr[0]); - const std::array query_point{{x0, y0}}; - m_kdtree2d_data.index->findNeighbors(resultSet, &query_point[0], {}); + + if (!maximumSearchDistanceSqr.has_value()) + { + nanoflann::KNNResultSet resultSet(knn); + resultSet.init(&ret_indexes[0], &out_dist_sqr[0]); + + m_kdtree2d_data.index->findNeighbors( + resultSet, &query_point[0], {}); + } + else + { +#if NANOFLANN_VERSION >= 0x151 + nanoflann::RKNNResultSet resultSet( + knn, *maximumSearchDistanceSqr); + resultSet.init(&ret_indexes[0], &out_dist_sqr[0]); + + m_kdtree2d_data.index->findNeighbors( + resultSet, &query_point[0], {}); +#else + THROW_EXCEPTION("RKNN search requires nanoflann>=1.5.1"); +#endif + } for (size_t i = 0; i < knn; i++) { @@ -327,11 +350,14 @@ class KDTreeCapable inline std::vector kdTreeNClosestPoint2D( const TPoint2D& p0, size_t N, std::vector& pOut, - std::vector& outDistSqr) const + std::vector& outDistSqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { std::vector dmy1, dmy2; std::vector res = kdTreeNClosestPoint2D( - d2f(p0.x), d2f(p0.y), N, dmy1, dmy2, outDistSqr); + d2f(p0.x), d2f(p0.y), N, dmy1, dmy2, outDistSqr, + maximumSearchDistanceSqr); pOut.resize(dmy1.size()); for (size_t i = 0; i < dmy1.size(); i++) { @@ -354,12 +380,16 @@ class KDTreeCapable * \param out_idx The indexes of the found closest correspondence. * \param out_dist_sqr The square distance between the query and the *returned point. + * \param maximumSearchDistanceSqr If provided, only NN up to that given + *squared distance will be returned. * * \sa kdTreeClosestPoint2D */ inline void kdTreeNClosestPoint2DIdx( float x0, float y0, size_t knn, std::vector& out_idx, - std::vector& out_dist_sqr) const + std::vector& out_dist_sqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { MRPT_START rebuild_kdTree_2D(); // First: Create the 2D KD-Tree if required @@ -368,11 +398,30 @@ class KDTreeCapable out_idx.resize(knn); out_dist_sqr.resize(knn); - nanoflann::KNNResultSet resultSet(knn); - resultSet.init(&out_idx[0], &out_dist_sqr[0]); - const std::array query_point{{x0, y0}}; - m_kdtree2d_data.index->findNeighbors(resultSet, &query_point[0], {}); + + if (!maximumSearchDistanceSqr.has_value()) + { + nanoflann::KNNResultSet resultSet(knn); + resultSet.init(&out_idx[0], &out_dist_sqr[0]); + + m_kdtree2d_data.index->findNeighbors( + resultSet, &query_point[0], {}); + } + else + { +#if NANOFLANN_VERSION >= 0x151 + nanoflann::RKNNResultSet resultSet( + knn, *maximumSearchDistanceSqr); + resultSet.init(&out_idx[0], &out_dist_sqr[0]); + + m_kdtree2d_data.index->findNeighbors( + resultSet, &query_point[0], {}); +#else + THROW_EXCEPTION("RKNN search requires nanoflann>=1.5.1"); +#endif + } + MRPT_END } @@ -482,13 +531,17 @@ class KDTreeCapable *correspondences. * \param out_dist_sqr The vector containing the square distance between *the query and the returned points. + * \param maximumSearchDistanceSqr If provided, only NN up to that given + *squared distance will be returned. * * \sa kdTreeNClosestPoint2D */ inline void kdTreeNClosestPoint3D( float x0, float y0, float z0, size_t knn, std::vector& out_x, std::vector& out_y, std::vector& out_z, - std::vector& out_dist_sqr) const + std::vector& out_dist_sqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { MRPT_START rebuild_kdTree_3D(); // First: Create the 3D KD-Tree if required @@ -500,12 +553,27 @@ class KDTreeCapable out_y.resize(knn); out_z.resize(knn); out_dist_sqr.resize(knn); - - nanoflann::KNNResultSet resultSet(knn); - resultSet.init(&ret_indexes[0], &out_dist_sqr[0]); - const std::array query_point{{x0, y0, z0}}; - m_kdtree3d_data.index->findNeighbors(resultSet, &query_point[0], {}); + + if (!maximumSearchDistanceSqr.has_value()) + { + nanoflann::KNNResultSet resultSet(knn); + resultSet.init(&ret_indexes[0], &out_dist_sqr[0]); + m_kdtree3d_data.index->findNeighbors( + resultSet, &query_point[0], {}); + } + else + { +#if NANOFLANN_VERSION >= 0x151 + nanoflann::RKNNResultSet resultSet( + knn, *maximumSearchDistanceSqr); + resultSet.init(&ret_indexes[0], &out_dist_sqr[0]); + m_kdtree3d_data.index->findNeighbors( + resultSet, &query_point[0], {}); +#else + THROW_EXCEPTION("RKNN search requires nanoflann>=1.5.1"); +#endif + } for (size_t i = 0; i < knn; i++) { @@ -542,7 +610,9 @@ class KDTreeCapable inline void kdTreeNClosestPoint3DWithIdx( float x0, float y0, float z0, size_t knn, std::vector& out_x, std::vector& out_y, std::vector& out_z, - std::vector& out_idx, std::vector& out_dist_sqr) const + std::vector& out_idx, std::vector& out_dist_sqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { MRPT_START rebuild_kdTree_3D(); // First: Create the 3D KD-Tree if required @@ -554,12 +624,28 @@ class KDTreeCapable out_z.resize(knn); out_idx.resize(knn); out_dist_sqr.resize(knn); + const std::array query_point{{x0, y0, z0}}; - nanoflann::KNNResultSet resultSet(knn); - resultSet.init(&out_idx[0], &out_dist_sqr[0]); + if (!maximumSearchDistanceSqr.has_value()) + { + nanoflann::KNNResultSet resultSet(knn); + resultSet.init(&out_idx[0], &out_dist_sqr[0]); - const std::array query_point{{x0, y0, z0}}; - m_kdtree3d_data.index->findNeighbors(resultSet, &query_point[0], {}); + m_kdtree3d_data.index->findNeighbors( + resultSet, &query_point[0], {}); + } + else + { +#if NANOFLANN_VERSION >= 0x151 + nanoflann::RKNNResultSet resultSet( + knn, *maximumSearchDistanceSqr); + resultSet.init(&out_idx[0], &out_dist_sqr[0]); + m_kdtree3d_data.index->findNeighbors( + resultSet, &query_point[0], {}); +#else + THROW_EXCEPTION("RKNN search requires nanoflann>=1.5.1"); +#endif + } for (size_t i = 0; i < knn; i++) { @@ -572,11 +658,14 @@ class KDTreeCapable inline void kdTreeNClosestPoint3D( const TPoint3D& p0, size_t N, std::vector& pOut, - std::vector& outDistSqr) const + std::vector& outDistSqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { std::vector dmy1, dmy2, dmy3; kdTreeNClosestPoint3D( - d2f(p0.x), d2f(p0.y), d2f(p0.z), N, dmy1, dmy2, dmy3, outDistSqr); + d2f(p0.x), d2f(p0.y), d2f(p0.z), N, dmy1, dmy2, dmy3, outDistSqr, + maximumSearchDistanceSqr); pOut.resize(dmy1.size()); for (size_t i = 0; i < dmy1.size(); i++) { @@ -675,7 +764,9 @@ class KDTreeCapable */ inline void kdTreeNClosestPoint3DIdx( float x0, float y0, float z0, size_t knn, std::vector& out_idx, - std::vector& out_dist_sqr) const + std::vector& out_dist_sqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { MRPT_START rebuild_kdTree_3D(); // First: Create the 3D KD-Tree if required @@ -684,20 +775,40 @@ class KDTreeCapable out_idx.resize(knn); out_dist_sqr.resize(knn); - nanoflann::KNNResultSet resultSet(knn); - resultSet.init(&out_idx[0], &out_dist_sqr[0]); - const std::array query_point{{x0, y0, z0}}; - m_kdtree3d_data.index->findNeighbors(resultSet, &query_point[0], {}); + + if (!maximumSearchDistanceSqr.has_value()) + { + nanoflann::KNNResultSet resultSet(knn); + resultSet.init(&out_idx[0], &out_dist_sqr[0]); + m_kdtree3d_data.index->findNeighbors( + resultSet, &query_point[0], {}); + } + else + { +#if NANOFLANN_VERSION >= 0x151 + nanoflann::RKNNResultSet resultSet( + knn, *maximumSearchDistanceSqr); + resultSet.init(&out_idx[0], &out_dist_sqr[0]); + m_kdtree3d_data.index->findNeighbors( + resultSet, &query_point[0], {}); +#else + THROW_EXCEPTION("RKNN search requires nanoflann>=1.5.1"); +#endif + } + MRPT_END } inline void kdTreeNClosestPoint3DIdx( const TPoint3D& p0, size_t N, std::vector& outIdx, - std::vector& outDistSqr) const + std::vector& outDistSqr, + const std::optional& maximumSearchDistanceSqr = + std::nullopt) const { kdTreeNClosestPoint3DIdx( - d2f(p0.x), d2f(p0.y), d2f(p0.z), N, outIdx, outDistSqr); + d2f(p0.x), d2f(p0.y), d2f(p0.z), N, outIdx, outDistSqr, + maximumSearchDistanceSqr); } inline void kdTreeEnsureIndexBuilt3D() { rebuild_kdTree_3D(); } diff --git a/libs/obs/include/mrpt/obs.h b/libs/obs/include/mrpt/obs.h index 3830a965ed..b21ccc6226 100644 --- a/libs/obs/include/mrpt/obs.h +++ b/libs/obs/include/mrpt/obs.h @@ -39,6 +39,7 @@ MRPT_WARNING( #include #include #include +#include #include #include #include diff --git a/libs/maps/include/mrpt/obs/CObservationRotatingScan.h b/libs/obs/include/mrpt/obs/CObservationRotatingScan.h similarity index 72% rename from libs/maps/include/mrpt/obs/CObservationRotatingScan.h rename to libs/obs/include/mrpt/obs/CObservationRotatingScan.h index 71e3da3cda..8016079d7b 100644 --- a/libs/maps/include/mrpt/obs/CObservationRotatingScan.h +++ b/libs/obs/include/mrpt/obs/CObservationRotatingScan.h @@ -21,7 +21,6 @@ namespace mrpt::obs { class CObservationVelodyneScan; class CObservation2DRangeScan; -class CObservationPointCloud; /** \addtogroup mrpt_obs_grp * @{ */ @@ -30,11 +29,8 @@ class CObservationPointCloud; * rotating scanner. This class is the preferred alternative to * CObservationVelodyneScan and CObservation2DRangeScan in MRPT 2.x, since it * exposes range data as an organized matrix, more convenient for feature - * detection directly on "range images". - * This class can also import data from KITTI dataset-like binary files - * containing unorganized (non "undistorted", i.e. without compensation for - * lidar motion) point clouds, which get organized into a 2D range image for - * easier filtering and postprocessing. + * detection directly on "range images" and on points stored as a matrix in the + * member organizedPoints. * * Check out the main data fields in the list of members below. * @@ -46,14 +42,10 @@ class CObservationPointCloud; * local computer-based timestamp based on the reception of the message in * the computer. * - * Both timestamps correspond to the firing of the first laser in - * the first CObservationRotatingScan::scan_packets packet. + * Both timestamps correspond to the firing of the **first** laser in + * the scan, i.e. the first column in organizedPoints. * - *
- * - * API for accurate reconstruction of point clouds from raw range images: - * - generatePointCloud() - * - generatePointCloudAlongSE3Trajectory() + * The reference frame for the 3D LIDAR is with +X pointing forward, +Z up. * * \note New in MRPT 2.0.0 * \sa CObservation, mrpt::hwdrivers::CVelodyneScanner @@ -62,13 +54,26 @@ class CObservationRotatingScan : public CObservation { DEFINE_SERIALIZABLE(CObservationRotatingScan, mrpt::obs) + public: + enum class ExternalStorageFormat : uint8_t + { + None = 0, //!< is always stored in memory + MRPT_Serialization, //!< Uses mrpt-serialization binary file + /// Plain text, format explained in saveToTextFile() + PlainTextFile + }; + + protected: + ExternalStorageFormat m_externally_stored = ExternalStorageFormat::None; + std::string m_external_file; + public: /** @name Scan range data @{ */ /** Number of "Lidar rings" (e.g. 16 for a Velodyne VLP16, etc.). This * should be constant for a given LiDAR scanner. - * All matrices in `imageLayer_*` have this number of rows. + * All matrices defined below have this number of rows. */ uint16_t rowCount{0}; @@ -85,9 +90,16 @@ class CObservationRotatingScan : public CObservation * (i.e. invalid range). This member must be always provided, containing the * ranges for the STRONGEST ray returns. * To obtain ranges in meters, multiply this matrix by `rangeResolution`. + * + * \sa organizedPoints */ mrpt::math::CMatrix_u16 rangeImage{0, 0}; + /** If present, it contains all 3D points, in local coordinates wrt the + * sensor, for all !=0 entries in \a rangeImage. + */ + mrpt::math::CMatrixDynamic organizedPoints{0, 0}; + /** Optionally, an intensity channel. Matrix with a 0x0 size if not * provided. */ mrpt::math::CMatrix_u8 intensityImage{0, 0}; @@ -109,7 +121,8 @@ class CObservationRotatingScan : public CObservation */ double startAzimuth{-M_PI}, azimuthSpan{2 * M_PI}; - /** Time(in seconds) that passed since `startAzimuth` to* `endAzimuth`. */ + /** Time (in seconds) that passed since `startAzimuth` (first column) to + * `endAzimuth` (last column). */ double sweepDuration{.0}; /** The driver should fill in this observation */ @@ -124,8 +137,6 @@ class CObservationRotatingScan : public CObservation * of reference */ mrpt::poses::CPose3D sensorPose; - // TODO: Calibration!! - /** The local computer-based timestamp based on the * reception of the message in the computer. \sa * has_satellite_timestamp, CObservation::timestamp in the @@ -146,21 +157,56 @@ class CObservationRotatingScan : public CObservation void fromVelodyne(const mrpt::obs::CObservationVelodyneScan& o); void fromScan2D(const mrpt::obs::CObservation2DRangeScan& o); - void fromPointCloud(const mrpt::obs::CObservationPointCloud& o); /** Will convert from another observation if it's any of the supported - * source types (see fromVelodyne(), fromScan2D(), fromPointCloud()) and + * source types (see fromVelodyne(), fromScan2D()) and * return true, or will return false otherwise if there is no known way to * convert from the passed object. */ bool fromGeneric(const mrpt::obs::CObservation& o); + /** @} */ + /** @name Delayed-load manual control methods. + @{ */ + // See base class docs. + void load() const override; + void unload() const override; /** @} */ - /** @name "Convert to" API + /** \name Point cloud external storage functions * @{ */ + inline bool isExternallyStored() const + { + return m_externally_stored != ExternalStorageFormat::None; + } + inline const std::string& getExternalStorageFile() const + { + return m_external_file; + } + void setAsExternalStorage( + const std::string& fileName, const ExternalStorageFormat fmt); - /** @} */ + void overrideExternalStorageFormatFlag(const ExternalStorageFormat fmt) + { + m_externally_stored = fmt; + } + /** Write scan data to a plain text, each line has: + * `x y z range intensity row_idx col_idx` + * + * For each point in the organized point cloud. + * Invalid points (e.g. no lidar return) are stored as (x,y,z)=(0,0,0) and + * range=0. + * + * \return true on success + */ + bool saveToTextFile(const std::string& filename) const; + + /** Loads the range, intensity, and organizedPoints members from a plain + * text file in the format describd in saveToTextFile() + */ + bool loadFromTextFile(const std::string& filename); + + /** @} */ // See base class docs mrpt::system::TTimeStamp getOriginalReceivedTimeStamp() const override; diff --git a/libs/maps/src/obs/CObservationRotatingScan.cpp b/libs/obs/src/CObservationRotatingScan.cpp similarity index 62% rename from libs/maps/src/obs/CObservationRotatingScan.cpp rename to libs/obs/src/CObservationRotatingScan.cpp index 1864601583..4d3afe7b8a 100644 --- a/libs/maps/src/obs/CObservationRotatingScan.cpp +++ b/libs/obs/src/CObservationRotatingScan.cpp @@ -7,16 +7,21 @@ | Released under BSD License. See: https://www.mrpt.org/License | +------------------------------------------------------------------------+ */ -#include "maps-precomp.h" // Precomp header +#include "obs-precomp.h" // Precomp header // +#include +#include +#include #include #include #include -#include #include #include #include #include +#include + +#include using namespace std; using namespace mrpt::obs; @@ -24,8 +29,6 @@ using namespace mrpt::obs; // This must be added to any CSerializable class implementation file. IMPLEMENTS_SERIALIZABLE(CObservationRotatingScan, CObservation, mrpt::obs) -// static CSinCosLookUpTableFor2DScans velodyne_sincos_tables; - using RotScan = CObservationRotatingScan; mrpt::system::TTimeStamp RotScan::getOriginalReceivedTimeStamp() const @@ -33,6 +36,73 @@ mrpt::system::TTimeStamp RotScan::getOriginalReceivedTimeStamp() const return originalReceivedTimestamp; } +namespace +{ +void writeMatricesTo(const RotScan& me, mrpt::serialization::CArchive& out) +{ + out.WriteAs(me.rangeImage.cols()); + out.WriteAs(me.rangeImage.rows()); + if (!me.rangeImage.empty()) + out.WriteBufferFixEndianness( + &me.rangeImage(0, 0), me.rangeImage.size()); + + out.WriteAs(me.intensityImage.cols()); + out.WriteAs(me.intensityImage.rows()); + if (!me.intensityImage.empty()) + out.WriteBufferFixEndianness( + &me.intensityImage(0, 0), me.intensityImage.size()); + + out.WriteAs(me.rangeOtherLayers.size()); + for (const auto& ly : me.rangeOtherLayers) + { + out << ly.first; + ASSERT_EQUAL_(ly.second.cols(), me.columnCount); + ASSERT_EQUAL_(ly.second.rows(), me.rowCount); + out.WriteBufferFixEndianness(&ly.second(0, 0), ly.second.size()); + } + + out.WriteAs(me.organizedPoints.cols()); + out.WriteAs(me.organizedPoints.rows()); + for (const auto& pt : me.organizedPoints) + out << pt; +} + +void readMatricesFrom(RotScan& me, mrpt::serialization::CArchive& in) +{ + const auto nCols = in.ReadAs(), nRows = in.ReadAs(); + me.rangeImage.resize(nRows, nCols); + if (!me.rangeImage.empty()) + in.ReadBufferFixEndianness(&me.rangeImage(0, 0), me.rangeImage.size()); + + { + const auto nIntCols = in.ReadAs(), + nIntRows = in.ReadAs(); + me.intensityImage.resize(nIntRows, nIntCols); + if (!me.intensityImage.empty()) + in.ReadBufferFixEndianness( + &me.intensityImage(0, 0), me.intensityImage.size()); + } + + const auto nOtherLayers = in.ReadAs(); + me.rangeOtherLayers.clear(); + for (size_t i = 0; i < nOtherLayers; i++) + { + std::string name; + in >> name; + auto& im = me.rangeOtherLayers[name]; + im.resize(nRows, nCols); + in.ReadBufferFixEndianness(&im(0, 0), im.size()); + } + + const auto nIntCols = in.ReadAs(), + nIntRows = in.ReadAs(); + me.organizedPoints.resize(nIntRows, nIntCols); + for (auto& pt : me.organizedPoints) + in >> pt; +} + +} // namespace + uint8_t RotScan::serializeGetVersion() const { return 0; } void RotScan::serializeTo(mrpt::serialization::CArchive& out) const { @@ -41,24 +111,15 @@ void RotScan::serializeTo(mrpt::serialization::CArchive& out) const << lidarModel << minRange << maxRange << sensorPose << originalReceivedTimestamp << has_satellite_timestamp; - out.WriteAs(rangeImage.cols()); - out.WriteAs(rangeImage.rows()); - if (!rangeImage.empty()) - out.WriteBufferFixEndianness(&rangeImage(0, 0), rangeImage.size()); + out.WriteAs(m_externally_stored); - out.WriteAs(intensityImage.cols()); - out.WriteAs(intensityImage.rows()); - if (!intensityImage.empty()) - out.WriteBufferFixEndianness( - &intensityImage(0, 0), intensityImage.size()); - - out.WriteAs(rangeOtherLayers.size()); - for (const auto& ly : rangeOtherLayers) + if (isExternallyStored()) + { // + out << m_external_file; + } + else { - out << ly.first; - ASSERT_EQUAL_(ly.second.cols(), columnCount); - ASSERT_EQUAL_(ly.second.rows(), rowCount); - out.WriteBufferFixEndianness(&ly.second(0, 0), ly.second.size()); + writeMatricesTo(*this, out); } } @@ -74,31 +135,21 @@ void RotScan::serializeFrom(mrpt::serialization::CArchive& in, uint8_t version) sensorPose >> originalReceivedTimestamp >> has_satellite_timestamp; - const auto nCols = in.ReadAs(), - nRows = in.ReadAs(); - rangeImage.resize(nRows, nCols); - if (!rangeImage.empty()) - in.ReadBufferFixEndianness( - &rangeImage(0, 0), rangeImage.size()); + m_externally_stored = + static_cast(in.ReadPOD()); - { - const auto nIntCols = in.ReadAs(), - nIntRows = in.ReadAs(); - intensityImage.resize(nIntRows, nIntCols); - if (!intensityImage.empty()) - in.ReadBufferFixEndianness( - &intensityImage(0, 0), intensityImage.size()); + if (isExternallyStored()) + { // just read the file name + in >> m_external_file; + rangeImage.resize(0, 0); + intensityImage.resize(0, 0); + organizedPoints.resize(0, 0); + rangeOtherLayers.clear(); } - - const auto nOtherLayers = in.ReadAs(); - rangeOtherLayers.clear(); - for (size_t i = 0; i < nOtherLayers; i++) + else { - std::string name; - in >> name; - auto& im = rangeOtherLayers[name]; - im.resize(nRows, nCols); - in.ReadBufferFixEndianness(&im(0, 0), im.size()); + m_external_file.clear(); + readMatricesFrom(*this, in); } } break; @@ -118,6 +169,8 @@ void RotScan::getDescriptionAsText(std::ostream& o) const o << "lidarModel: " << lidarModel << "\n"; o << "Range rows=" << rowCount << " cols=" << columnCount << "\n"; o << "Range resolution=" << rangeResolution << " [meter]\n"; + o << "Has organized points=" << (!organizedPoints.empty() ? "YES" : "NO") + << "\n"; o << "Scan azimuth: start=" << mrpt::RAD2DEG(startAzimuth) << " span=" << mrpt::RAD2DEG(azimuthSpan) << "\n"; o << "Sweep duration: " << sweepDuration << " [s]\n"; @@ -130,8 +183,6 @@ void RotScan::getDescriptionAsText(std::ostream& o) const << " (UTC)\n"; } -MRPT_TODO("toPointCloud / calibration"); - void RotScan::fromVelodyne(const mrpt::obs::CObservationVelodyneScan& o) { using Velo = mrpt::obs::CObservationVelodyneScan; @@ -338,6 +389,8 @@ void RotScan::fromVelodyne(const mrpt::obs::CObservationVelodyneScan& o) sweepDuration = 1e-6 * (microsecs_last_pkt - microsecs_1st_pkt) + timeBetweenLastTwoBlocks; + MRPT_TODO("populate organizedPoints"); + // Decode model byte: switch (model) { @@ -369,12 +422,16 @@ void RotScan::fromScan2D(const mrpt::obs::CObservation2DRangeScan& o) this->rangeImage.setZero(rowCount, columnCount); this->intensityImage.setZero(rowCount, columnCount); + this->organizedPoints.resize(rowCount, columnCount); this->rangeOtherLayers.clear(); this->rangeResolution = 0.01; this->azimuthSpan = o.aperture * (o.rightToLeft ? +1.0 : -1.0); this->startAzimuth = o.aperture * (o.rightToLeft ? -0.5 : +0.5); - for (size_t i = 0; i < o.getScanSize(); i++) + double a = startAzimuth; + const double Aa = azimuthSpan / o.getScanSize(); + + for (size_t i = 0; i < o.getScanSize(); i++, a += Aa) { uint16_t& range_out = rangeImage(0, i); uint8_t& intensity_out = intensityImage(0, i); @@ -391,6 +448,14 @@ void RotScan::fromScan2D(const mrpt::obs::CObservation2DRangeScan& o) range_out = r_discr; if (o.hasIntensity()) intensity_out = o.getScanIntensity(i); + + if (r > 0) + { + const auto ptLocal = mrpt::math::TPoint3Df( + cos(a) * range_out, sin(a) * range_out, 0); + + organizedPoints(0, i) = sensorPose.composePoint(ptLocal); + } } this->lidarModel = std::string("2D_SCAN_") + this->sensorLabel; @@ -398,14 +463,6 @@ void RotScan::fromScan2D(const mrpt::obs::CObservation2DRangeScan& o) MRPT_END } -void RotScan::fromPointCloud(const mrpt::obs::CObservationPointCloud& o) -{ - MRPT_START - MRPT_TODO("fromPointCloud"); - THROW_EXCEPTION("fromPointCloud() not implemented yet"); - MRPT_END -} - bool RotScan::fromGeneric(const mrpt::obs::CObservation& o) { MRPT_START @@ -420,12 +477,151 @@ bool RotScan::fromGeneric(const mrpt::obs::CObservation& o) fromScan2D(*o2D); return true; } - if (auto oPc = dynamic_cast(&o); oPc) + return false; + + MRPT_END +} + +void RotScan::load() const +{ + // Already loaded? + if (!isExternallyStored() || (isExternallyStored() && !rangeImage.empty())) + return; + + const auto abs_filename = + mrpt::io::lazy_load_absolute_path(m_external_file); + ASSERT_FILE_EXISTS_(abs_filename); + + auto& me = const_cast(*this); + + switch (m_externally_stored) { - fromPointCloud(*oPc); - return true; + case ExternalStorageFormat::None: break; + case ExternalStorageFormat::PlainTextFile: + { + me.loadFromTextFile(abs_filename); + } + break; + case ExternalStorageFormat::MRPT_Serialization: + { + mrpt::io::CFileGZInputStream f(abs_filename); + auto ar = mrpt::serialization::archiveFrom(f); + readMatricesFrom(me, ar); + } + break; + }; +} + +void RotScan::unload() const +{ + MRPT_START + if (!isExternallyStored() || organizedPoints.empty()) return; + + // Free memory, saving to the file if it doesn't exist: + const auto abs_filename = + mrpt::io::lazy_load_absolute_path(m_external_file); + + if (!mrpt::system::fileExists(abs_filename)) + { + switch (m_externally_stored) + { + case ExternalStorageFormat::None: break; + case ExternalStorageFormat::PlainTextFile: + { + this->saveToTextFile(abs_filename); + } + break; + case ExternalStorageFormat::MRPT_Serialization: + { + mrpt::io::CFileGZOutputStream f(abs_filename); + auto ar = mrpt::serialization::archiveFrom(f); + writeMatricesTo(*this, ar); + } + break; + }; } - return false; + + // Now we can safely free the mem: + auto& me = const_cast(*this); + + me.organizedPoints.resize(0, 0); + me.rangeImage.resize(0, 0); + me.intensityImage.resize(0, 0); + me.rangeOtherLayers.clear(); MRPT_END } + +void RotScan::setAsExternalStorage( + const std::string& fileName, const ExternalStorageFormat fmt) +{ + MRPT_START + ASSERTMSG_(!isExternallyStored(), "Already marked as externally-stored."); + m_external_file = fileName; + m_externally_stored = fmt; + + MRPT_END +} + +// Write scan data to a plain text, each line has: +// `x y z intensity range row_idx col_idx` +bool RotScan::saveToTextFile(const std::string& filename) const +{ + ASSERT_(!organizedPoints.empty()); + ASSERT_EQUAL_(organizedPoints.size(), rangeImage.size()); + if (!intensityImage.empty()) + { + ASSERT_EQUAL_(organizedPoints.size(), intensityImage.size()); + } + + std::ofstream f(filename); + if (!f.is_open()) return false; + + for (size_t r = 0; r < rowCount; r++) + { + for (size_t c = 0; c < columnCount; c++) + { + const auto& pt = organizedPoints(r, c); + + const int valInt = intensityImage.empty() + ? 0 + : static_cast(intensityImage(r, c)); + + f << mrpt::format( + "%g %g %g %f %i %zu %zu\n", pt.x, pt.y, pt.z, + rangeResolution * rangeImage(r, c), valInt, r, c); + } + } + return true; +} + +bool RotScan::loadFromTextFile(const std::string& filename) +{ + mrpt::math::CMatrixFloat data; + data.loadFromTextFile(filename); + if (data.rows() == 0) + THROW_EXCEPTION_FMT( + "Empty point cloud plain text file? `%s`", filename.c_str()); + + // `x y z range intensity row_idx col_idx` + ASSERT_EQUAL_(data.cols(), 7UL); + + ASSERT_GT_(rowCount, 0); + ASSERT_GT_(columnCount, 0); + + organizedPoints.resize(rowCount, columnCount); + rangeImage.resize(rowCount, columnCount); + intensityImage.resize(rowCount, columnCount); + + for (int i = 0; i < data.rows(); i++) + { + const size_t r = static_cast(data(i, 5)); + const size_t c = static_cast(data(i, 6)); + + organizedPoints(r, c) = {data(i, 0), data(i, 1), data(i, 2)}; + rangeImage(r, c) = data(i, 3); + intensityImage(r, c) = data(i, 4); + } + + return true; +} diff --git a/libs/maps/src/obs/CObservationRotatingScan_unittest.cpp b/libs/obs/src/CObservationRotatingScan_unittest.cpp similarity index 100% rename from libs/maps/src/obs/CObservationRotatingScan_unittest.cpp rename to libs/obs/src/CObservationRotatingScan_unittest.cpp diff --git a/libs/obs/src/CSerializable_unittest.cpp b/libs/obs/src/CSerializable_unittest.cpp index 1a5cc4bbbd..fb4af0ede7 100644 --- a/libs/obs/src/CSerializable_unittest.cpp +++ b/libs/obs/src/CSerializable_unittest.cpp @@ -50,6 +50,7 @@ TEST_CLASS_MOVE_COPY_CTORS(CObservationCANBusJ1939); TEST_CLASS_MOVE_COPY_CTORS(CObservationRawDAQ); TEST_CLASS_MOVE_COPY_CTORS(CObservation6DFeatures); TEST_CLASS_MOVE_COPY_CTORS(CObservationVelodyneScan); +TEST_CLASS_MOVE_COPY_CTORS(CObservationRotatingScan); TEST_CLASS_MOVE_COPY_CTORS(CActionRobotMovement2D); TEST_CLASS_MOVE_COPY_CTORS(CActionRobotMovement3D); @@ -69,6 +70,7 @@ const mrpt::rtti::TRuntimeClassId* lstClasses[] = { #endif CLASS_ID(CObservationCANBusJ1939), CLASS_ID(CObservationRawDAQ), CLASS_ID(CObservation6DFeatures), CLASS_ID(CObservationVelodyneScan), + CLASS_ID(CObservationRotatingScan), // Actions: CLASS_ID(CActionRobotMovement2D), CLASS_ID(CActionRobotMovement3D)}; diff --git a/libs/obs/src/registerAllClasses.cpp b/libs/obs/src/registerAllClasses.cpp index 5227f714e7..6010811e18 100644 --- a/libs/obs/src/registerAllClasses.cpp +++ b/libs/obs/src/registerAllClasses.cpp @@ -68,6 +68,7 @@ MRPT_INITIALIZER(registerAllClasses_mrpt_obs) registerClass(CLASS_ID(CActionRobotMovement3D)); registerClass(CLASS_ID(CObservationSkeleton)); + registerClass(CLASS_ID(CObservationRotatingScan)); registerClass(CLASS_ID(TMapGenericParams)); #endif diff --git a/libs/opengl/include/mrpt/opengl/CPointCloud.h b/libs/opengl/include/mrpt/opengl/CPointCloud.h index cc93527e51..b3bf6124bd 100644 --- a/libs/opengl/include/mrpt/opengl/CPointCloud.h +++ b/libs/opengl/include/mrpt/opengl/CPointCloud.h @@ -69,6 +69,13 @@ class CPointCloud : public CRenderizableShaderPoints, * PLY_import_set_vertex */ void PLY_import_set_vertex_count(size_t N) override; + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } + /** In a base class, reserve memory to prepare subsequent calls to * PLY_import_set_face */ void PLY_import_set_face_count([[maybe_unused]] size_t N) override {} diff --git a/libs/opengl/include/mrpt/opengl/CPointCloudColoured.h b/libs/opengl/include/mrpt/opengl/CPointCloudColoured.h index 527904d91d..51583bd1c5 100644 --- a/libs/opengl/include/mrpt/opengl/CPointCloudColoured.h +++ b/libs/opengl/include/mrpt/opengl/CPointCloudColoured.h @@ -248,6 +248,12 @@ class CPointCloudColoured : public CRenderizableShaderPoints, /** In a base class, reserve memory to prepare subsequent calls to * PLY_import_set_face */ void PLY_import_set_face_count([[maybe_unused]] size_t N) override {} + void PLY_import_set_vertex_timestamp( + [[maybe_unused]] size_t idx, + [[maybe_unused]] const double unixTimestamp) override + { + // do nothing, this class ignores timestamps + } /** In a base class, will be called after PLY_import_set_vertex_count() once * for each loaded point. * \param pt_color Will be nullptr if the loaded file does not provide diff --git a/libs/opengl/include/mrpt/opengl/PLY_import_export.h b/libs/opengl/include/mrpt/opengl/PLY_import_export.h index 1f15c5b5d9..ff00b4b0eb 100644 --- a/libs/opengl/include/mrpt/opengl/PLY_import_export.h +++ b/libs/opengl/include/mrpt/opengl/PLY_import_export.h @@ -68,6 +68,9 @@ class PLY_Importer size_t idx, const mrpt::math::TPoint3Df& pt, const mrpt::img::TColorf* pt_color = nullptr) = 0; + virtual void PLY_import_set_vertex_timestamp( + size_t idx, const double unixTimestamp) = 0; + /** @} */ private: diff --git a/libs/opengl/include/mrpt/opengl/Viewport.h b/libs/opengl/include/mrpt/opengl/Viewport.h index fc7346c5d9..6688b60de2 100644 --- a/libs/opengl/include/mrpt/opengl/Viewport.h +++ b/libs/opengl/include/mrpt/opengl/Viewport.h @@ -87,14 +87,17 @@ class Viewport : public mrpt::serialization::CSerializable, * Internally, the texture is drawn using a mrpt::opengl::CTexturedPlane * The viewport can be reverted to behave like a normal viewport by * calling setNormalMode() + * + * \param[in] transparentBackground This method can also make the viewport + * transparent (default), so the area not filled with the image still allows + * seeing an underlying viewport. */ - void setImageView(const mrpt::img::CImage& img); + void setImageView( + const mrpt::img::CImage& img, bool transparentBackground = true); - /** Just like \a setImageView but moves the internal image memory instead of - * making a copy, so it's faster but empties the input image. - * \sa setImageView - */ - void setImageView(mrpt::img::CImage&& img); + /** \overload With move semantics */ + void setImageView( + mrpt::img::CImage&& img, bool transparentBackground = true); /** Returns true if setImageView() has been called on this viewport */ bool isImageViewMode() const { return !!m_imageViewPlane; } @@ -102,7 +105,7 @@ class Viewport : public mrpt::serialization::CSerializable, /** Reset the viewport to normal mode: rendering its own objects. * \sa setCloneView, setNormalMode */ - inline void resetCloneView() { setNormalMode(); } + void resetCloneView() { setNormalMode(); } /** If set to true, and setCloneView() has been called, this viewport will * be rendered using the camera of the cloned viewport. @@ -113,7 +116,7 @@ class Viewport : public mrpt::serialization::CSerializable, * Note this works even for viewports not in "clone" mode, so you can * render different scenes but using the same camera. */ - inline void setClonedCameraFrom(const std::string& viewPortName) + void setClonedCameraFrom(const std::string& viewPortName) { m_isClonedCamera = true; m_clonedCameraViewport = viewPortName; @@ -123,6 +126,9 @@ class Viewport : public mrpt::serialization::CSerializable, * setImageView */ void setNormalMode(); + void setViewportVisibility(bool visible) { m_isViewportVisible = visible; } + bool getViewportVisibility() const { return m_isViewportVisible; } + /** @} */ // end of Set the "viewport mode" @@ -147,7 +153,7 @@ class Viewport : public mrpt::serialization::CSerializable, @{ */ /** Returns the name of the viewport */ - inline std::string getName() { return m_name; } + std::string getName() { return m_name; } /** Change the viewport position and dimension on the rendering window. * X & Y coordinates here can have two interpretations: * - If in the range [0,1], they are factors with respect to the actual @@ -205,11 +211,8 @@ class Viewport : public mrpt::serialization::CSerializable, void getLightShadowClipDistances(float& clip_min, float& clip_max) const; /** Set the border size ("frame") of the viewport (default=0) */ - inline void setBorderSize(unsigned int lineWidth) - { - m_borderWidth = lineWidth; - } - inline unsigned int getBorderSize() const { return m_borderWidth; } + void setBorderSize(unsigned int lineWidth) { m_borderWidth = lineWidth; } + unsigned int getBorderSize() const { return m_borderWidth; } void setBorderColor(const mrpt::img::TColor& c) { m_borderColor = c; } const mrpt::img::TColor& getBorderColor() const { return m_borderColor; } @@ -217,20 +220,20 @@ class Viewport : public mrpt::serialization::CSerializable, /** Return whether the viewport will be rendered transparent over previous * viewports. */ - inline bool isTransparent() { return m_isTransparent; } + bool isTransparent() { return m_isTransparent; } /** Set the transparency, that is, whether the viewport will be rendered * transparent over previous viewports (default=false). */ - inline void setTransparent(bool trans) { m_isTransparent = trans; } + void setTransparent(bool trans) { m_isTransparent = trans; } /** Defines the viewport background color */ - inline void setCustomBackgroundColor(const mrpt::img::TColorf& color) + void setCustomBackgroundColor(const mrpt::img::TColorf& color) { m_background_color = color; } - inline mrpt::img::TColorf getCustomBackgroundColor() const + mrpt::img::TColorf getCustomBackgroundColor() const { return m_background_color; } @@ -280,10 +283,10 @@ class Viewport : public mrpt::serialization::CSerializable, using const_iterator = CListOpenGLObjects::const_iterator; using iterator = CListOpenGLObjects::iterator; - inline const_iterator begin() const { return m_objects.begin(); } - inline const_iterator end() const { return m_objects.end(); } - inline iterator begin() { return m_objects.begin(); } - inline iterator end() { return m_objects.end(); } + const_iterator begin() const { return m_objects.begin(); } + const_iterator end() const { return m_objects.end(); } + iterator begin() { return m_objects.begin(); } + iterator end() { return m_objects.end(); } /** Delete all internal obejcts * \sa insert */ void clear(); @@ -355,8 +358,8 @@ class Viewport : public mrpt::serialization::CSerializable, void removeObject(const CRenderizable::Ptr& obj); /** Number of objects contained. */ - inline size_t size() const { return m_objects.size(); } - inline bool empty() const { return m_objects.empty(); } + size_t size() const { return m_objects.size(); } + bool empty() const { return m_objects.empty(); } /** Get a reference to the camera associated with this viewport. */ opengl::CCamera& getCamera() { return m_camera; } /** Get a reference to the camera associated with this viewport. */ @@ -440,6 +443,8 @@ class Viewport : public mrpt::serialization::CSerializable, /** Set by setCloneCamera */ bool m_isClonedCamera{false}; + bool m_isViewportVisible = true; + /** Only if m_isCloned=true */ std::string m_clonedViewport; @@ -506,7 +511,7 @@ class Viewport : public mrpt::serialization::CSerializable, */ opengl::CListOpenGLObjects m_objects; - void internal_enableImageView(); + void internal_enableImageView(bool transparentBackground); // OpenGL global settings: bool m_OpenGL_enablePolygonNicest{true}; @@ -563,7 +568,7 @@ class mrptEventGLPreRender : public mrpt::system::mrptEvent void do_nothing() override {} public: - inline mrptEventGLPreRender(const Viewport* obj) : source_viewport(obj) {} + mrptEventGLPreRender(const Viewport* obj) : source_viewport(obj) {} const Viewport* const source_viewport; }; // End of class def. @@ -586,7 +591,7 @@ class mrptEventGLPostRender : public mrpt::system::mrptEvent void do_nothing() override {} public: - inline mrptEventGLPostRender(const Viewport* obj) : source_viewport(obj) {} + mrptEventGLPostRender(const Viewport* obj) : source_viewport(obj) {} const Viewport* const source_viewport; }; // End of class def. diff --git a/libs/opengl/src/CPointCloud.cpp b/libs/opengl/src/CPointCloud.cpp index 0aa9fd3b25..30c5557780 100644 --- a/libs/opengl/src/CPointCloud.cpp +++ b/libs/opengl/src/CPointCloud.cpp @@ -432,13 +432,7 @@ void CPointCloud::markAllPointsAsNew() /** In a base class, reserve memory to prepare subsequent calls to * PLY_import_set_vertex */ -void CPointCloud::PLY_import_set_vertex_count(size_t N) -{ - std::unique_lock wfWriteLock( - CRenderizableShaderPoints::m_pointsMtx.data); - - this->resize(N); -} +void CPointCloud::PLY_import_set_vertex_count(size_t N) { this->resize(N); } /** In a base class, will be called after PLY_import_set_vertex_count() once * for each loaded point. \param pt_color Will be nullptr if the loaded file @@ -448,9 +442,6 @@ void CPointCloud::PLY_import_set_vertex( size_t idx, const mrpt::math::TPoint3Df& pt, [[maybe_unused]] const mrpt::img::TColorf* pt_color) { - std::unique_lock wfWriteLock( - CRenderizableShaderPoints::m_pointsMtx.data); - this->setPoint(idx, pt.x, pt.y, pt.z); } diff --git a/libs/opengl/src/CPointCloudColoured.cpp b/libs/opengl/src/CPointCloudColoured.cpp index cbd4a83d8b..e49da40c45 100644 --- a/libs/opengl/src/CPointCloudColoured.cpp +++ b/libs/opengl/src/CPointCloudColoured.cpp @@ -247,6 +247,9 @@ void CPointCloudColoured::PLY_export_get_vertex( size_t idx, mrpt::math::TPoint3Df& pt, bool& pt_has_color, mrpt::img::TColorf& pt_color) const { + std::shared_lock wfReadLock( + CRenderizableShaderPoints::m_pointsMtx.data); + auto& p = m_points[idx]; auto& p_color = m_point_colors[idx]; p = pt; diff --git a/libs/opengl/src/PLY_import_export.cpp b/libs/opengl/src/PLY_import_export.cpp index 9861dbf9ef..508ae811e3 100644 --- a/libs/opengl/src/PLY_import_export.cpp +++ b/libs/opengl/src/PLY_import_export.cpp @@ -52,7 +52,9 @@ WARRANTY OF MERCHANTABILITY OR FITNESS FOR A PARTICULAR PURPOSE. #include #include +#include #include +#include using namespace std; using namespace mrpt; @@ -69,9 +71,10 @@ using namespace mrpt::img; /* scalar data types supported by PLY format */ -enum +enum PLY_DATA_TYPE { PLY_START_TYPE = 0, + PLY_INVALID = 0, PLY_CHAR = 1, PLY_SHORT = 2, PLY_INT = 3, @@ -94,32 +97,51 @@ const char STORE_PROP = 1; const char OTHER_PROP = 0; const char NAMED_PROP = 1; -typedef struct PlyProperty +struct PlyProperty { /* description of a property */ + PlyProperty() = default; + + PlyProperty( + const char* Name, PLY_DATA_TYPE External_type, + PLY_DATA_TYPE Internal_type, size_t Offset, bool Is_list = false, + PLY_DATA_TYPE Count_external = PLY_INVALID, + PLY_DATA_TYPE Count_internal = PLY_INVALID, size_t Count_offset = 0) + : name(Name), + external_type(External_type), + internal_type(Internal_type), + offset(Offset), + count_external(Count_external), + count_internal(Count_internal), + count_offset(Count_offset) + { + } + std::string name; /* property name */ - int external_type = 0; /* file's data type */ - int internal_type = 0; /* program's data type */ - int offset = 0; /* offset bytes of prop in a struct */ + PLY_DATA_TYPE external_type = PLY_INVALID; /* file's data type */ + PLY_DATA_TYPE internal_type = PLY_INVALID; /* program's data type */ - int is_list = 0; /* 1 = list, 0 = scalar */ - int count_external = 0; /* file's count type */ - int count_internal = 0; /* program's count type */ - int count_offset = 0; /* offset byte for list count */ + size_t offset = 0; /* offset bytes of prop in a struct */ -} PlyProperty; + bool is_list = false; + PLY_DATA_TYPE count_external = PLY_INVALID; /* file's count type */ + PLY_DATA_TYPE count_internal = PLY_INVALID; /* program's count type */ + size_t count_offset = 0; /* offset byte for list count */ +}; -typedef struct PlyElement +struct PlyElement { /* description of an element */ - PlyElement() : other_offset(NO_OTHER_PROPS) {} + PlyElement() {} + string name; /* element name */ - int num{0}; /* number of elements in this object */ - int size{0}; /* size of element (bytes) or -1 if variable */ + int num = 0; /* number of elements in this object */ + int size = 0; /* size of element (bytes) or -1 if variable */ vector props; /* list of properties in the file */ vector store_prop; /* flags: property wanted by user? */ - int other_offset = 0; /* offset to un-asked-for props, or -1 if none*/ + int other_offset = + NO_OTHER_PROPS; /* offset to un-asked-for props, or -1 if none*/ int other_size = 0; /* size of other_props structure */ -} PlyElement; +}; struct PlyFile { /* description of PLY file */ @@ -133,12 +155,52 @@ struct PlyFile PlyElement* which_elem{nullptr}; /* which element we're currently writing */ }; -const std::string type_names[] = { - string("invalid"), string("char"), string("short"), - string("int"), string("uchar"), string("ushort"), - string("uint"), string("float"), string("double"), +using namespace std::string_literals; +const std::map type_names = { + {"char"s, PLY_CHAR}, // + + {"short"s, PLY_SHORT}, // + {"int16"s, PLY_SHORT}, // + + {"int"s, PLY_INT}, // + {"int32"s, PLY_INT}, // + + {"uchar"s, PLY_UCHAR}, // + {"uint8"s, PLY_UCHAR}, // + + {"ushort"s, PLY_USHORT}, // + {"uint16"s, PLY_USHORT}, // + + {"uint"s, PLY_UINT}, // + {"uint32"s, PLY_UINT}, // + + {"float"s, PLY_FLOAT}, // + {"float32"s, PLY_FLOAT}, // + + {"double"s, PLY_DOUBLE}, // + {"float64"s, PLY_DOUBLE}, // +}; + +const std::map type_names_inv = { + {PLY_CHAR, "char"}, // + {PLY_SHORT, "short"}, // + {PLY_INT, "int"}, // + {PLY_UCHAR, "uchar"}, // + {PLY_USHORT, "ushort"}, // + {PLY_UINT, "uint"}, // + {PLY_FLOAT, "float"s}, // + {PLY_DOUBLE, "double"}, // }; + const int ply_type_size[] = {0, 1, 2, 4, 1, 2, 4, 4, 8}; +// PLY_CHAR = 1, +// PLY_SHORT = 2, +// PLY_INT = 3, +// PLY_UCHAR = 4, +// PLY_USHORT = 5, +// PLY_UINT = 6, +// PLY_FLOAT = 7, +// PLY_DOUBLE = 8, /* find an element in a plyfile's list */ PlyElement* find_element(PlyFile*, const std::string& s); @@ -147,7 +209,7 @@ PlyElement* find_element(PlyFile*, const std::string& s); PlyProperty* find_property(PlyElement*, const std::string& s, int*); /* write to a file the word describing a PLY file data type */ -void write_scalar_type(FILE*, int); +void write_scalar_type(FILE*, PLY_DATA_TYPE); /* read a line from a file and break it up into separate words */ vector get_words(FILE*, string&); @@ -759,8 +821,8 @@ called ply_get_element_setup(). void ply_get_property( PlyFile* plyfile, const string& elem_name, const PlyProperty* prop) { - PlyElement* elem; - PlyProperty* prop_ptr; + PlyElement* elem = nullptr; + PlyProperty* prop_ptr = nullptr; int index; /* find information about the element */ @@ -772,9 +834,8 @@ void ply_get_property( prop_ptr = find_property(elem, prop->name, &index); if (prop_ptr == nullptr) { - fprintf( - stderr, "Warning: Can't find property '%s' in element '%s'\n", - prop->name.c_str(), elem_name.c_str()); + // "Warning: Can't find property '%s' in element '%s'\n", + // prop->name.c_str(), elem_name.c_str() return; } prop_ptr->internal_type = prop->internal_type; @@ -1198,7 +1259,7 @@ Write to a file the word that represents a PLY data type. code - code for type ******************************************************************************/ -void write_scalar_type(FILE* fp, int code) +void write_scalar_type(FILE* fp, PLY_DATA_TYPE code) { /* make sure this is a valid code */ @@ -1208,7 +1269,7 @@ void write_scalar_type(FILE* fp, int code) /* write the code to a file */ - fprintf(fp, "%s", type_names[code].c_str()); + fprintf(fp, "%s", type_names_inv.at(code).c_str()); } /****************************************************************************** @@ -1702,15 +1763,12 @@ Return the type of a property, given the name of the property. returns integer code for property, or 0 if not found ******************************************************************************/ -int get_prop_type(const string& type_name) +PLY_DATA_TYPE get_prop_type(const string& type_name) { - int i; + auto it = type_names.find(type_name); + if (it != type_names.end()) return it->second; - for (i = PLY_START_TYPE + 1; i < PLY_END_TYPE; i++) - if (type_name == type_names[i]) return (i); - - /* if we get here, we didn't find the type */ - return (0); + THROW_EXCEPTION_FMT("Unknown PLY data type: '%s'", type_name.c_str()); } /****************************************************************************** @@ -1727,24 +1785,22 @@ void add_property(PlyFile* plyfile, const vector& words) /* add this property to the list of properties of the current element */ PlyElement* elem = &(*plyfile->elems.rbegin()); - elem->props.emplace_back(); - - PlyProperty* prop = &(*elem->props.rbegin()); + PlyProperty& prop = elem->props.emplace_back(); /* create the new property */ if (words[1] == "list") { /* is a list */ - prop->count_external = get_prop_type(words[2]); - prop->external_type = get_prop_type(words[3]); - prop->name = words[4]; - prop->is_list = 1; + prop.count_external = get_prop_type(words[2]); + prop.external_type = get_prop_type(words[3]); + prop.name = words[4]; + prop.is_list = true; } else { /* not a list */ - prop->external_type = get_prop_type(words[1]); - prop->name = words[2]; - prop->is_list = 0; + prop.external_type = get_prop_type(words[1]); + prop.name = words[2]; + prop.is_list = false; } } @@ -1785,20 +1841,31 @@ const float VAL_NOT_SET = -1e10; struct TVertex { - float x{0}, y{0}, z{0}; - float r{0}, g{0}, b{0}; - float intensity{0}; + float x = 0, y = 0, z = 0; + float r = 0, g = 0, b = 0; + float intensity = 0; + float timestamp = 0; + + void markAsNotSet() + { + x = y = z = VAL_NOT_SET; + r = g = b = VAL_NOT_SET; + intensity = VAL_NOT_SET; + timestamp = VAL_NOT_SET; + } }; -const PlyProperty vert_props[] = - {/* list of property information for a vertex */ - // is_list count_external - // count_internal count_offset - {"x", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, x), 0, 0, 0, 0}, - {"y", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, y), 0, 0, 0, 0}, - {"z", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, z), 0, 0, 0, 0}, - {"intensity", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, intensity), 0, 0, 0, - 0}}; +const std::array vert_props = { + /* list of property information for a vertex */ + // ... is_list count_external count_internal count_offset + PlyProperty("x", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, x)), + PlyProperty("y", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, y)), + PlyProperty("z", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, z)), + PlyProperty( + "intensity", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, intensity)), + PlyProperty( + "timestamp", PLY_FLOAT, PLY_FLOAT, offsetof(TVertex, timestamp)), +}; struct TFace { @@ -1809,10 +1876,9 @@ struct TFace const PlyProperty face_props[] = {/* list of property information for a vertex */ - {"intensity", PLY_FLOAT, PLY_FLOAT, offsetof(TFace, intensity), 0, 0, 0, - 0}, - {"vertex_indices", PLY_INT, PLY_INT, offsetof(TFace, verts), 1, PLY_UCHAR, - PLY_UCHAR, offsetof(TFace, nverts)}}; + {"intensity", PLY_FLOAT, PLY_FLOAT, offsetof(TFace, intensity)}, + {"vertex_indices", PLY_INT, PLY_INT, offsetof(TFace, verts), true, + PLY_UCHAR, PLY_UCHAR, offsetof(TFace, nverts)}}; /* Loads from a PLY file. @@ -1845,46 +1911,42 @@ bool PLY_Importer::loadFromPlyFile( // printf ("element %s %d\n", elem_name, num_elems); /* if we're on vertex elements, read them in */ - if ("vertex" == elem_name) - { - /* set up for getting vertex elements */ - for (const auto& vert_prop : vert_props) - ply_get_property(ply, elem_name, &vert_prop); + if ("vertex" != elem_name) continue; - /* grab all the vertex elements */ - this->PLY_import_set_vertex_count(num_elems); - for (int j = 0; j < num_elems; j++) - { - TVertex pt; - pt.x = pt.y = pt.z = pt.r = pt.g = pt.b = pt.intensity = - VAL_NOT_SET; - - /* grab an element from the file */ - ply_get_element(ply, reinterpret_cast(&pt)); - const TPoint3Df xyz(pt.x, pt.y, pt.z); - if (pt.intensity != VAL_NOT_SET) - { // Grayscale - const TColorf col( - pt.intensity, pt.intensity, pt.intensity); - this->PLY_import_set_vertex(j, xyz, &col); - } - else if ( - pt.r != VAL_NOT_SET && pt.g != VAL_NOT_SET && - pt.b != VAL_NOT_SET) - { // RGB - const TColorf col(pt.r, pt.g, pt.b); - this->PLY_import_set_vertex(j, xyz, &col); - } - else - { // No color - this->PLY_import_set_vertex(j, xyz); - } + /* set up for getting vertex elements */ + for (const auto& vert_prop : vert_props) + ply_get_property(ply, elem_name, &vert_prop); + + /* grab all the vertex elements */ + this->PLY_import_set_vertex_count(num_elems); + for (int j = 0; j < num_elems; j++) + { + TVertex pt; + pt.markAsNotSet(); + + /* grab an element from the file */ + ply_get_element(ply, reinterpret_cast(&pt)); + const TPoint3Df xyz(pt.x, pt.y, pt.z); + if (pt.intensity != VAL_NOT_SET) + { // Grayscale + const TColorf col(pt.intensity, pt.intensity, pt.intensity); + this->PLY_import_set_vertex(j, xyz, &col); + } + else if ( + pt.r != VAL_NOT_SET && pt.g != VAL_NOT_SET && + pt.b != VAL_NOT_SET) + { // RGB + const TColorf col(pt.r, pt.g, pt.b); + this->PLY_import_set_vertex(j, xyz, &col); } + else + { // No color + this->PLY_import_set_vertex(j, xyz); + } + // timestamp? + if (pt.timestamp != VAL_NOT_SET) + this->PLY_import_set_vertex_timestamp(j, pt.timestamp); } - - // print out the properties we got, for debugging - // for (int j = 0; j < nprops; j++) - // printf ("property %s\n", plist[j]->name); } // grab and print out the comments in the file diff --git a/libs/opengl/src/Viewport.cpp b/libs/opengl/src/Viewport.cpp index 058100b078..b28c48dd3e 100644 --- a/libs/opengl/src/Viewport.cpp +++ b/libs/opengl/src/Viewport.cpp @@ -70,8 +70,6 @@ void Viewport::setViewportPosition( const double x, const double y, const double width, const double height) { MRPT_START - ASSERT_(width > 0); - ASSERT_(height > 0); m_view_x = x; m_view_y = y; @@ -118,7 +116,7 @@ int sizeFromRatio(const int startCoord, const double dSize, const int iLength) if (dSize >= -1) return static_cast(-iLength * dSize - startCoord + 1); else - return static_cast(-dSize - startCoord + 1); + return static_cast(iLength + dSize - startCoord + 1); } // Otherwise: a fraction return static_cast(iLength * dSize); @@ -570,6 +568,8 @@ void Viewport::render( mrpt::system::CTimeLoggerEntry tle(opengl_profiler(), "Viewport.render"); #endif + if (!m_isViewportVisible) return; + // Prepare shaders upon first invokation: if (m_threadedData.get().shaders.empty()) loadDefaultShaders(); @@ -640,7 +640,9 @@ void Viewport::render( if (!m_isTransparent) { // Clear color & depth buffers: - // Save? + // Save: + GLfloat prevBkCol[4]; + glGetFloatv(GL_COLOR_CLEAR_VALUE, prevBkCol); glClearColor( m_background_color.R, m_background_color.G, m_background_color.B, @@ -650,6 +652,8 @@ void Viewport::render( glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT | GL_STENCIL_BUFFER_BIT); CHECK_OPENGL_ERROR_IN_DEBUG(); + + glClearColor(prevBkCol[0], prevBkCol[1], prevBkCol[2], prevBkCol[3]); } else { // Clear depth buffer only: @@ -701,7 +705,7 @@ void Viewport::render( #endif } -uint8_t Viewport::serializeGetVersion() const { return 9; } +uint8_t Viewport::serializeGetVersion() const { return 10; } void Viewport::serializeTo(mrpt::serialization::CArchive& out) const { // Save data: @@ -756,6 +760,9 @@ void Viewport::serializeTo(mrpt::serialization::CArchive& out) const // Added in v9: out << m_clip_max << m_clip_min << m_lightShadowClipMin << m_lightShadowClipMax; + + // v10: + out << m_isViewportVisible; } void Viewport::serializeFrom(mrpt::serialization::CArchive& in, uint8_t version) @@ -772,6 +779,7 @@ void Viewport::serializeFrom(mrpt::serialization::CArchive& in, uint8_t version) case 7: case 8: case 9: + case 10: { // Load data: in >> m_camera >> m_isCloned >> m_isClonedCamera >> @@ -865,6 +873,8 @@ void Viewport::serializeFrom(mrpt::serialization::CArchive& in, uint8_t version) in >> m_clip_max >> m_clip_min >> m_lightShadowClipMin >> m_lightShadowClipMax; } + + if (version >= 10) { in >> m_isViewportVisible; } } break; default: MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(version); @@ -1146,18 +1156,19 @@ void Viewport::setNormalMode() m_isClonedCamera = false; } -void Viewport::setImageView(const mrpt::img::CImage& img) +void Viewport::setImageView( + const mrpt::img::CImage& img, bool transparentBackground) { - internal_enableImageView(); + internal_enableImageView(transparentBackground); m_imageViewPlane->assignImage(img); } -void Viewport::setImageView(mrpt::img::CImage&& img) +void Viewport::setImageView(mrpt::img::CImage&& img, bool transparentBackground) { - internal_enableImageView(); + internal_enableImageView(transparentBackground); m_imageViewPlane->assignImage(img); } -void Viewport::internal_enableImageView() +void Viewport::internal_enableImageView(bool transparentBackground) { // If this is the first time, we have to create the quad object: if (!m_imageViewPlane) @@ -1166,6 +1177,7 @@ void Viewport::internal_enableImageView() // Flip vertically: m_imageViewPlane->setPlaneCorners(-1, 1, 1, -1); } + setTransparent(transparentBackground); } /** Evaluates the bounding box of this object (including possible children) in diff --git a/libs/ros1bridge/src/point_cloud2.cpp b/libs/ros1bridge/src/point_cloud2.cpp index f44aed3d7c..927e99701a 100644 --- a/libs/ros1bridge/src/point_cloud2.cpp +++ b/libs/ros1bridge/src/point_cloud2.cpp @@ -261,7 +261,7 @@ bool mrpt::ros1bridge::toROS( const auto& xs = obj.getPointsBufferRef_x(); const auto& ys = obj.getPointsBufferRef_y(); const auto& zs = obj.getPointsBufferRef_z(); - const auto& Is = obj.getPointsBufferRef_intensity(); + const auto* Is = obj.getPointsBufferRef_intensity(); float* pointDest = reinterpret_cast(msg.data.data()); for (size_t i = 0; i < xs.size(); i++) @@ -269,7 +269,7 @@ bool mrpt::ros1bridge::toROS( *pointDest++ = xs[i]; *pointDest++ = ys[i]; *pointDest++ = zs[i]; - *pointDest++ = Is[i]; + *pointDest++ = (*Is)[i]; } return true; diff --git a/libs/ros2bridge/include/mrpt/ros2bridge/point_cloud2.h b/libs/ros2bridge/include/mrpt/ros2bridge/point_cloud2.h index e56778cf22..386b48aa1e 100644 --- a/libs/ros2bridge/include/mrpt/ros2bridge/point_cloud2.h +++ b/libs/ros2bridge/include/mrpt/ros2bridge/point_cloud2.h @@ -11,6 +11,7 @@ #include #include +#include #include #include @@ -28,7 +29,7 @@ namespace mrpt::ros2bridge /** Convert sensor_msgs/PointCloud2 -> mrpt::slam::CSimplePointsMap * Only (x,y,z) data is converted. To use the intensity channel, see - * the alternative signature for CPointsMapXYZI. + * the alternative signatures for CPointsMapXYZI or CPointsMapXYZIRT * Requires point cloud fields: x,y,z. * \return true on sucessful conversion, false on any error. * \sa toROS @@ -43,14 +44,27 @@ bool fromROS( bool fromROS( const sensor_msgs::msg::PointCloud2& msg, mrpt::maps::CPointsMapXYZI& obj); +/** \overload For (x,y,z,intensity,ring,time) channels. + * Requires point cloud fields: x,y,z,intensity,ring,time + */ +bool fromROS( + const sensor_msgs::msg::PointCloud2& msg, + mrpt::maps::CPointsMapXYZIRT& obj); + /** Convert sensor_msgs/PointCloud2 -> mrpt::obs::CObservationRotatingScan. - * Requires point cloud fields: x,y,z,intensity,ring + * Requires point cloud fields: x,y,z,ring[,intensity][,time] + * + * If num_azimuth_divisions=0, it will be taken from the point cloud "width" + * field. + * + * Points are supposed to be given in the sensor frame of reference. + * */ bool fromROS( const sensor_msgs::msg::PointCloud2& m, mrpt::obs::CObservationRotatingScan& o, const mrpt::poses::CPose3D& sensorPoseOnRobot, - unsigned int num_azimuth_divisions = 360); + unsigned int num_azimuth_divisions = 0, float max_intensity = 1000.0f); /** Extract a list of fields found in the point cloud. * Typically: {"x","y","z","intensity"} @@ -71,12 +85,7 @@ bool toROS( const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg); -/** Convert mrpt::slam::CSimplePointsMap -> sensor_msgs/PointCloud2 - * The user must supply the "msg_header" field to be copied into the output - * message object, since that part does not appear in MRPT classes. - * - * Generated sensor_msgs::PointCloud2::channels: `x`, `y`, `z`, `intensity` - * +/** \overload With these fields: `x`, `y`, `z`, `intensity` * \return true on sucessful conversion, false on any error. * \sa fromROS */ @@ -85,6 +94,15 @@ bool toROS( const std_msgs::msg::Header& msg_header, sensor_msgs::msg::PointCloud2& msg); +/** \overload With these fields: `x`, `y`, `z`, `intensity` + * \return true on successful conversion, false on any error. + * \sa fromROS + */ +bool toROS( + const mrpt::maps::CPointsMapXYZIRT& obj, + const std_msgs::msg::Header& msg_header, + sensor_msgs::msg::PointCloud2& msg); + /** @} */ /** @} */ diff --git a/libs/ros2bridge/src/point_cloud2.cpp b/libs/ros2bridge/src/point_cloud2.cpp index f96de27374..a451ee53fe 100644 --- a/libs/ros2bridge/src/point_cloud2.cpp +++ b/libs/ros2bridge/src/point_cloud2.cpp @@ -18,6 +18,8 @@ // #include // MRPT_IS_BIG_ENDIAN +#include + using namespace mrpt::maps; static bool check_field( @@ -149,7 +151,6 @@ bool mrpt::ros2bridge::fromROS( if (incompatible || (!x_field || !y_field || !z_field || !i_field)) return false; - // If not, memcpy each group of contiguous fields separately for (unsigned int row = 0; row < msg.height; ++row) { const unsigned char* row_data = &msg.data[row * msg.row_step]; @@ -164,7 +165,69 @@ bool mrpt::ros2bridge::fromROS( get_float_from_field(i_field, msg_data, i); obj.insertPoint(x, y, z); - obj.setPointIntensity(obj.size() - 1, i / 255.0); + obj.setPointIntensity(obj.size() - 1, i); + } + } + return true; +} + +bool mrpt::ros2bridge::fromROS( + const sensor_msgs::msg::PointCloud2& msg, CPointsMapXYZIRT& obj) +{ + // Copy point data + unsigned int num_points = msg.width * msg.height; + + bool incompatible = false; + const sensor_msgs::msg::PointField *x_field = nullptr, *y_field = nullptr, + *z_field = nullptr, *i_field = nullptr, + *r_field = nullptr, *t_field = nullptr; + + for (unsigned int i = 0; i < msg.fields.size() && !incompatible; i++) + { + incompatible |= check_field(msg.fields[i], "x", &x_field); + incompatible |= check_field(msg.fields[i], "y", &y_field); + incompatible |= check_field(msg.fields[i], "z", &z_field); + incompatible |= check_field(msg.fields[i], "intensity", &i_field); + incompatible |= check_field(msg.fields[i], "ring", &r_field); + incompatible |= check_field(msg.fields[i], "time", &t_field); + } + + if (incompatible || (!x_field || !y_field || !z_field)) return false; + + obj.resize_XYZIRT(num_points, !!i_field, !!r_field, !!t_field); + + unsigned int idx = 0; + for (unsigned int row = 0; row < msg.height; ++row) + { + const unsigned char* row_data = &msg.data[row * msg.row_step]; + for (uint32_t col = 0; col < msg.width; ++col, ++idx) + { + const unsigned char* msg_data = row_data + col * msg.point_step; + + float x, y, z; + 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); + obj.setPointFast(idx, x, y, z); + + if (i_field) + { + float i; + get_float_from_field(i_field, msg_data, i); + obj.setPointIntensity(idx, i); + } + if (r_field) + { + uint16_t ring_id = 0; + get_uint16_from_field(r_field, msg_data, ring_id); + obj.setPointRing(idx, ring_id); + } + if (t_field) + { + float t; + get_float_from_field(t_field, msg_data, t); + obj.setPointTime(idx, t); + } } } return true; @@ -263,7 +326,7 @@ bool mrpt::ros2bridge::toROS( const auto& xs = obj.getPointsBufferRef_x(); const auto& ys = obj.getPointsBufferRef_y(); const auto& zs = obj.getPointsBufferRef_z(); - const auto& Is = obj.getPointsBufferRef_intensity(); + const auto* Is = obj.getPointsBufferRef_intensity(); float* pointDest = reinterpret_cast(msg.data.data()); for (size_t i = 0; i < xs.size(); i++) @@ -271,7 +334,96 @@ bool mrpt::ros2bridge::toROS( *pointDest++ = xs[i]; *pointDest++ = ys[i]; *pointDest++ = zs[i]; - *pointDest++ = Is[i]; + *pointDest++ = (*Is)[i]; + } + + return true; +} + +bool mrpt::ros2bridge::toROS( + const CPointsMapXYZIRT& obj, const std_msgs::msg::Header& msg_header, + sensor_msgs::msg::PointCloud2& msg) +{ + msg.header = msg_header; + + // 2D structure of the point cloud. If the cloud is unordered, height is + // 1 and width is the length of the point cloud. + msg.height = 1; + msg.width = obj.size(); + + std::vector names = {"x", "y", "z"}; + std::vector offsets = {0, sizeof(float) * 1, sizeof(float) * 2}; + + msg.point_step = sizeof(float) * 3; + + if (obj.hasIntensityField()) + { + names.push_back("intensity"); + offsets.push_back(msg.point_step); + msg.point_step += sizeof(float); + } + if (obj.hasTimeField()) + { + names.push_back("time"); + offsets.push_back(msg.point_step); + msg.point_step += sizeof(float); + } + if (obj.hasRingField()) + { + names.push_back("ring"); + offsets.push_back(msg.point_step); + msg.point_step += sizeof(uint16_t); + } + + msg.fields.resize(names.size()); + for (size_t i = 0; i < names.size(); i++) + { + auto& f = msg.fields.at(i); + + f.count = 1; + f.offset = offsets[i]; + f.datatype = (names[i] == "ring") + ? sensor_msgs::msg::PointField::UINT16 + : sensor_msgs::msg::PointField::FLOAT32; + f.name = names[i]; + } + +#if MRPT_IS_BIG_ENDIAN + msg.is_bigendian = true; +#else + msg.is_bigendian = false; +#endif + + msg.row_step = msg.width * msg.point_step; + + // data: + msg.data.resize(msg.row_step * msg.height); + + const auto& xs = obj.getPointsBufferRef_x(); + const auto& ys = obj.getPointsBufferRef_y(); + const auto& zs = obj.getPointsBufferRef_z(); + const auto& Is = obj.getPointsBufferRef_intensity(); + const auto& Rs = obj.getPointsBufferRef_ring(); + const auto& Ts = obj.getPointsBufferRef_timestamp(); + + uint8_t* pointDest = msg.data.data(); + for (size_t i = 0; i < xs.size(); i++) + { + int f = 0; + memcpy(pointDest + offsets[f++], &xs[i], sizeof(float)); + memcpy(pointDest + offsets[f++], &ys[i], sizeof(float)); + memcpy(pointDest + offsets[f++], &zs[i], sizeof(float)); + + if (obj.hasIntensityField()) + memcpy(pointDest + offsets[f++], &Is[i], sizeof(float)); + + if (obj.hasTimeField()) + memcpy(pointDest + offsets[f++], &Ts[i], sizeof(float)); + + if (obj.hasRingField()) + memcpy(pointDest + offsets[f++], &Rs[i], sizeof(uint16_t)); + + pointDest += msg.point_step; } return true; @@ -282,10 +434,11 @@ bool mrpt::ros2bridge::fromROS( const sensor_msgs::msg::PointCloud2& msg, mrpt::obs::CObservationRotatingScan& obj, const mrpt::poses::CPose3D& sensorPoseOnRobot, - unsigned int num_azimuth_divisions) + unsigned int num_azimuth_divisions, float max_intensity) { // Copy point data obj.timestamp = mrpt::ros2bridge::fromROS(msg.header.stamp); + obj.originalReceivedTimestamp = obj.timestamp; bool incompatible = false; const sensor_msgs::msg::PointField *x_field = nullptr, *y_field = nullptr, @@ -323,13 +476,33 @@ bool mrpt::ros2bridge::fromROS( ASSERT_NOT_EQUAL_(ring_min, ring_max); obj.rowCount = ring_max - ring_min + 1; + + const bool inputCloudIsOrganized = msg.height != 1; + + if (!num_azimuth_divisions) + { + if (inputCloudIsOrganized) + { + ASSERT_GT_(msg.width, 0U); + num_azimuth_divisions = msg.width; + } + else + { + THROW_EXCEPTION( + "An explicit value for num_azimuth_divisions must be given if " + "the input cloud is not 'organized'"); + } + } + obj.columnCount = num_azimuth_divisions; obj.rangeImage.resize(obj.rowCount, obj.columnCount); obj.rangeImage.fill(0); - // Default unit: 1cm - if (obj.rangeResolution == 0) obj.rangeResolution = 1e-2; + obj.sensorPose = sensorPoseOnRobot; + + // Default unit: 5mm + if (obj.rangeResolution == 0) obj.rangeResolution = 5e-3; if (i_field) { @@ -339,6 +512,11 @@ bool mrpt::ros2bridge::fromROS( else obj.intensityImage.resize(0, 0); + if (inputCloudIsOrganized) + { + obj.organizedPoints.resize(obj.rowCount, obj.columnCount); + } + // If not, memcpy each group of contiguous fields separately for (unsigned int row = 0; row < msg.height; ++row) { @@ -354,15 +532,24 @@ bool mrpt::ros2bridge::fromROS( get_float_from_field(z_field, msg_data, z); get_uint16_from_field(ring_field, msg_data, ring_id); - const mrpt::math::TPoint3D localPt = - sensorPoseOnRobot.inverseComposePoint( - mrpt::math::TPoint3D(x, y, z)); - const double azimuth = std::atan2(localPt.y, localPt.x); + const mrpt::math::TPoint3D localPt = {x, y, z}; - const auto az_idx = lround( - (num_azimuth_divisions - 1) * (azimuth + M_PI) / (2 * M_PI)); - ASSERT_GE_(az_idx, 0); - ASSERT_LE_(az_idx, num_azimuth_divisions - 1); + unsigned int az_idx; + if (inputCloudIsOrganized) + { + // "azimuth index" is just the "column": + az_idx = col; + } + else + { + // Recover "azimuth index" from trigonometry: + const double azimuth = std::atan2(localPt.y, localPt.x); + + az_idx = lround( + (num_azimuth_divisions - 1) * (azimuth + M_PI) / + (2 * M_PI)); + ASSERT_LE_(az_idx, num_azimuth_divisions - 1); + } // Store in matrix form: obj.rangeImage(ring_id, az_idx) = @@ -372,10 +559,14 @@ bool mrpt::ros2bridge::fromROS( { float intensity; get_float_from_field(i_field, msg_data, intensity); - ASSERT_LE_(intensity, 255.0f); - obj.intensityImage(ring_id, az_idx) = lround(intensity); + obj.intensityImage(ring_id, az_idx) = + lround(255 * intensity / max_intensity); } + + if (inputCloudIsOrganized) + obj.organizedPoints(ring_id, az_idx) = localPt; } } + return true; } diff --git a/package.xml b/package.xml index e636e9288d..a4c835275f 100644 --- a/package.xml +++ b/package.xml @@ -7,7 +7,7 @@ mrpt2 - 2.11.3 + 2.11.4 Mobile Robot Programming Toolkit (MRPT) version 2.x Jose-Luis Blanco-Claraco diff --git a/python/all_mrpt_math1.cpp b/python/all_mrpt_math1.cpp index b5c05d6677..e433f637e0 100644 --- a/python/all_mrpt_math1.cpp +++ b/python/all_mrpt_math1.cpp @@ -1,11 +1,12 @@ #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_4.cpp" #include "src/mrpt/math/CMatrixFixed.cpp" +#include "src/mrpt/math/MatrixVectorBase.cpp" #include "src/mrpt/math/CPolygon.cpp" diff --git a/python/generate-python.sh b/python/generate-python.sh index c6e320f649..04af9d7597 100755 --- a/python/generate-python.sh +++ b/python/generate-python.sh @@ -94,5 +94,5 @@ find $WRAP_OUT_DIR -name "*.cpp" | xargs -I FIL \ # applying manual patches: echo "Applying manual patches to pybind11 code..." -find . -name "patch-0*.diff" | xargs -I FIL bash -c "echo \"Applying patch: FIL\" && git apply FIL --ignore-whitespace" +find . -name "patch-0*.diff" | sort | xargs -I FIL bash -c "echo \"Applying patch: FIL\" && git apply FIL --ignore-whitespace" diff --git a/python/patch-003.diff b/python/patch-003.diff index b41e393e13..9b6aae0632 100644 --- a/python/patch-003.diff +++ b/python/patch-003.diff @@ -1,334 +1,3 @@ -diff --git a/python/src/mrpt/math/CMatrixDynamic.cpp b/python/src/mrpt/math/CMatrixDynamic.cpp -index 43b379213..edd9586d4 100644 ---- a/python/src/mrpt/math/CMatrixDynamic.cpp -+++ b/python/src/mrpt/math/CMatrixDynamic.cpp -@@ -42,8 +42,8 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string - cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); - cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("data", (float * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> float *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (float & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__getitem__", (float & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("ith")); - cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); - cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); - cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); -@@ -70,8 +70,8 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string - cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); - cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("data", (unsigned char * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> unsigned char *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned char &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned char &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); -+ cl.def("__call__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned char &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__getitem__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned char &", pybind11::return_value_policy::reference, pybind11::arg("ith")); - } - { // mrpt::math::CMatrixDynamic file:mrpt/math/CMatrixDynamic.h line:41 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixDynamic_unsigned_short_t", ""); -@@ -94,7 +94,7 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string - cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); - cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("data", (unsigned short * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> unsigned short *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned short &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned short &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); -+ cl.def("__call__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned short &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__getitem__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned short &", pybind11::return_value_policy::reference, pybind11::arg("ith")); - } - } -diff --git a/python/src/mrpt/math/CMatrixDynamic_1.cpp b/python/src/mrpt/math/CMatrixDynamic_1.cpp -index 2867b9ecf..7eae41c0a 100644 ---- a/python/src/mrpt/math/CMatrixDynamic_1.cpp -+++ b/python/src/mrpt/math/CMatrixDynamic_1.cpp -@@ -127,8 +127,8 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri - cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); - cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("data", (double * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("ith")); - cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); - cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); - cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); -diff --git a/python/src/mrpt/math/CMatrixFixed.cpp b/python/src/mrpt/math/CMatrixFixed.cpp -index e4a508e5f..342ed0569 100644 ---- a/python/src/mrpt/math/CMatrixFixed.cpp -+++ b/python/src/mrpt/math/CMatrixFixed.cpp -@@ -38,9 +38,9 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } -@@ -64,9 +64,9 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -@@ -91,9 +91,9 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -@@ -118,9 +118,9 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } -diff --git a/python/src/mrpt/math/CMatrixFixed_1.cpp b/python/src/mrpt/math/CMatrixFixed_1.cpp -index ed3593796..c0eee45ec 100644 ---- a/python/src/mrpt/math/CMatrixFixed_1.cpp -+++ b/python/src/mrpt/math/CMatrixFixed_1.cpp -@@ -38,9 +38,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } -@@ -64,9 +64,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -@@ -91,9 +91,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 -@@ -116,9 +116,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - } -diff --git a/python/src/mrpt/math/CMatrixFixed_2.cpp b/python/src/mrpt/math/CMatrixFixed_2.cpp -index 7ce27e1bf..f8bc51568 100644 ---- a/python/src/mrpt/math/CMatrixFixed_2.cpp -+++ b/python/src/mrpt/math/CMatrixFixed_2.cpp -@@ -38,9 +38,9 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } -@@ -64,9 +64,9 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 -@@ -89,9 +89,9 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 -@@ -114,9 +114,9 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -diff --git a/python/src/mrpt/math/CMatrixFixed_3.cpp b/python/src/mrpt/math/CMatrixFixed_3.cpp -index 7844b2818..2eb493a48 100644 ---- a/python/src/mrpt/math/CMatrixFixed_3.cpp -+++ b/python/src/mrpt/math/CMatrixFixed_3.cpp -@@ -38,9 +38,9 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 -@@ -62,9 +62,9 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } -@@ -88,9 +88,9 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -@@ -115,9 +115,9 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -diff --git a/python/src/mrpt/math/CMatrixFixed_4.cpp b/python/src/mrpt/math/CMatrixFixed_4.cpp -index c2c8d6a73..5307d0b77 100644 ---- a/python/src/mrpt/math/CMatrixFixed_4.cpp -+++ b/python/src/mrpt/math/CMatrixFixed_4.cpp -@@ -39,9 +39,9 @@ void bind_mrpt_math_CMatrixFixed_4(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 -@@ -64,9 +64,9 @@ void bind_mrpt_math_CMatrixFixed_4(std::function< pybind11::module &(std::string - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -+ cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -diff --git a/python/src/mrpt/math/CVectorDynamic.cpp b/python/src/mrpt/math/CVectorDynamic.cpp -index 780fbaa83..b9075ff96 100644 ---- a/python/src/mrpt/math/CVectorDynamic.cpp -+++ b/python/src/mrpt/math/CVectorDynamic.cpp -@@ -46,8 +46,8 @@ void bind_mrpt_math_CVectorDynamic(std::function< pybind11::module &(std::string - cl.def("resize", (void (mrpt::math::CVectorDynamic::*)(std::size_t, bool)) &mrpt::math::CVectorDynamic::resize, "C++: mrpt::math::CVectorDynamic::resize(std::size_t, bool) --> void", pybind11::arg("N"), pybind11::arg("zeroNewElements")); - cl.def("push_back", (void (mrpt::math::CVectorDynamic::*)(const double &)) &mrpt::math::CVectorDynamic::push_back, "C++: mrpt::math::CVectorDynamic::push_back(const double &) --> void", pybind11::arg("val")); - cl.def("segmentCopy", (class mrpt::math::CVectorDynamic (mrpt::math::CVectorDynamic::*)(int, int) const) &mrpt::math::CVectorDynamic::segmentCopy, "C++: mrpt::math::CVectorDynamic::segmentCopy(int, int) const --> class mrpt::math::CVectorDynamic", pybind11::arg("start"), pybind11::arg("LEN")); -- cl.def("__call__", (double & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (double & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); -+ cl.def("__call__", (double & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__getitem__", (double & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("ith")); - cl.def("assign", (class mrpt::math::CVectorDynamic & (mrpt::math::CVectorDynamic::*)(const class mrpt::math::CVectorDynamic &)) &mrpt::math::CVectorDynamic::operator=, "C++: mrpt::math::CVectorDynamic::operator=(const class mrpt::math::CVectorDynamic &) --> class mrpt::math::CVectorDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::math::CVectorDynamic file:mrpt/math/CVectorDynamic.h line:32 -@@ -70,8 +70,8 @@ void bind_mrpt_math_CVectorDynamic(std::function< pybind11::module &(std::string - cl.def("resize", (void (mrpt::math::CVectorDynamic::*)(std::size_t, bool)) &mrpt::math::CVectorDynamic::resize, "C++: mrpt::math::CVectorDynamic::resize(std::size_t, bool) --> void", pybind11::arg("N"), pybind11::arg("zeroNewElements")); - cl.def("push_back", (void (mrpt::math::CVectorDynamic::*)(const float &)) &mrpt::math::CVectorDynamic::push_back, "C++: mrpt::math::CVectorDynamic::push_back(const float &) --> void", pybind11::arg("val")); - cl.def("segmentCopy", (class mrpt::math::CVectorDynamic (mrpt::math::CVectorDynamic::*)(int, int) const) &mrpt::math::CVectorDynamic::segmentCopy, "C++: mrpt::math::CVectorDynamic::segmentCopy(int, int) const --> class mrpt::math::CVectorDynamic", pybind11::arg("start"), pybind11::arg("LEN")); -- cl.def("__call__", (float & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (float & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); -+ cl.def("__call__", (float & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -+ cl.def("__getitem__", (float & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("ith")); - cl.def("assign", (class mrpt::math::CVectorDynamic & (mrpt::math::CVectorDynamic::*)(const class mrpt::math::CVectorDynamic &)) &mrpt::math::CVectorDynamic::operator=, "C++: mrpt::math::CVectorDynamic::operator=(const class mrpt::math::CVectorDynamic &) --> class mrpt::math::CVectorDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - } diff --git a/python/src/mrpt/math/TPoint2D.cpp b/python/src/mrpt/math/TPoint2D.cpp index 80c7704f4..d137dc43c 100644 --- a/python/src/mrpt/math/TPoint2D.cpp diff --git a/python/patch-004.diff b/python/patch-004.diff index d784d39a02..e0acd99abe 100644 --- a/python/patch-004.diff +++ b/python/patch-004.diff @@ -1,12 +1,14 @@ diff --git a/python/src/mrpt/math/CMatrixDynamic.cpp b/python/src/mrpt/math/CMatrixDynamic.cpp -index edd9586d4..1b600737a 100644 +index 43b379213..1b600737a 100644 --- a/python/src/mrpt/math/CMatrixDynamic.cpp +++ b/python/src/mrpt/math/CMatrixDynamic.cpp -@@ -43,11 +43,23 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string +@@ -42,12 +42,24 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string + cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); cl.def("data", (float * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> float *", pybind11::return_value_policy::automatic); - cl.def("__call__", (float & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("ith")); +- cl.def("__call__", (float & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (float & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); @@ -27,15 +29,93 @@ index edd9586d4..1b600737a 100644 } { // mrpt::math::CMatrixDynamic file:mrpt/math/CMatrixDynamic.h line:41 pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixDynamic_unsigned_char_t", ""); +@@ -70,8 +82,8 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string + cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); + cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("data", (unsigned char * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> unsigned char *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned char &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned char &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned char &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__getitem__", (unsigned char & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned char &", pybind11::return_value_policy::reference, pybind11::arg("ith")); + } + { // mrpt::math::CMatrixDynamic file:mrpt/math/CMatrixDynamic.h line:41 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixDynamic_unsigned_short_t", ""); +@@ -94,7 +106,7 @@ void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string + cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); + cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("data", (unsigned short * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> unsigned short *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned short &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned short &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> unsigned short &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__getitem__", (unsigned short & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> unsigned short &", pybind11::return_value_policy::reference, pybind11::arg("ith")); + } + } diff --git a/python/src/mrpt/math/CMatrixDynamic_1.cpp b/python/src/mrpt/math/CMatrixDynamic_1.cpp -index 7eae41c0a..70f933be5 100644 +index 5e303af0c..be42731ed 100644 --- a/python/src/mrpt/math/CMatrixDynamic_1.cpp +++ b/python/src/mrpt/math/CMatrixDynamic_1.cpp -@@ -128,11 +128,23 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri +@@ -48,8 +48,8 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri + cl.def("derived", (class mrpt::math::CMatrixDynamic > & (mrpt::math::CMatrixDynamic>::*)()) &mrpt::math::CMatrixDynamic>::derived, "C++: mrpt::math::CMatrixDynamic>::derived() --> class mrpt::math::CMatrixDynamic > &", pybind11::return_value_policy::automatic); + cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::conservativeResize, "C++: mrpt::math::CMatrixDynamic>::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("data", (struct mrpt::math::TPoint3D_ * (mrpt::math::CMatrixDynamic>::*)()) &mrpt::math::CMatrixDynamic>::data, "C++: mrpt::math::CMatrixDynamic>::data() --> struct mrpt::math::TPoint3D_ *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::operator(), "C++: mrpt::math::CMatrixDynamic>::operator()(size_t, size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t)) &mrpt::math::CMatrixDynamic>::operator[], "C++: mrpt::math::CMatrixDynamic>::operator[](size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::operator(), "C++: mrpt::math::CMatrixDynamic>::operator()(size_t, size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__getitem__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t)) &mrpt::math::CMatrixDynamic>::operator[], "C++: mrpt::math::CMatrixDynamic>::operator[](size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::reference, pybind11::arg("ith")); + cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic>::*)() const) &mrpt::math::CMatrixDynamic>::cast_float, "C++: mrpt::math::CMatrixDynamic>::cast_float() const --> class mrpt::math::CMatrixDynamic"); + cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic>::*)() const) &mrpt::math::CMatrixDynamic>::cast_double, "C++: mrpt::math::CMatrixDynamic>::cast_double() const --> class mrpt::math::CMatrixDynamic"); + } +@@ -73,9 +73,9 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +@@ -99,11 +99,23 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); ++ ++ // Manually-added matrix methods: ++ using dat_t = double; ++ using mat_t = mrpt::math::CMatrixFixed; ++ cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); ++ cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); ++ cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); ++ cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); ++ cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); ++ cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); ++ cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); ++ cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); ++ cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); cl.def("data", (double * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("ith")); +- cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::operator[], "C++: mrpt::math::CMatrixDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); @@ -57,38 +137,18 @@ index 7eae41c0a..70f933be5 100644 { // mrpt::math::CMatrixD file:mrpt/math/CMatrixD.h line:23 pybind11::class_, PyCallBack_mrpt_math_CMatrixD, mrpt::serialization::CSerializable, mrpt::math::CMatrixDynamic> 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 "); diff --git a/python/src/mrpt/math/CMatrixFixed.cpp b/python/src/mrpt/math/CMatrixFixed.cpp -index 342ed0569..877ac0cb4 100644 +index a9ec794ef..2168c4bf9 100644 --- a/python/src/mrpt/math/CMatrixFixed.cpp +++ b/python/src/mrpt/math/CMatrixFixed.cpp -@@ -66,10 +66,22 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); -+ -+ // Manually-added matrix methods: -+ using dat_t = double; -+ using mat_t = mrpt::math::CMatrixFixed; -+ cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); -+ cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); -+ cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); -+ cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); -+ cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); -+ cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); -+ cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); -+ cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); -+ cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_4UL_4UL_t", ""); -@@ -93,10 +105,22 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c +@@ -38,12 +38,24 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -108,11 +168,15 @@ index 342ed0569..877ac0cb4 100644 } { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_6UL_6UL_t", ""); -@@ -120,8 +144,21 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c +@@ -65,11 +77,23 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + @@ -128,18 +192,31 @@ index 342ed0569..877ac0cb4 100644 + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_7UL_7UL_t", ""); +@@ -91,9 +115,9 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +@@ -117,11 +141,22 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -156,17 +233,89 @@ index c0eee45ec..9e7db6b2b 100644 + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 +@@ -63,9 +63,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_4UL_t", ""); +@@ -88,9 +88,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +@@ -114,9 +114,9 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + } diff --git a/python/src/mrpt/math/CMatrixFixed_2.cpp b/python/src/mrpt/math/CMatrixFixed_2.cpp -index f8bc51568..88d8935ca 100644 +index 4cfc7c55d..2f75fb4ea 100644 --- a/python/src/mrpt/math/CMatrixFixed_2.cpp +++ b/python/src/mrpt/math/CMatrixFixed_2.cpp -@@ -116,9 +116,20 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string +@@ -38,9 +38,9 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 +@@ -63,12 +63,23 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -183,16 +332,30 @@ index f8bc51568..88d8935ca 100644 + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_4UL_3UL_t", ""); +@@ -90,9 +101,9 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 +@@ -114,10 +125,22 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + @@ -209,13 +372,20 @@ index 2eb493a48..916e0bad4 100644 + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_4UL_4UL_t", ""); -@@ -90,10 +102,22 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string + } +diff --git a/python/src/mrpt/math/CMatrixFixed_3.cpp b/python/src/mrpt/math/CMatrixFixed_3.cpp +index 9f57fa132..0192960f3 100644 +--- a/python/src/mrpt/math/CMatrixFixed_3.cpp ++++ b/python/src/mrpt/math/CMatrixFixed_3.cpp +@@ -38,12 +38,24 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -235,7 +405,15 @@ index 2eb493a48..916e0bad4 100644 } { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_3UL_1UL_t", ""); -@@ -121,5 +145,18 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string +@@ -65,12 +77,23 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -251,18 +429,31 @@ index 2eb493a48..916e0bad4 100644 + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_12UL_1UL_t", ""); +@@ -92,9 +115,9 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); ++ cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 +@@ -117,11 +140,22 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); -- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); +- cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("i")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -279,5 +470,30 @@ index 5307d0b77..1fef0199e 100644 + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r(M("mrpt::math"), "TMatrixTextFileFormat", pybind11::arithmetic(), "Selection of the number format in MatrixVectorBase::saveToTextFile()\n \n") + } +diff --git a/python/src/mrpt/math/CVectorDynamic.cpp b/python/src/mrpt/math/CVectorDynamic.cpp +index 780fbaa83..b9075ff96 100644 +--- a/python/src/mrpt/math/CVectorDynamic.cpp ++++ b/python/src/mrpt/math/CVectorDynamic.cpp +@@ -46,8 +46,8 @@ void bind_mrpt_math_CVectorDynamic(std::function< pybind11::module &(std::string + cl.def("resize", (void (mrpt::math::CVectorDynamic::*)(std::size_t, bool)) &mrpt::math::CVectorDynamic::resize, "C++: mrpt::math::CVectorDynamic::resize(std::size_t, bool) --> void", pybind11::arg("N"), pybind11::arg("zeroNewElements")); + cl.def("push_back", (void (mrpt::math::CVectorDynamic::*)(const double &)) &mrpt::math::CVectorDynamic::push_back, "C++: mrpt::math::CVectorDynamic::push_back(const double &) --> void", pybind11::arg("val")); + cl.def("segmentCopy", (class mrpt::math::CVectorDynamic (mrpt::math::CVectorDynamic::*)(int, int) const) &mrpt::math::CVectorDynamic::segmentCopy, "C++: mrpt::math::CVectorDynamic::segmentCopy(int, int) const --> class mrpt::math::CVectorDynamic", pybind11::arg("start"), pybind11::arg("LEN")); +- cl.def("__call__", (double & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (double & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (double & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__getitem__", (double & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("ith")); + cl.def("assign", (class mrpt::math::CVectorDynamic & (mrpt::math::CVectorDynamic::*)(const class mrpt::math::CVectorDynamic &)) &mrpt::math::CVectorDynamic::operator=, "C++: mrpt::math::CVectorDynamic::operator=(const class mrpt::math::CVectorDynamic &) --> class mrpt::math::CVectorDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::math::CVectorDynamic file:mrpt/math/CVectorDynamic.h line:32 +@@ -70,8 +70,8 @@ void bind_mrpt_math_CVectorDynamic(std::function< pybind11::module &(std::string + cl.def("resize", (void (mrpt::math::CVectorDynamic::*)(std::size_t, bool)) &mrpt::math::CVectorDynamic::resize, "C++: mrpt::math::CVectorDynamic::resize(std::size_t, bool) --> void", pybind11::arg("N"), pybind11::arg("zeroNewElements")); + cl.def("push_back", (void (mrpt::math::CVectorDynamic::*)(const float &)) &mrpt::math::CVectorDynamic::push_back, "C++: mrpt::math::CVectorDynamic::push_back(const float &) --> void", pybind11::arg("val")); + cl.def("segmentCopy", (class mrpt::math::CVectorDynamic (mrpt::math::CVectorDynamic::*)(int, int) const) &mrpt::math::CVectorDynamic::segmentCopy, "C++: mrpt::math::CVectorDynamic::segmentCopy(int, int) const --> class mrpt::math::CVectorDynamic", pybind11::arg("start"), pybind11::arg("LEN")); +- cl.def("__call__", (float & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("row"), pybind11::arg("col")); +- cl.def("__getitem__", (float & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::automatic, pybind11::arg("ith")); ++ cl.def("__call__", (float & (mrpt::math::CVectorDynamic::*)(size_t, size_t)) &mrpt::math::CVectorDynamic::operator(), "C++: mrpt::math::CVectorDynamic::operator()(size_t, size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); ++ cl.def("__getitem__", (float & (mrpt::math::CVectorDynamic::*)(size_t)) &mrpt::math::CVectorDynamic::operator[], "C++: mrpt::math::CVectorDynamic::operator[](size_t) --> float &", pybind11::return_value_policy::reference, pybind11::arg("ith")); + cl.def("assign", (class mrpt::math::CVectorDynamic & (mrpt::math::CVectorDynamic::*)(const class mrpt::math::CVectorDynamic &)) &mrpt::math::CVectorDynamic::operator=, "C++: mrpt::math::CVectorDynamic::operator=(const class mrpt::math::CVectorDynamic &) --> class mrpt::math::CVectorDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + } diff --git a/python/patch-011.diff b/python/patch-011.diff index 4a84290295..11876b923d 100644 --- a/python/patch-011.diff +++ b/python/patch-011.diff @@ -1,8 +1,8 @@ diff --git a/python/src/mrpt/maps/CColouredOctoMap.cpp b/python/src/mrpt/maps/CColouredOctoMap.cpp -index 69357914c..e50023c9f 100644 +index a4398860f..2919d286a 100644 --- a/python/src/mrpt/maps/CColouredOctoMap.cpp +++ b/python/src/mrpt/maps/CColouredOctoMap.cpp -@@ -1012,7 +1012,7 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi +@@ -1051,7 +1051,7 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi } return CPointsMap::nn_index_count(); } @@ -11,7 +11,7 @@ index 69357914c..e50023c9f 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -1025,7 +1025,7 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi +@@ -1064,7 +1064,7 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi } return CPointsMap::nn_single_search(a0, a1, a2, a3); } @@ -21,10 +21,10 @@ index 69357914c..e50023c9f 100644 pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { diff --git a/python/src/mrpt/maps/COccupancyGridMap2D.cpp b/python/src/mrpt/maps/COccupancyGridMap2D.cpp -index e6e7c2594..6a8f7845c 100644 +index 6b4c0940e..9ba6f5aec 100644 --- a/python/src/mrpt/maps/COccupancyGridMap2D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap2D.cpp -@@ -309,7 +309,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D : public mrpt::maps::COccupancyG +@@ -310,7 +310,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D : public mrpt::maps::COccupancyG } return COccupancyGridMap2D::nn_index_count(); } @@ -33,7 +33,7 @@ index e6e7c2594..6a8f7845c 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -322,7 +322,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D : public mrpt::maps::COccupancyG +@@ -323,7 +323,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D : public mrpt::maps::COccupancyG } return COccupancyGridMap2D::nn_single_search(a0, a1, a2, a3); } @@ -42,22 +42,22 @@ index e6e7c2594..6a8f7845c 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -637,8 +637,8 @@ void bind_mrpt_maps_COccupancyGridMap2D(std::function< pybind11::module &(std::s +@@ -664,8 +664,8 @@ void bind_mrpt_maps_COccupancyGridMap2D(std::function< pybind11::module &(std::s cl.def("asString", (std::string (mrpt::maps::COccupancyGridMap2D::*)() const) &mrpt::maps::COccupancyGridMap2D::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::COccupancyGridMap2D::asString() const --> std::string"); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::COccupancyGridMap2D::*)() const) &mrpt::maps::COccupancyGridMap2D::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::COccupancyGridMap2D::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::COccupancyGridMap2D::*)() const) &mrpt::maps::COccupancyGridMap2D::nn_index_count, "C++: mrpt::maps::COccupancyGridMap2D::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); cl.def("assign", (class mrpt::maps::COccupancyGridMap2D & (mrpt::maps::COccupancyGridMap2D::*)(const class mrpt::maps::COccupancyGridMap2D &)) &mrpt::maps::COccupancyGridMap2D::operator=, "C++: mrpt::maps::COccupancyGridMap2D::operator=(const class mrpt::maps::COccupancyGridMap2D &) --> class mrpt::maps::COccupancyGridMap2D &", pybind11::return_value_policy::automatic, pybind11::arg("")); { // mrpt::maps::COccupancyGridMap2D::TUpdateCellsInfoChangeOnly file:mrpt/maps/COccupancyGridMap2D.h line:215 diff --git a/python/src/mrpt/maps/COccupancyGridMap3D.cpp b/python/src/mrpt/maps/COccupancyGridMap3D.cpp -index 7a271082a..0da94c502 100644 +index b68479e5c..72772ebc2 100644 --- a/python/src/mrpt/maps/COccupancyGridMap3D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap3D.cpp -@@ -302,7 +302,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D : public mrpt::maps::COccupancyG +@@ -303,7 +303,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D : public mrpt::maps::COccupancyG } return COccupancyGridMap3D::nn_index_count(); } @@ -66,7 +66,7 @@ index 7a271082a..0da94c502 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -315,7 +315,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D : public mrpt::maps::COccupancyG +@@ -316,7 +316,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D : public mrpt::maps::COccupancyG } return COccupancyGridMap3D::nn_single_search(a0, a1, a2, a3); } @@ -75,22 +75,22 @@ index 7a271082a..0da94c502 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -541,8 +541,8 @@ void bind_mrpt_maps_COccupancyGridMap3D(std::function< pybind11::module &(std::s +@@ -568,8 +568,8 @@ void bind_mrpt_maps_COccupancyGridMap3D(std::function< pybind11::module &(std::s cl.def("asString", (std::string (mrpt::maps::COccupancyGridMap3D::*)() const) &mrpt::maps::COccupancyGridMap3D::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::COccupancyGridMap3D::asString() const --> std::string"); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::COccupancyGridMap3D::*)() const) &mrpt::maps::COccupancyGridMap3D::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::COccupancyGridMap3D::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::COccupancyGridMap3D::*)() const) &mrpt::maps::COccupancyGridMap3D::nn_index_count, "C++: mrpt::maps::COccupancyGridMap3D::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); cl.def("assign", (class mrpt::maps::COccupancyGridMap3D & (mrpt::maps::COccupancyGridMap3D::*)(const class mrpt::maps::COccupancyGridMap3D &)) &mrpt::maps::COccupancyGridMap3D::operator=, "C++: mrpt::maps::COccupancyGridMap3D::operator=(const class mrpt::maps::COccupancyGridMap3D &) --> class mrpt::maps::COccupancyGridMap3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); { // mrpt::maps::COccupancyGridMap3D::TInsertionOptions file:mrpt/maps/COccupancyGridMap3D.h line:221 diff --git a/python/src/mrpt/maps/COctoMap.cpp b/python/src/mrpt/maps/COctoMap.cpp -index 67a8016c3..97447db55 100644 +index b4178a0b5..0d0a72f70 100644 --- a/python/src/mrpt/maps/COctoMap.cpp +++ b/python/src/mrpt/maps/COctoMap.cpp -@@ -1017,7 +1017,7 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM +@@ -1056,7 +1056,7 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM } return CPointsMap::nn_index_count(); } @@ -99,7 +99,7 @@ index 67a8016c3..97447db55 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -1030,7 +1030,7 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM +@@ -1069,7 +1069,7 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM } return CPointsMap::nn_single_search(a0, a1, a2, a3); } @@ -109,10 +109,10 @@ index 67a8016c3..97447db55 100644 pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { diff --git a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp -index 53a2c31ed..283cffcd2 100644 +index 9e61fbe51..f5485e2cb 100644 --- a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp +++ b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp -@@ -581,7 +581,7 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { +@@ -620,7 +620,7 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { } return CPointsMap::nn_index_count(); } @@ -121,7 +121,7 @@ index 53a2c31ed..283cffcd2 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -594,7 +594,7 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { +@@ -633,7 +633,7 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { } return CPointsMap::nn_single_search(a0, a1, a2, a3); } @@ -131,25 +131,25 @@ index 53a2c31ed..283cffcd2 100644 pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { diff --git a/python/src/mrpt/maps/CPointsMap.cpp b/python/src/mrpt/maps/CPointsMap.cpp -index 1b940df9a..a29c05e9a 100644 +index b7cbd6fb6..35650c183 100644 --- a/python/src/mrpt/maps/CPointsMap.cpp +++ b/python/src/mrpt/maps/CPointsMap.cpp -@@ -255,8 +255,8 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con - cl.def("asString", (std::string (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::CPointsMap::asString() const --> std::string"); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool"); +@@ -257,8 +257,8 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_prepare_for_3d_queries, "C++: mrpt::maps::CPointsMap::nn_prepare_for_3d_queries() const --> void"); + cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, "C++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_index_count, "C++: mrpt::maps::CPointsMap::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); { // mrpt::maps::CPointsMap::TInsertionOptions file:mrpt/maps/CPointsMap.h line:228 auto & enclosing_class = cl; diff --git a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp -index 8b5a2b818..02ac97b7b 100644 +index bed19b4fc..09244fb04 100644 --- a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp +++ b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp -@@ -850,7 +850,7 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi +@@ -889,7 +889,7 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi } return CPointsMap::nn_index_count(); } @@ -158,7 +158,7 @@ index 8b5a2b818..02ac97b7b 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -863,7 +863,7 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi +@@ -902,7 +902,7 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi } return CPointsMap::nn_single_search(a0, a1, a2, a3); } @@ -167,11 +167,20 @@ index 8b5a2b818..02ac97b7b 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { +@@ -1130,7 +1130,7 @@ void bind_mrpt_maps_CReflectivityGridMap2D(std::function< pybind11::module &(std + cl.def("setSize", (void (mrpt::maps::CWeightedPointsMap::*)(size_t)) &mrpt::maps::CWeightedPointsMap::setSize, "C++: mrpt::maps::CWeightedPointsMap::setSize(size_t) --> void", pybind11::arg("newLength")); + cl.def("insertPointFast", [](mrpt::maps::CWeightedPointsMap &o, float const & a0, float const & a1) -> void { return o.insertPointFast(a0, a1); }, "", pybind11::arg("x"), pybind11::arg("y")); + cl.def("insertPointFast", (void (mrpt::maps::CWeightedPointsMap::*)(float, float, float)) &mrpt::maps::CWeightedPointsMap::insertPointFast, "The virtual method for *without* calling\n mark_as_modified() \n\nC++: mrpt::maps::CWeightedPointsMap::insertPointFast(float, float, float) --> void", pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z")); +- cl.def("setPointWeight", (void (mrpt::maps::CWeightedPointsMap::*)(size_t, unsigned long)) &mrpt::maps::CWeightedPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::setPointWeight(size_t, unsigned long) --> void", pybind11::arg("index"), pybind11::arg("w")); ++ cl.def("setPointWeight", (void (mrpt::maps::CWeightedPointsMap::*)(size_t, uint64_t)) &mrpt::maps::CWeightedPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::setPointWeight(size_t, uint64_t) --> void", pybind11::arg("index"), pybind11::arg("w")); + cl.def("getPointWeight", (unsigned int (mrpt::maps::CWeightedPointsMap::*)(size_t) const) &mrpt::maps::CWeightedPointsMap::getPointWeight, "Gets the point weight, which is ignored in all classes (defaults to 1)\n but in those which actually store that field (Note: No checks are done\n for out-of-bounds index). \n\n setPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::getPointWeight(size_t) const --> unsigned int", pybind11::arg("index")); + + { // mrpt::maps::CWeightedPointsMap::TMapDefinitionBase file: line:80 diff --git a/python/src/mrpt/maps/CVoxelMap.cpp b/python/src/mrpt/maps/CVoxelMap.cpp -index 1ba095dce..f042679cc 100644 +index d36a783ff..6955a6caf 100644 --- a/python/src/mrpt/maps/CVoxelMap.cpp +++ b/python/src/mrpt/maps/CVoxelMap.cpp -@@ -238,7 +238,7 @@ struct PyCallBack_mrpt_maps_CVoxelMap : public mrpt::maps::CVoxelMap { +@@ -264,7 +264,7 @@ struct PyCallBack_mrpt_maps_CVoxelMap : public mrpt::maps::CVoxelMap { } return CVoxelMapOccupancyBase::nn_index_count(); } @@ -180,7 +189,7 @@ index 1ba095dce..f042679cc 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -251,7 +251,7 @@ struct PyCallBack_mrpt_maps_CVoxelMap : public mrpt::maps::CVoxelMap { +@@ -277,7 +277,7 @@ struct PyCallBack_mrpt_maps_CVoxelMap : public mrpt::maps::CVoxelMap { } return CVoxelMapOccupancyBase::nn_single_search(a0, a1, a2, a3); } @@ -189,7 +198,7 @@ index 1ba095dce..f042679cc 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -588,7 +588,7 @@ struct PyCallBack_mrpt_maps_CVoxelMapRGB : public mrpt::maps::CVoxelMapRGB { +@@ -640,7 +640,7 @@ struct PyCallBack_mrpt_maps_CVoxelMapRGB : public mrpt::maps::CVoxelMapRGB { } return CVoxelMapOccupancyBase::nn_index_count(); } @@ -198,7 +207,7 @@ index 1ba095dce..f042679cc 100644 pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { -@@ -601,7 +601,7 @@ struct PyCallBack_mrpt_maps_CVoxelMapRGB : public mrpt::maps::CVoxelMapRGB { +@@ -653,7 +653,7 @@ struct PyCallBack_mrpt_maps_CVoxelMapRGB : public mrpt::maps::CVoxelMapRGB { } return CVoxelMapOccupancyBase::nn_single_search(a0, a1, a2, a3); } @@ -208,69 +217,69 @@ index 1ba095dce..f042679cc 100644 pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_single_search"); if (overload) { diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp -index 56901034a..dade459d9 100644 +index fdb5816a8..7fbf0e079 100644 --- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp +++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp -@@ -69,8 +69,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s - cl.def_static("p2l", (signed char (*)(const float)) &mrpt::maps::CVoxelMapOccupancyBase::p2l, "C++: mrpt::maps::CVoxelMapOccupancyBase::p2l(const float) --> signed char", pybind11::arg("p")); +@@ -71,8 +71,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_index_count, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); cl.def("assign", (class mrpt::maps::CVoxelMapOccupancyBase & (mrpt::maps::CVoxelMapOccupancyBase::*)(const class mrpt::maps::CVoxelMapOccupancyBase &)) &mrpt::maps::CVoxelMapOccupancyBase::operator=, "C++: mrpt::maps::CVoxelMapOccupancyBase::operator=(const class mrpt::maps::CVoxelMapOccupancyBase &) --> class mrpt::maps::CVoxelMapOccupancyBase &", pybind11::return_value_policy::automatic, pybind11::arg("")); cl.def("assign", (class mrpt::maps::CVoxelMapBase & (mrpt::maps::CVoxelMapBase::*)(const class mrpt::maps::CVoxelMapBase &)) &mrpt::maps::CVoxelMapBase::operator=, "C++: mrpt::maps::CVoxelMapBase::operator=(const class mrpt::maps::CVoxelMapBase &) --> class mrpt::maps::CVoxelMapBase &", pybind11::return_value_policy::automatic, pybind11::arg("o")); cl.def("asString", (std::string (mrpt::maps::CVoxelMapBase::*)() const) &mrpt::maps::CVoxelMapBase::asString, "C++: mrpt::maps::CVoxelMapBase::asString() const --> std::string"); -@@ -103,8 +103,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s - cl.def("assign", (class mrpt::maps::CMetricMap & (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CMetricMap &)) &mrpt::maps::CMetricMap::operator=, "C++: mrpt::maps::CMetricMap::operator=(const class mrpt::maps::CMetricMap &) --> class mrpt::maps::CMetricMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); +@@ -107,8 +107,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); cl.def("assign", (class mrpt::maps::NearestNeighborsCapable & (mrpt::maps::NearestNeighborsCapable::*)(const class mrpt::maps::NearestNeighborsCapable &)) &mrpt::maps::NearestNeighborsCapable::operator=, "C++: mrpt::maps::NearestNeighborsCapable::operator=(const class mrpt::maps::NearestNeighborsCapable &) --> class mrpt::maps::NearestNeighborsCapable &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp -index 48fc11853..e5b22eac1 100644 +index 08e90fd3f..d24835a7d 100644 --- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp +++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp -@@ -69,8 +69,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s - cl.def_static("p2l", (signed char (*)(const float)) &mrpt::maps::CVoxelMapOccupancyBase::p2l, "C++: mrpt::maps::CVoxelMapOccupancyBase::p2l(const float) --> signed char", pybind11::arg("p")); +@@ -71,8 +71,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_index_count, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); cl.def("assign", (class mrpt::maps::CVoxelMapOccupancyBase & (mrpt::maps::CVoxelMapOccupancyBase::*)(const class mrpt::maps::CVoxelMapOccupancyBase &)) &mrpt::maps::CVoxelMapOccupancyBase::operator=, "C++: mrpt::maps::CVoxelMapOccupancyBase::operator=(const class mrpt::maps::CVoxelMapOccupancyBase &) --> class mrpt::maps::CVoxelMapOccupancyBase &", pybind11::return_value_policy::automatic, pybind11::arg("")); cl.def("assign", (class mrpt::maps::CVoxelMapBase & (mrpt::maps::CVoxelMapBase::*)(const class mrpt::maps::CVoxelMapBase &)) &mrpt::maps::CVoxelMapBase::operator=, "C++: mrpt::maps::CVoxelMapBase::operator=(const class mrpt::maps::CVoxelMapBase &) --> class mrpt::maps::CVoxelMapBase &", pybind11::return_value_policy::automatic, pybind11::arg("o")); cl.def("asString", (std::string (mrpt::maps::CVoxelMapBase::*)() const) &mrpt::maps::CVoxelMapBase::asString, "C++: mrpt::maps::CVoxelMapBase::asString() const --> std::string"); -@@ -103,8 +103,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s - cl.def("assign", (class mrpt::maps::CMetricMap & (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CMetricMap &)) &mrpt::maps::CMetricMap::operator=, "C++: mrpt::maps::CMetricMap::operator=(const class mrpt::maps::CMetricMap &) --> class mrpt::maps::CMetricMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); +@@ -107,8 +107,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); cl.def("assign", (class mrpt::maps::NearestNeighborsCapable & (mrpt::maps::NearestNeighborsCapable::*)(const class mrpt::maps::NearestNeighborsCapable &)) &mrpt::maps::NearestNeighborsCapable::operator=, "C++: mrpt::maps::NearestNeighborsCapable::operator=(const class mrpt::maps::NearestNeighborsCapable &) --> class mrpt::maps::NearestNeighborsCapable &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/src/mrpt/maps/NearestNeighborsCapable.cpp b/python/src/mrpt/maps/NearestNeighborsCapable.cpp -index a22f929c1..b4d515565 100644 +index 893de5dfb..ecd47c380 100644 --- a/python/src/mrpt/maps/NearestNeighborsCapable.cpp +++ b/python/src/mrpt/maps/NearestNeighborsCapable.cpp -@@ -28,8 +28,8 @@ void bind_mrpt_maps_NearestNeighborsCapable(std::function< pybind11::module &(st - pybind11::class_> cl(M("mrpt::maps"), "NearestNeighborsCapable", "Virtual interface for maps having the capability of searching the closest\n neighbor(s) of a given query 2D or 3D point.\n\n Note this is more generic than mrpt::math::KDTreeCapable since it does not\n assume the use of KD-trees, and it is also non templatized, so users can use\n dynamic casting to interact with maps in a generic way.\n\n \n New in MRPT 2.11.3\n \n\n\n "); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); +@@ -30,8 +30,8 @@ void bind_mrpt_maps_NearestNeighborsCapable(std::function< pybind11::module &(st + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); - cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); - cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); ++ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); cl.def("assign", (class mrpt::maps::NearestNeighborsCapable & (mrpt::maps::NearestNeighborsCapable::*)(const class mrpt::maps::NearestNeighborsCapable &)) &mrpt::maps::NearestNeighborsCapable::operator=, "C++: mrpt::maps::NearestNeighborsCapable::operator=(const class mrpt::maps::NearestNeighborsCapable &) --> class mrpt::maps::NearestNeighborsCapable &", pybind11::return_value_policy::automatic, pybind11::arg("")); } } diff --git a/python/patch-012.diff b/python/patch-012.diff index 072448cbf7..e780aa47c4 100644 --- a/python/patch-012.diff +++ b/python/patch-012.diff @@ -1,112 +1,13 @@ -diff --git a/python/src/mrpt/maps/COccupancyGridMap2D.cpp b/python/src/mrpt/maps/COccupancyGridMap2D.cpp -index 6a8f7845c..59755fef0 100644 ---- a/python/src/mrpt/maps/COccupancyGridMap2D.cpp -+++ b/python/src/mrpt/maps/COccupancyGridMap2D.cpp -@@ -637,8 +637,8 @@ void bind_mrpt_maps_COccupancyGridMap2D(std::function< pybind11::module &(std::s - cl.def("asString", (std::string (mrpt::maps::COccupancyGridMap2D::*)() const) &mrpt::maps::COccupancyGridMap2D::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::COccupancyGridMap2D::asString() const --> std::string"); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::COccupancyGridMap2D::*)() const) &mrpt::maps::COccupancyGridMap2D::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::COccupancyGridMap2D::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::COccupancyGridMap2D::*)() const) &mrpt::maps::COccupancyGridMap2D::nn_index_count, "C++: mrpt::maps::COccupancyGridMap2D::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap2D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap2D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap2D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("assign", (class mrpt::maps::COccupancyGridMap2D & (mrpt::maps::COccupancyGridMap2D::*)(const class mrpt::maps::COccupancyGridMap2D &)) &mrpt::maps::COccupancyGridMap2D::operator=, "C++: mrpt::maps::COccupancyGridMap2D::operator=(const class mrpt::maps::COccupancyGridMap2D &) --> class mrpt::maps::COccupancyGridMap2D &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::maps::COccupancyGridMap2D::TUpdateCellsInfoChangeOnly file:mrpt/maps/COccupancyGridMap2D.h line:215 -diff --git a/python/src/mrpt/maps/COccupancyGridMap3D.cpp b/python/src/mrpt/maps/COccupancyGridMap3D.cpp -index 0da94c502..166f1cc88 100644 ---- a/python/src/mrpt/maps/COccupancyGridMap3D.cpp -+++ b/python/src/mrpt/maps/COccupancyGridMap3D.cpp -@@ -541,8 +541,8 @@ void bind_mrpt_maps_COccupancyGridMap3D(std::function< pybind11::module &(std::s - cl.def("asString", (std::string (mrpt::maps::COccupancyGridMap3D::*)() const) &mrpt::maps::COccupancyGridMap3D::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::COccupancyGridMap3D::asString() const --> std::string"); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::COccupancyGridMap3D::*)() const) &mrpt::maps::COccupancyGridMap3D::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::COccupancyGridMap3D::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::COccupancyGridMap3D::*)() const) &mrpt::maps::COccupancyGridMap3D::nn_index_count, "C++: mrpt::maps::COccupancyGridMap3D::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::COccupancyGridMap3D::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::COccupancyGridMap3D::nn_single_search, "C++: mrpt::maps::COccupancyGridMap3D::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("assign", (class mrpt::maps::COccupancyGridMap3D & (mrpt::maps::COccupancyGridMap3D::*)(const class mrpt::maps::COccupancyGridMap3D &)) &mrpt::maps::COccupancyGridMap3D::operator=, "C++: mrpt::maps::COccupancyGridMap3D::operator=(const class mrpt::maps::COccupancyGridMap3D &) --> class mrpt::maps::COccupancyGridMap3D &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - { // mrpt::maps::COccupancyGridMap3D::TInsertionOptions file:mrpt/maps/COccupancyGridMap3D.h line:221 -diff --git a/python/src/mrpt/maps/CPointsMap.cpp b/python/src/mrpt/maps/CPointsMap.cpp -index a29c05e9a..3d2ece918 100644 ---- a/python/src/mrpt/maps/CPointsMap.cpp -+++ b/python/src/mrpt/maps/CPointsMap.cpp -@@ -255,8 +255,8 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con - cl.def("asString", (std::string (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::CPointsMap::asString() const --> std::string"); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_index_count, "C++: mrpt::maps::CPointsMap::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - - { // mrpt::maps::CPointsMap::TInsertionOptions file:mrpt/maps/CPointsMap.h line:228 - auto & enclosing_class = cl; -diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp -index dade459d9..67a288932 100644 ---- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp -+++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp -@@ -69,8 +69,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s - cl.def_static("p2l", (signed char (*)(const float)) &mrpt::maps::CVoxelMapOccupancyBase::p2l, "C++: mrpt::maps::CVoxelMapOccupancyBase::p2l(const float) --> signed char", pybind11::arg("p")); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_index_count, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("assign", (class mrpt::maps::CVoxelMapOccupancyBase & (mrpt::maps::CVoxelMapOccupancyBase::*)(const class mrpt::maps::CVoxelMapOccupancyBase &)) &mrpt::maps::CVoxelMapOccupancyBase::operator=, "C++: mrpt::maps::CVoxelMapOccupancyBase::operator=(const class mrpt::maps::CVoxelMapOccupancyBase &) --> class mrpt::maps::CVoxelMapOccupancyBase &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("assign", (class mrpt::maps::CVoxelMapBase & (mrpt::maps::CVoxelMapBase::*)(const class mrpt::maps::CVoxelMapBase &)) &mrpt::maps::CVoxelMapBase::operator=, "C++: mrpt::maps::CVoxelMapBase::operator=(const class mrpt::maps::CVoxelMapBase &) --> class mrpt::maps::CVoxelMapBase &", pybind11::return_value_policy::automatic, pybind11::arg("o")); - cl.def("asString", (std::string (mrpt::maps::CVoxelMapBase::*)() const) &mrpt::maps::CVoxelMapBase::asString, "C++: mrpt::maps::CVoxelMapBase::asString() const --> std::string"); -@@ -103,8 +103,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s - cl.def("assign", (class mrpt::maps::CMetricMap & (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CMetricMap &)) &mrpt::maps::CMetricMap::operator=, "C++: mrpt::maps::CMetricMap::operator=(const class mrpt::maps::CMetricMap &) --> class mrpt::maps::CMetricMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); - cl.def("assign", (class mrpt::maps::NearestNeighborsCapable & (mrpt::maps::NearestNeighborsCapable::*)(const class mrpt::maps::NearestNeighborsCapable &)) &mrpt::maps::NearestNeighborsCapable::operator=, "C++: mrpt::maps::NearestNeighborsCapable::operator=(const class mrpt::maps::NearestNeighborsCapable &) --> class mrpt::maps::NearestNeighborsCapable &", pybind11::return_value_policy::automatic, pybind11::arg("")); +diff --git a/python/src/mrpt/math/CMatrixDynamic_1.cpp b/python/src/mrpt/math/CMatrixDynamic_1.cpp +index be42731ed..4d90b28d6 100644 +--- a/python/src/mrpt/math/CMatrixDynamic_1.cpp ++++ b/python/src/mrpt/math/CMatrixDynamic_1.cpp +@@ -50,8 +50,6 @@ void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::stri + cl.def("data", (struct mrpt::math::TPoint3D_ * (mrpt::math::CMatrixDynamic>::*)()) &mrpt::math::CMatrixDynamic>::data, "C++: mrpt::math::CMatrixDynamic>::data() --> struct mrpt::math::TPoint3D_ *", pybind11::return_value_policy::automatic); + cl.def("__call__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::operator(), "C++: mrpt::math::CMatrixDynamic>::operator()(size_t, size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__getitem__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t)) &mrpt::math::CMatrixDynamic>::operator[], "C++: mrpt::math::CMatrixDynamic>::operator[](size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::reference, pybind11::arg("ith")); +- cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic>::*)() const) &mrpt::math::CMatrixDynamic>::cast_float, "C++: mrpt::math::CMatrixDynamic>::cast_float() const --> class mrpt::math::CMatrixDynamic"); +- cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic>::*)() const) &mrpt::math::CMatrixDynamic>::cast_double, "C++: mrpt::math::CMatrixDynamic>::cast_double() const --> class mrpt::math::CMatrixDynamic"); } - } -diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp -index e5b22eac1..49b74e052 100644 ---- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp -+++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp -@@ -69,8 +69,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s - cl.def_static("p2l", (signed char (*)(const float)) &mrpt::maps::CVoxelMapOccupancyBase::p2l, "C++: mrpt::maps::CVoxelMapOccupancyBase::p2l(const float) --> signed char", pybind11::arg("p")); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_index_count, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); - cl.def("assign", (class mrpt::maps::CVoxelMapOccupancyBase & (mrpt::maps::CVoxelMapOccupancyBase::*)(const class mrpt::maps::CVoxelMapOccupancyBase &)) &mrpt::maps::CVoxelMapOccupancyBase::operator=, "C++: mrpt::maps::CVoxelMapOccupancyBase::operator=(const class mrpt::maps::CVoxelMapOccupancyBase &) --> class mrpt::maps::CVoxelMapOccupancyBase &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("assign", (class mrpt::maps::CVoxelMapBase & (mrpt::maps::CVoxelMapBase::*)(const class mrpt::maps::CVoxelMapBase &)) &mrpt::maps::CVoxelMapBase::operator=, "C++: mrpt::maps::CVoxelMapBase::operator=(const class mrpt::maps::CVoxelMapBase &) --> class mrpt::maps::CVoxelMapBase &", pybind11::return_value_policy::automatic, pybind11::arg("o")); - cl.def("asString", (std::string (mrpt::maps::CVoxelMapBase::*)() const) &mrpt::maps::CVoxelMapBase::asString, "C++: mrpt::maps::CVoxelMapBase::asString() const --> std::string"); -@@ -103,8 +103,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s - cl.def("assign", (class mrpt::maps::CMetricMap & (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CMetricMap &)) &mrpt::maps::CMetricMap::operator=, "C++: mrpt::maps::CMetricMap::operator=(const class mrpt::maps::CMetricMap &) --> class mrpt::maps::CMetricMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); - cl.def("assign", (class mrpt::maps::NearestNeighborsCapable & (mrpt::maps::NearestNeighborsCapable::*)(const class mrpt::maps::NearestNeighborsCapable &)) &mrpt::maps::NearestNeighborsCapable::operator=, "C++: mrpt::maps::NearestNeighborsCapable::operator=(const class mrpt::maps::NearestNeighborsCapable &) --> class mrpt::maps::NearestNeighborsCapable &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - } -diff --git a/python/src/mrpt/maps/NearestNeighborsCapable.cpp b/python/src/mrpt/maps/NearestNeighborsCapable.cpp -index b4d515565..ab164dbca 100644 ---- a/python/src/mrpt/maps/NearestNeighborsCapable.cpp -+++ b/python/src/mrpt/maps/NearestNeighborsCapable.cpp -@@ -28,8 +28,8 @@ void bind_mrpt_maps_NearestNeighborsCapable(std::function< pybind11::module &(st - pybind11::class_> cl(M("mrpt::maps"), "NearestNeighborsCapable", "Virtual interface for maps having the capability of searching the closest\n neighbor(s) of a given query 2D or 3D point.\n\n Note this is more generic than mrpt::math::KDTreeCapable since it does not\n assume the use of KD-trees, and it is also non templatized, so users can use\n dynamic casting to interact with maps in a generic way.\n\n \n New in MRPT 2.11.3\n \n\n\n "); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); - cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); -- cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -- cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, unsigned long &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); -+ cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); - cl.def("assign", (class mrpt::maps::NearestNeighborsCapable & (mrpt::maps::NearestNeighborsCapable::*)(const class mrpt::maps::NearestNeighborsCapable &)) &mrpt::maps::NearestNeighborsCapable::operator=, "C++: mrpt::maps::NearestNeighborsCapable::operator=(const class mrpt::maps::NearestNeighborsCapable &) --> class mrpt::maps::NearestNeighborsCapable &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_2UL_2UL_t", ""); diff --git a/python/python.conf b/python/python.conf index 3050455b82..7d7545f687 100644 --- a/python/python.conf +++ b/python/python.conf @@ -213,6 +213,7 @@ -class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> +-class mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >> -class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> -class mrpt::math::MatrixBase> @@ -232,6 +233,7 @@ -class mrpt::math::MatrixVectorBase> -class mrpt::math::MatrixVectorBase> -class mrpt::math::MatrixVectorBase> +-class mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> -class mrpt::math::MatrixVectorBase> -class mrpt::math::MatrixVectorBase> -class mrpt::math::MatrixVectorBase> diff --git a/python/src/mrpt/config/CConfigFileBase.cpp b/python/src/mrpt/config/CConfigFileBase.cpp index a8b528e2e7..acab2533da 100644 --- a/python/src/mrpt/config/CConfigFileBase.cpp +++ b/python/src/mrpt/config/CConfigFileBase.cpp @@ -180,7 +180,9 @@ void bind_mrpt_config_CConfigFileBase(std::function< pybind11::module &(std::str cl.def("read_enum", [](mrpt::config::CConfigFileBase const &o, const std::string & a0, const std::string & a1, const enum mrpt::system::VerbosityLevel & a2) -> mrpt::system::VerbosityLevel { return o.read_enum(a0, a1, a2); }, "", pybind11::arg("section"), pybind11::arg("name"), pybind11::arg("defaultValue")); cl.def("read_enum", (enum mrpt::system::VerbosityLevel (mrpt::config::CConfigFileBase::*)(const std::string &, const std::string &, const enum mrpt::system::VerbosityLevel &, bool) const) &mrpt::config::CConfigFileBase::read_enum, "C++: mrpt::config::CConfigFileBase::read_enum(const std::string &, const std::string &, const enum mrpt::system::VerbosityLevel &, bool) const --> enum mrpt::system::VerbosityLevel", pybind11::arg("section"), pybind11::arg("name"), pybind11::arg("defaultValue"), pybind11::arg("failIfNotFound")); cl.def("getAllSections", (void (mrpt::config::CConfigFileBase::*)(class std::vector &) const) &mrpt::config::CConfigFileBase::getAllSections, "Returns a list with all the section names. \n\nC++: mrpt::config::CConfigFileBase::getAllSections(class std::vector &) const --> void", pybind11::arg("sections")); + cl.def("sections", (class std::vector (mrpt::config::CConfigFileBase::*)() const) &mrpt::config::CConfigFileBase::sections, "Returns, by value, a list with all the section names. \n\nC++: mrpt::config::CConfigFileBase::sections() const --> class std::vector"); cl.def("getAllKeys", (void (mrpt::config::CConfigFileBase::*)(const std::string &, class std::vector &) const) &mrpt::config::CConfigFileBase::getAllKeys, "Returs a list with all the keys into a section \n\nC++: mrpt::config::CConfigFileBase::getAllKeys(const std::string &, class std::vector &) const --> void", pybind11::arg("section"), pybind11::arg("keys")); + cl.def("keys", (class std::vector (mrpt::config::CConfigFileBase::*)(const std::string &) const) &mrpt::config::CConfigFileBase::keys, "Returs, by value, a list with all the keys into a section \n\nC++: mrpt::config::CConfigFileBase::keys(const std::string &) const --> class std::vector", pybind11::arg("section")); cl.def("sectionExists", (bool (mrpt::config::CConfigFileBase::*)(const std::string &) const) &mrpt::config::CConfigFileBase::sectionExists, "Checks if a given section exists (name is case insensitive)\n \n\n keyExists() \n\nC++: mrpt::config::CConfigFileBase::sectionExists(const std::string &) const --> bool", pybind11::arg("section_name")); cl.def("keyExists", (bool (mrpt::config::CConfigFileBase::*)(const std::string &, const std::string &) const) &mrpt::config::CConfigFileBase::keyExists, "Checks if a given key exists inside a section (case insensitive)\n \n\n sectionExists() \n\nC++: mrpt::config::CConfigFileBase::keyExists(const std::string &, const std::string &) const --> bool", pybind11::arg("section"), pybind11::arg("key")); cl.def("setContentFromYAML", (void (mrpt::config::CConfigFileBase::*)(const std::string &)) &mrpt::config::CConfigFileBase::setContentFromYAML, "Changes the contents of the virtual \"config file\" from a text block\n containing a YAML configuration text. Refer to unit test\n yaml2config_unittest.cpp for examples of use.\n \n\n getContentAsYAML()\n\nC++: mrpt::config::CConfigFileBase::setContentFromYAML(const std::string &) --> void", pybind11::arg("yaml_block")); diff --git a/python/src/mrpt/maps/CColouredOctoMap.cpp b/python/src/mrpt/maps/CColouredOctoMap.cpp index e50023c9f7..267f0864df 100644 --- a/python/src/mrpt/maps/CColouredOctoMap.cpp +++ b/python/src/mrpt/maps/CColouredOctoMap.cpp @@ -579,7 +579,7 @@ struct PyCallBack_mrpt_maps_CColouredOctoMap_TMapDefinition : public mrpt::maps: } }; -// mrpt::maps::CColouredPointsMap file:mrpt/maps/CColouredPointsMap.h line:29 +// mrpt::maps::CColouredPointsMap file:mrpt/maps/CColouredPointsMap.h line:30 struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPointsMap { using mrpt::maps::CColouredPointsMap::CColouredPointsMap; @@ -830,6 +830,19 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi } return CColouredPointsMap::PLY_import_set_vertex_count(a0); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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 CColouredPointsMap::PLY_import_set_vertex_timestamp(a0, a1); + } void PLY_export_get_vertex(size_t a0, struct mrpt::math::TPoint3D_ & a1, bool & a2, struct mrpt::img::TColorf & a3) const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_export_get_vertex"); @@ -986,6 +999,32 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi } return CPointsMap::asString(); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 CPointsMap::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 CPointsMap::nn_prepare_for_3d_queries(); + } bool nn_has_indices_or_ids() const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_has_indices_or_ids"); @@ -1105,7 +1144,7 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap : public mrpt::maps::CColouredPoi } }; -// mrpt::maps::CColouredPointsMap::TColourOptions file:mrpt/maps/CColouredPointsMap.h line:207 +// mrpt::maps::CColouredPointsMap::TColourOptions file:mrpt/maps/CColouredPointsMap.h line:208 struct PyCallBack_mrpt_maps_CColouredPointsMap_TColourOptions : public mrpt::maps::CColouredPointsMap::TColourOptions { using mrpt::maps::CColouredPointsMap::TColourOptions::TColourOptions; @@ -1257,7 +1296,7 @@ void bind_mrpt_maps_CColouredOctoMap(std::function< pybind11::module &(std::stri } } - { // mrpt::maps::CColouredPointsMap file:mrpt/maps/CColouredPointsMap.h line:29 + { // mrpt::maps::CColouredPointsMap file:mrpt/maps/CColouredPointsMap.h line:30 pybind11::class_, PyCallBack_mrpt_maps_CColouredPointsMap, mrpt::maps::CPointsMap> cl(M("mrpt::maps"), "CColouredPointsMap", "A map of 2D/3D points with individual colours (RGB).\n For different color schemes, see CColouredPointsMap::colorScheme\n Colors are defined in the range [0,1].\n \n\n mrpt::maps::CPointsMap, mrpt::maps::CMetricMap,\n mrpt::serialization::CSerializable\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::maps::CColouredPointsMap(); }, [](){ return new PyCallBack_mrpt_maps_CColouredPointsMap(); } ) ); cl.def( pybind11::init(), pybind11::arg("o") ); @@ -1298,7 +1337,7 @@ void bind_mrpt_maps_CColouredOctoMap(std::function< pybind11::module &(std::stri cl.def("resetPointsMinDist", [](mrpt::maps::CColouredPointsMap &o) -> void { return o.resetPointsMinDist(); }, ""); cl.def("resetPointsMinDist", (void (mrpt::maps::CColouredPointsMap::*)(float)) &mrpt::maps::CColouredPointsMap::resetPointsMinDist, "Reset the minimum-observed-distance buffer for all the points to a\n predefined value \n\nC++: mrpt::maps::CColouredPointsMap::resetPointsMinDist(float) --> void", pybind11::arg("defValue")); - { // mrpt::maps::CColouredPointsMap::TColourOptions file:mrpt/maps/CColouredPointsMap.h line:207 + { // mrpt::maps::CColouredPointsMap::TColourOptions file:mrpt/maps/CColouredPointsMap.h line:208 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CColouredPointsMap_TColourOptions, mrpt::config::CLoadableOptions> cl(enclosing_class, "TColourOptions", "The definition of parameters for generating colors from laser scans "); cl.def( pybind11::init( [](){ return new mrpt::maps::CColouredPointsMap::TColourOptions(); }, [](){ return new PyCallBack_mrpt_maps_CColouredPointsMap_TColourOptions(); } ) ); diff --git a/python/src/mrpt/maps/CColouredPointsMap.cpp b/python/src/mrpt/maps/CColouredPointsMap.cpp index 71ca221797..994b51a6ef 100644 --- a/python/src/mrpt/maps/CColouredPointsMap.cpp +++ b/python/src/mrpt/maps/CColouredPointsMap.cpp @@ -32,7 +32,7 @@ void bind_mrpt_maps_CColouredPointsMap(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CColouredPointsMap.h line:366 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CColouredPointsMap.h line:374 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CColouredPointsMap_t", "Specialization\n mrpt::opengl::PointCloudAdapter \n\n\n mrpt_adapters_grp "); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/COccupancyGridMap2D.cpp b/python/src/mrpt/maps/COccupancyGridMap2D.cpp index 59755fef0f..9ba6f5aec2 100644 --- a/python/src/mrpt/maps/COccupancyGridMap2D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap2D.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #include #include #include @@ -387,6 +388,32 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D : public mrpt::maps::COccupancyG } return CMetricMap::squareDistanceToClosestCorrespondence(a0, a1); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 NearestNeighborsCapable::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 NearestNeighborsCapable::nn_prepare_for_3d_queries(); + } }; // mrpt::maps::COccupancyGridMap2D::TInsertionOptions file:mrpt/maps/COccupancyGridMap2D.h line:475 diff --git a/python/src/mrpt/maps/COccupancyGridMap3D.cpp b/python/src/mrpt/maps/COccupancyGridMap3D.cpp index 166f1cc882..72772ebc28 100644 --- a/python/src/mrpt/maps/COccupancyGridMap3D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap3D.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include #include @@ -380,6 +381,32 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D : public mrpt::maps::COccupancyG } return CMetricMap::squareDistanceToClosestCorrespondence(a0, a1); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 NearestNeighborsCapable::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 NearestNeighborsCapable::nn_prepare_for_3d_queries(); + } }; // mrpt::maps::COccupancyGridMap3D::TInsertionOptions file:mrpt/maps/COccupancyGridMap3D.h line:221 diff --git a/python/src/mrpt/maps/COctoMap.cpp b/python/src/mrpt/maps/COctoMap.cpp index 97447db55f..0d0a72f709 100644 --- a/python/src/mrpt/maps/COctoMap.cpp +++ b/python/src/mrpt/maps/COctoMap.cpp @@ -783,6 +783,19 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM } return CSimplePointsMap::PLY_import_set_vertex_count(a0); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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 CSimplePointsMap::PLY_import_set_vertex_timestamp(a0, a1); + } float squareDistanceToClosestCorrespondence(float a0, float a1) const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "squareDistanceToClosestCorrespondence"); @@ -991,6 +1004,32 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM } return CPointsMap::asString(); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 CPointsMap::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 CPointsMap::nn_prepare_for_3d_queries(); + } bool nn_has_indices_or_ids() const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_has_indices_or_ids"); diff --git a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp index 283cffcd2e..fac1e6cf8f 100644 --- a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp +++ b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp @@ -148,7 +148,7 @@ struct PyCallBack_mrpt_maps_CPointCloudFilterByDistance_TOptions : public mrpt:: } }; -// mrpt::maps::CPointsMapXYZI file:mrpt/maps/CPointsMapXYZI.h line:26 +// mrpt::maps::CPointsMapXYZI file:mrpt/maps/CPointsMapXYZI.h line:24 struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { using mrpt::maps::CPointsMapXYZI::CPointsMapXYZI; @@ -399,6 +399,19 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { } return CPointsMapXYZI::PLY_import_set_vertex_count(a0); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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 CPointsMapXYZI::PLY_import_set_vertex_timestamp(a0, a1); + } void PLY_export_get_vertex(size_t a0, struct mrpt::math::TPoint3D_ & a1, bool & a2, struct mrpt::img::TColorf & a3) const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_export_get_vertex"); @@ -555,6 +568,32 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { } return CPointsMap::asString(); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 CPointsMap::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 CPointsMap::nn_prepare_for_3d_queries(); + } bool nn_has_indices_or_ids() const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_has_indices_or_ids"); @@ -748,7 +787,7 @@ void bind_mrpt_maps_CPointCloudFilterByDistance(std::function< pybind11::module } } - { // mrpt::maps::CPointsMapXYZI file:mrpt/maps/CPointsMapXYZI.h line:26 + { // mrpt::maps::CPointsMapXYZI file:mrpt/maps/CPointsMapXYZI.h line:24 pybind11::class_, PyCallBack_mrpt_maps_CPointsMapXYZI, mrpt::maps::CPointsMap> cl(M("mrpt::maps"), "CPointsMapXYZI", "A map of 3D points with reflectance/intensity (float).\n \n\n mrpt::maps::CPointsMap, mrpt::maps::CMetricMap\n \n\n\n "); cl.def( pybind11::init( [](){ return new mrpt::maps::CPointsMapXYZI(); }, [](){ return new PyCallBack_mrpt_maps_CPointsMapXYZI(); } ) ); cl.def( pybind11::init(), pybind11::arg("o") ); diff --git a/python/src/mrpt/maps/CPointsMap.cpp b/python/src/mrpt/maps/CPointsMap.cpp index 3d2ece918e..35650c183f 100644 --- a/python/src/mrpt/maps/CPointsMap.cpp +++ b/python/src/mrpt/maps/CPointsMap.cpp @@ -253,7 +253,9 @@ void bind_mrpt_maps_CPointsMap(std::function< pybind11::module &(std::string con cl.def("kdtree_distance", (float (mrpt::maps::CPointsMap::*)(const float *, size_t, size_t) const) &mrpt::maps::CPointsMap::kdtree_distance, "Returns the distance between the vector \"p1[0:size-1]\" and the data\n point with index \"idx_p2\" stored in the class:\n\nC++: mrpt::maps::CPointsMap::kdtree_distance(const float *, size_t, size_t) const --> float", pybind11::arg("p1"), pybind11::arg("idx_p2"), pybind11::arg("size")); cl.def("mark_as_modified", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::mark_as_modified, "Users normally don't need to call this. Called by this class or children\n classes, set m_largestDistanceFromOriginIsUpdated=false, invalidates the\n kd-tree cache, and such. \n\nC++: mrpt::maps::CPointsMap::mark_as_modified() const --> void"); cl.def("asString", (std::string (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::asString, "Returns a short description of the map. \n\nC++: mrpt::maps::CPointsMap::asString() const --> std::string"); - cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, " @{ \n\nC++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool"); + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_prepare_for_2d_queries, " @{ \n\nC++: mrpt::maps::CPointsMap::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_prepare_for_3d_queries, "C++: mrpt::maps::CPointsMap::nn_prepare_for_3d_queries() const --> void"); + cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_has_indices_or_ids, "C++: mrpt::maps::CPointsMap::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::CPointsMap::*)() const) &mrpt::maps::CPointsMap::nn_index_count, "C++: mrpt::maps::CPointsMap::nn_index_count() const --> size_t"); cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); cl.def("nn_single_search", (bool (mrpt::maps::CPointsMap::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::CPointsMap::nn_single_search, "C++: mrpt::maps::CPointsMap::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); diff --git a/python/src/mrpt/maps/CPointsMapXYZI.cpp b/python/src/mrpt/maps/CPointsMapXYZI.cpp index 8a3a52ea94..0730248630 100644 --- a/python/src/mrpt/maps/CPointsMapXYZI.cpp +++ b/python/src/mrpt/maps/CPointsMapXYZI.cpp @@ -32,7 +32,7 @@ void bind_mrpt_maps_CPointsMapXYZI(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMapXYZI.h line:299 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMapXYZI.h line:304 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CPointsMapXYZI_t", "Specialization\n mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/CPointsMap_1.cpp b/python/src/mrpt/maps/CPointsMap_1.cpp index 84facc2086..3fcae64cb3 100644 --- a/python/src/mrpt/maps/CPointsMap_1.cpp +++ b/python/src/mrpt/maps/CPointsMap_1.cpp @@ -39,7 +39,7 @@ void bind_mrpt_maps_CPointsMap_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMap.h line:1244 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CPointsMap.h line:1254 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CPointsMap_t", "Specialization mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp index 02ac97b7bd..09244fb041 100644 --- a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp +++ b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp @@ -642,6 +642,19 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi } return CWeightedPointsMap::PLY_import_set_vertex_count(a0); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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 CWeightedPointsMap::PLY_import_set_vertex_timestamp(a0, a1); + } float squareDistanceToClosestCorrespondence(float a0, float a1) const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "squareDistanceToClosestCorrespondence"); @@ -824,6 +837,32 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi } return CPointsMap::asString(); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 CPointsMap::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 CPointsMap::nn_prepare_for_3d_queries(); + } bool nn_has_indices_or_ids() const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_has_indices_or_ids"); @@ -1091,7 +1130,7 @@ void bind_mrpt_maps_CReflectivityGridMap2D(std::function< pybind11::module &(std cl.def("setSize", (void (mrpt::maps::CWeightedPointsMap::*)(size_t)) &mrpt::maps::CWeightedPointsMap::setSize, "C++: mrpt::maps::CWeightedPointsMap::setSize(size_t) --> void", pybind11::arg("newLength")); cl.def("insertPointFast", [](mrpt::maps::CWeightedPointsMap &o, float const & a0, float const & a1) -> void { return o.insertPointFast(a0, a1); }, "", pybind11::arg("x"), pybind11::arg("y")); cl.def("insertPointFast", (void (mrpt::maps::CWeightedPointsMap::*)(float, float, float)) &mrpt::maps::CWeightedPointsMap::insertPointFast, "The virtual method for *without* calling\n mark_as_modified() \n\nC++: mrpt::maps::CWeightedPointsMap::insertPointFast(float, float, float) --> void", pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z")); - cl.def("setPointWeight", (void (mrpt::maps::CWeightedPointsMap::*)(size_t, unsigned long)) &mrpt::maps::CWeightedPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::setPointWeight(size_t, unsigned long) --> void", pybind11::arg("index"), pybind11::arg("w")); + cl.def("setPointWeight", (void (mrpt::maps::CWeightedPointsMap::*)(size_t, uint64_t)) &mrpt::maps::CWeightedPointsMap::setPointWeight, "Sets the point weight, which is ignored in all classes but those which\n actually store that field (Note: No checks are done for out-of-bounds\n index). \n\n getPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::setPointWeight(size_t, uint64_t) --> void", pybind11::arg("index"), pybind11::arg("w")); cl.def("getPointWeight", (unsigned int (mrpt::maps::CWeightedPointsMap::*)(size_t) const) &mrpt::maps::CWeightedPointsMap::getPointWeight, "Gets the point weight, which is ignored in all classes (defaults to 1)\n but in those which actually store that field (Note: No checks are done\n for out-of-bounds index). \n\n setPointWeight\n\nC++: mrpt::maps::CWeightedPointsMap::getPointWeight(size_t) const --> unsigned int", pybind11::arg("index")); { // mrpt::maps::CWeightedPointsMap::TMapDefinitionBase file: line:80 diff --git a/python/src/mrpt/maps/CSimplePointsMap.cpp b/python/src/mrpt/maps/CSimplePointsMap.cpp index 7506534560..1b80be4b8a 100644 --- a/python/src/mrpt/maps/CSimplePointsMap.cpp +++ b/python/src/mrpt/maps/CSimplePointsMap.cpp @@ -28,7 +28,7 @@ void bind_mrpt_maps_CSimplePointsMap(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CSimplePointsMap.h line:154 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CSimplePointsMap.h line:160 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CSimplePointsMap_t", "Specialization mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/CVoxelMap.cpp b/python/src/mrpt/maps/CVoxelMap.cpp index f042679cc9..6955a6caf6 100644 --- a/python/src/mrpt/maps/CVoxelMap.cpp +++ b/python/src/mrpt/maps/CVoxelMap.cpp @@ -212,6 +212,32 @@ struct PyCallBack_mrpt_maps_CVoxelMap : public mrpt::maps::CVoxelMap { } return CVoxelMapOccupancyBase::boundingBox(); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 CVoxelMapOccupancyBase::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 CVoxelMapOccupancyBase::nn_prepare_for_3d_queries(); + } bool nn_has_indices_or_ids() const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_has_indices_or_ids"); @@ -562,6 +588,32 @@ struct PyCallBack_mrpt_maps_CVoxelMapRGB : public mrpt::maps::CVoxelMapRGB { } return CVoxelMapOccupancyBase::boundingBox(); } + void nn_prepare_for_2d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_2d_queries"); + 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 CVoxelMapOccupancyBase::nn_prepare_for_2d_queries(); + } + void nn_prepare_for_3d_queries() const override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_prepare_for_3d_queries"); + 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 CVoxelMapOccupancyBase::nn_prepare_for_3d_queries(); + } bool nn_has_indices_or_ids() const override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "nn_has_indices_or_ids"); diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp index 67a288932b..7fbf0e079e 100644 --- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp +++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_1.cpp @@ -67,6 +67,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s cl.def_static("l2p", (float (*)(const signed char)) &mrpt::maps::CVoxelMapOccupancyBase::l2p, "C++: mrpt::maps::CVoxelMapOccupancyBase::l2p(const signed char) --> float", pybind11::arg("l")); cl.def_static("l2p_255", (uint8_t (*)(const signed char)) &mrpt::maps::CVoxelMapOccupancyBase::l2p_255, "C++: mrpt::maps::CVoxelMapOccupancyBase::l2p_255(const signed char) --> uint8_t", pybind11::arg("l")); cl.def_static("p2l", (signed char (*)(const float)) &mrpt::maps::CVoxelMapOccupancyBase::p2l, "C++: mrpt::maps::CVoxelMapOccupancyBase::p2l(const float) --> signed char", pybind11::arg("p")); + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_2d_queries, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_index_count, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_index_count() const --> size_t"); cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); @@ -102,6 +104,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_1(std::function< pybind11::module &(s cl.def("getAsSimplePointsMap", (class mrpt::maps::CSimplePointsMap * (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::getAsSimplePointsMap, "C++: mrpt::maps::CMetricMap::getAsSimplePointsMap() --> class mrpt::maps::CSimplePointsMap *", pybind11::return_value_policy::automatic); cl.def("assign", (class mrpt::maps::CMetricMap & (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CMetricMap &)) &mrpt::maps::CMetricMap::operator=, "C++: mrpt::maps::CMetricMap::operator=(const class mrpt::maps::CMetricMap &) --> class mrpt::maps::CMetricMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); diff --git a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp index 49b74e0529..d24835a7dd 100644 --- a/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp +++ b/python/src/mrpt/maps/CVoxelMapOccupancyBase_2.cpp @@ -67,6 +67,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s cl.def_static("l2p", (float (*)(const signed char)) &mrpt::maps::CVoxelMapOccupancyBase::l2p, "C++: mrpt::maps::CVoxelMapOccupancyBase::l2p(const signed char) --> float", pybind11::arg("l")); cl.def_static("l2p_255", (uint8_t (*)(const signed char)) &mrpt::maps::CVoxelMapOccupancyBase::l2p_255, "C++: mrpt::maps::CVoxelMapOccupancyBase::l2p_255(const signed char) --> uint8_t", pybind11::arg("l")); cl.def_static("p2l", (signed char (*)(const float)) &mrpt::maps::CVoxelMapOccupancyBase::p2l, "C++: mrpt::maps::CVoxelMapOccupancyBase::p2l(const float) --> signed char", pybind11::arg("p")); + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_2d_queries, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_has_indices_or_ids() const --> bool"); cl.def("nn_index_count", (size_t (mrpt::maps::CVoxelMapOccupancyBase::*)() const) &mrpt::maps::CVoxelMapOccupancyBase::nn_index_count, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_index_count() const --> size_t"); cl.def("nn_single_search", (bool (mrpt::maps::CVoxelMapOccupancyBase::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::CVoxelMapOccupancyBase::nn_single_search, "C++: mrpt::maps::CVoxelMapOccupancyBase::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrID")); @@ -102,6 +104,8 @@ void bind_mrpt_maps_CVoxelMapOccupancyBase_2(std::function< pybind11::module &(s cl.def("getAsSimplePointsMap", (class mrpt::maps::CSimplePointsMap * (mrpt::maps::CMetricMap::*)()) &mrpt::maps::CMetricMap::getAsSimplePointsMap, "C++: mrpt::maps::CMetricMap::getAsSimplePointsMap() --> class mrpt::maps::CSimplePointsMap *", pybind11::return_value_policy::automatic); cl.def("assign", (class mrpt::maps::CMetricMap & (mrpt::maps::CMetricMap::*)(const class mrpt::maps::CMetricMap &)) &mrpt::maps::CMetricMap::operator=, "C++: mrpt::maps::CMetricMap::operator=(const class mrpt::maps::CMetricMap &) --> class mrpt::maps::CMetricMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); diff --git a/python/src/mrpt/maps/CWeightedPointsMap.cpp b/python/src/mrpt/maps/CWeightedPointsMap.cpp index dd90654543..28e0c9173a 100644 --- a/python/src/mrpt/maps/CWeightedPointsMap.cpp +++ b/python/src/mrpt/maps/CWeightedPointsMap.cpp @@ -28,7 +28,7 @@ void bind_mrpt_maps_CWeightedPointsMap(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CWeightedPointsMap.h line:168 + { // mrpt::opengl::PointCloudAdapter file:mrpt/maps/CWeightedPointsMap.h line:174 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_maps_CWeightedPointsMap_t", "Specialization\n mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/maps/NearestNeighborsCapable.cpp b/python/src/mrpt/maps/NearestNeighborsCapable.cpp index ab164dbca6..ecd47c3808 100644 --- a/python/src/mrpt/maps/NearestNeighborsCapable.cpp +++ b/python/src/mrpt/maps/NearestNeighborsCapable.cpp @@ -27,6 +27,8 @@ void bind_mrpt_maps_NearestNeighborsCapable(std::function< pybind11::module &(st { // mrpt::maps::NearestNeighborsCapable file:mrpt/maps/NearestNeighborsCapable.h line:26 pybind11::class_> cl(M("mrpt::maps"), "NearestNeighborsCapable", "Virtual interface for maps having the capability of searching the closest\n neighbor(s) of a given query 2D or 3D point.\n\n Note this is more generic than mrpt::math::KDTreeCapable since it does not\n assume the use of KD-trees, and it is also non templatized, so users can use\n dynamic casting to interact with maps in a generic way.\n\n \n New in MRPT 2.11.3\n \n\n\n "); cl.def("nn_has_indices_or_ids", (bool (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids, "Returns true if the rest of `nn_*` methods will populate the output\n indices values with 0-based contiguous **indices**.\n Returns false if indices are actually sparse **ID numbers** without any\n expectation of they be contiguous or start near zero.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_has_indices_or_ids() const --> bool"); + cl.def("nn_prepare_for_2d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_2d_queries() const --> void"); + cl.def("nn_prepare_for_3d_queries", (void (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries, "Must be called before calls to `nn_*_search()` to ensure the required\n data structures are ready for queries (e.g. KD-trees). Useful in\n multithreading applications.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_prepare_for_3d_queries() const --> void"); cl.def("nn_index_count", (size_t (mrpt::maps::NearestNeighborsCapable::*)() const) &mrpt::maps::NearestNeighborsCapable::nn_index_count, "If nn_has_indices_or_ids() returns `true`, this must return the number\n of \"points\" (or whatever entity) the indices correspond to. Otherwise,\n the return value should be ignored.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_index_count() const --> size_t"); cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "Search for the closest 3D point to a given one.\n\n \n The query input point.\n \n\n The found closest point.\n \n\n The square Euclidean distance between the query\n and the returned point.\n \n\n The index or ID of the result point in the\n map.\n\n \n True if successful, false if no point was found.\n\nC++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); cl.def("nn_single_search", (bool (mrpt::maps::NearestNeighborsCapable::*)(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const) &mrpt::maps::NearestNeighborsCapable::nn_single_search, "C++: mrpt::maps::NearestNeighborsCapable::nn_single_search(const struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &, float &, uint64_t &) const --> bool", pybind11::arg("query"), pybind11::arg("result"), pybind11::arg("out_dist_sqr"), pybind11::arg("resultIndexOrIDOrID")); diff --git a/python/src/mrpt/maps/metric_map_types.cpp b/python/src/mrpt/maps/metric_map_types.cpp index e8c18b2d66..73339d33d8 100644 --- a/python/src/mrpt/maps/metric_map_types.cpp +++ b/python/src/mrpt/maps/metric_map_types.cpp @@ -210,7 +210,7 @@ void bind_mrpt_maps_metric_map_types(std::function< pybind11::module &(std::stri cl.def( pybind11::init( [](mrpt::maps::TSetOfMetricMapInitializers const &o){ return new mrpt::maps::TSetOfMetricMapInitializers(o); } ) ); cl.def("size", (size_t (mrpt::maps::TSetOfMetricMapInitializers::*)() const) &mrpt::maps::TSetOfMetricMapInitializers::size, "C++: mrpt::maps::TSetOfMetricMapInitializers::size() const --> size_t"); cl.def("clear", (void (mrpt::maps::TSetOfMetricMapInitializers::*)()) &mrpt::maps::TSetOfMetricMapInitializers::clear, "C++: mrpt::maps::TSetOfMetricMapInitializers::clear() --> void"); - cl.def("loadFromConfigFile", (void (mrpt::maps::TSetOfMetricMapInitializers::*)(const class mrpt::config::CConfigFileBase &, const std::string &)) &mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile, "Loads the configuration for the set of internal maps from a textual\ndefinition in an INI-like file.\n The format of the ini file is defined in CConfigFile. The list\nof maps and their options\n will be loaded from a handle of sections:\n\n \n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n Where:\n - ##: Represents the index of the map (e.g. \"00\",\"01\",...)\n - By default, the variables into each \"TOptions\" structure of the\nmaps\nare defined in textual form by the same name of the corresponding C++\nvariable (e.g. \"float resolution;\" -> \"resolution=0.10\")\n\n \n Examples of map definitions can be found in the '.ini' files\nprovided in the demo directories: \"share/mrpt/config-files/\"\n\nC++: mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile(const class mrpt::config::CConfigFileBase &, const std::string &) --> void", pybind11::arg("source"), pybind11::arg("sectionName")); + cl.def("loadFromConfigFile", (void (mrpt::maps::TSetOfMetricMapInitializers::*)(const class mrpt::config::CConfigFileBase &, const std::string &)) &mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile, "Loads the configuration for the set of internal maps from a textual\ndefinition in an INI-like file.\n The format of the ini file is defined in CConfigFile. The list\nof maps and their options\n will be loaded from a handle of sections:\n\n \n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n Where:\n - ##: Represents the index of the map (e.g. \"00\",\"01\",...)\n - By default, the variables into each \"TOptions\" structure of the\nmaps\nare defined in textual form by the same name of the corresponding C++\nvariable (e.g. \"float resolution;\" -> \"resolution=0.10\")\n\n \n Examples of map definitions can be found in the '.ini' files\nprovided in the demo directories: \"share/mrpt/config-files/\"\n\nC++: mrpt::maps::TSetOfMetricMapInitializers::loadFromConfigFile(const class mrpt::config::CConfigFileBase &, const std::string &) --> void", pybind11::arg("source"), pybind11::arg("sectionName")); cl.def("saveToConfigFile", (void (mrpt::maps::TSetOfMetricMapInitializers::*)(class mrpt::config::CConfigFileBase &, const std::string &) const) &mrpt::maps::TSetOfMetricMapInitializers::saveToConfigFile, "C++: mrpt::maps::TSetOfMetricMapInitializers::saveToConfigFile(class mrpt::config::CConfigFileBase &, const std::string &) const --> void", pybind11::arg("target"), pybind11::arg("section")); cl.def("assign", (class mrpt::maps::TSetOfMetricMapInitializers & (mrpt::maps::TSetOfMetricMapInitializers::*)(const class mrpt::maps::TSetOfMetricMapInitializers &)) &mrpt::maps::TSetOfMetricMapInitializers::operator=, "C++: mrpt::maps::TSetOfMetricMapInitializers::operator=(const class mrpt::maps::TSetOfMetricMapInitializers &) --> class mrpt::maps::TSetOfMetricMapInitializers &", pybind11::return_value_policy::automatic, pybind11::arg("")); } diff --git a/python/src/mrpt/math/CMatrixDynamic_1.cpp b/python/src/mrpt/math/CMatrixDynamic_1.cpp index 70f933be5c..4d90b28d64 100644 --- a/python/src/mrpt/math/CMatrixDynamic_1.cpp +++ b/python/src/mrpt/math/CMatrixDynamic_1.cpp @@ -1,20 +1,16 @@ #include #include -#include #include #include #include -#include +#include +#include +#include +#include #include #include -#include -#include -#include -#include -#include #include // __str__ #include -#include #include #include @@ -29,140 +25,95 @@ 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_CMatrixDynamic_1(std::function< pybind11::module &(std::string const &namespace_) > &M) { { // mrpt::math::CMatrixDynamic file:mrpt/math/CMatrixDynamic.h line:41 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixDynamic_double_t", ""); - cl.def( pybind11::init( [](mrpt::math::CMatrixDynamic const &o){ return new mrpt::math::CMatrixDynamic(o); } ) ); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixDynamic(); } ), "doc" ); - cl.def( pybind11::init( [](size_t const & a0){ return new mrpt::math::CMatrixDynamic(a0); } ), "doc" , pybind11::arg("row")); + pybind11::class_>, std::shared_ptr>>> cl(M("mrpt::math"), "CMatrixDynamic_mrpt_math_TPoint3D_float_t", ""); + cl.def( pybind11::init( [](mrpt::math::CMatrixDynamic> const &o){ return new mrpt::math::CMatrixDynamic>(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixDynamic>(); } ), "doc" ); + cl.def( pybind11::init( [](size_t const & a0){ return new mrpt::math::CMatrixDynamic>(a0); } ), "doc" , pybind11::arg("row")); cl.def( pybind11::init(), pybind11::arg("row"), pybind11::arg("col") ); - cl.def( pybind11::init &, size_t, size_t>(), pybind11::arg("m"), pybind11::arg("cropRowCount"), pybind11::arg("cropColCount") ); + cl.def( pybind11::init > &, size_t, size_t>(), pybind11::arg("m"), pybind11::arg("cropRowCount"), pybind11::arg("cropColCount") ); + + cl.def("assign", (class mrpt::math::CMatrixDynamic > & (mrpt::math::CMatrixDynamic>::*)(const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::CMatrixDynamic>::operator=>, "C++: mrpt::math::CMatrixDynamic>::operator=(const class mrpt::math::CMatrixDynamic > &) --> class mrpt::math::CMatrixDynamic > &", pybind11::return_value_policy::automatic, pybind11::arg("m")); + cl.def("swap", (void (mrpt::math::CMatrixDynamic>::*)(class mrpt::math::CMatrixDynamic > &)) &mrpt::math::CMatrixDynamic>::swap, "C++: mrpt::math::CMatrixDynamic>::swap(class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("o")); + cl.def("assign", (class mrpt::math::CMatrixDynamic > & (mrpt::math::CMatrixDynamic>::*)(const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::CMatrixDynamic>::operator=, "C++: mrpt::math::CMatrixDynamic>::operator=(const class mrpt::math::CMatrixDynamic > &) --> class mrpt::math::CMatrixDynamic > &", pybind11::return_value_policy::automatic, pybind11::arg("m")); + cl.def("rows", (int (mrpt::math::CMatrixDynamic>::*)() const) &mrpt::math::CMatrixDynamic>::rows, "C++: mrpt::math::CMatrixDynamic>::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixDynamic>::*)() const) &mrpt::math::CMatrixDynamic>::cols, "C++: mrpt::math::CMatrixDynamic>::cols() const --> int"); + cl.def("setSize", [](mrpt::math::CMatrixDynamic> &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixDynamic>::*)(size_t, size_t, bool)) &mrpt::math::CMatrixDynamic>::setSize, "C++: mrpt::math::CMatrixDynamic>::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("resize", (void (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::resize, "C++: mrpt::math::CMatrixDynamic>::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixDynamic>::*)(size_t)) &mrpt::math::CMatrixDynamic>::resize, "C++: mrpt::math::CMatrixDynamic>::resize(size_t) --> void", pybind11::arg("vectorLen")); + cl.def("derived", (class mrpt::math::CMatrixDynamic > & (mrpt::math::CMatrixDynamic>::*)()) &mrpt::math::CMatrixDynamic>::derived, "C++: mrpt::math::CMatrixDynamic>::derived() --> class mrpt::math::CMatrixDynamic > &", pybind11::return_value_policy::automatic); + cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::conservativeResize, "C++: mrpt::math::CMatrixDynamic>::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("data", (struct mrpt::math::TPoint3D_ * (mrpt::math::CMatrixDynamic>::*)()) &mrpt::math::CMatrixDynamic>::data, "C++: mrpt::math::CMatrixDynamic>::data() --> struct mrpt::math::TPoint3D_ *", pybind11::return_value_policy::automatic); + cl.def("__call__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic>::operator(), "C++: mrpt::math::CMatrixDynamic>::operator()(size_t, size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__getitem__", (struct mrpt::math::TPoint3D_ & (mrpt::math::CMatrixDynamic>::*)(size_t)) &mrpt::math::CMatrixDynamic>::operator[], "C++: mrpt::math::CMatrixDynamic>::operator[](size_t) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::reference, pybind11::arg("ith")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_2UL_2UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); - cl.def("setFromMatrixLike", (void (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::setFromMatrixLike>, "C++: mrpt::math::CMatrixDynamic::setFromMatrixLike(const class mrpt::math::CMatrixDynamic &) --> void", pybind11::arg("m")); - cl.def("setFromMatrixLike", (void (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixDynamic::setFromMatrixLike>, "C++: mrpt::math::CMatrixDynamic::setFromMatrixLike(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("m")); - cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::operator=, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); - cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::operator=, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); - cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixDynamic::operator=<3UL,3UL>, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); - cl.def("swap", (void (mrpt::math::CMatrixDynamic::*)(class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::swap, "C++: mrpt::math::CMatrixDynamic::swap(class mrpt::math::CMatrixDynamic &) --> void", pybind11::arg("o")); - cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::operator=, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); - cl.def("rows", (int (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::rows, "C++: mrpt::math::CMatrixDynamic::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cols, "C++: mrpt::math::CMatrixDynamic::cols() const --> int"); - cl.def("setSize", [](mrpt::math::CMatrixDynamic &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t, bool)) &mrpt::math::CMatrixDynamic::setSize, "C++: mrpt::math::CMatrixDynamic::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("resize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::resize, "C++: mrpt::math::CMatrixDynamic::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::resize, "C++: mrpt::math::CMatrixDynamic::resize(size_t) --> void", pybind11::arg("vectorLen")); - cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); - cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("data", (double * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); - cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); - cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); - cl.def("lu_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::lu_solve, "C++: mrpt::math::CMatrixDynamic::lu_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_3UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); // Manually-added matrix methods: using dat_t = double; - using mat_t = mrpt::math::CMatrixDynamic; + using mat_t = mrpt::math::CMatrixFixed; cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); - cl.def_static("Identity", [](const size_t N) -> mat_t { return mat_t::Identity(N); }, "Returns the NxN identity matrix"); - cl.def_static("Zero", [](const size_t nRows, const size_t nCols) -> mat_t { return mat_t::Zero(nRows,nCols); }, "Returns a matrix with zeroes"); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, PyCallBack_mrpt_math_CMatrixD, mrpt::serialization::CSerializable, mrpt::math::CMatrixDynamic> 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 &>(), pybind11::arg("m") ); - - cl.def( pybind11::init &>(), pybind11::arg("m") ); - - 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("assign", (class mrpt::math::CMatrixD & (mrpt::math::CMatrixD::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixD::operator=>, "C++: mrpt::math::CMatrixD::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixD &", pybind11::return_value_policy::automatic, pybind11::arg("other")); - 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("other")); - 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/src/mrpt/math/CMatrixDynamic_2.cpp b/python/src/mrpt/math/CMatrixDynamic_2.cpp new file mode 100644 index 0000000000..4865de6147 --- /dev/null +++ b/python/src/mrpt/math/CMatrixDynamic_2.cpp @@ -0,0 +1,168 @@ +#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::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_CMatrixDynamic_2(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::math::CMatrixDynamic file:mrpt/math/CMatrixDynamic.h line:41 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixDynamic_double_t", ""); + cl.def( pybind11::init( [](mrpt::math::CMatrixDynamic const &o){ return new mrpt::math::CMatrixDynamic(o); } ) ); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixDynamic(); } ), "doc" ); + cl.def( pybind11::init( [](size_t const & a0){ return new mrpt::math::CMatrixDynamic(a0); } ), "doc" , pybind11::arg("row")); + cl.def( pybind11::init(), pybind11::arg("row"), pybind11::arg("col") ); + + cl.def( pybind11::init &, size_t, size_t>(), pybind11::arg("m"), pybind11::arg("cropRowCount"), pybind11::arg("cropColCount") ); + + cl.def("setFromMatrixLike", (void (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::setFromMatrixLike>, "C++: mrpt::math::CMatrixDynamic::setFromMatrixLike(const class mrpt::math::CMatrixDynamic &) --> void", pybind11::arg("m")); + cl.def("setFromMatrixLike", (void (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixDynamic::setFromMatrixLike>, "C++: mrpt::math::CMatrixDynamic::setFromMatrixLike(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("m")); + cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::operator=, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); + cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::operator=, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); + cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixDynamic::operator=<3UL,3UL>, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); + cl.def("swap", (void (mrpt::math::CMatrixDynamic::*)(class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::swap, "C++: mrpt::math::CMatrixDynamic::swap(class mrpt::math::CMatrixDynamic &) --> void", pybind11::arg("o")); + cl.def("assign", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixDynamic::operator=, "C++: mrpt::math::CMatrixDynamic::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic, pybind11::arg("m")); + cl.def("rows", (int (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::rows, "C++: mrpt::math::CMatrixDynamic::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cols, "C++: mrpt::math::CMatrixDynamic::cols() const --> int"); + cl.def("setSize", [](mrpt::math::CMatrixDynamic &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t, bool)) &mrpt::math::CMatrixDynamic::setSize, "C++: mrpt::math::CMatrixDynamic::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("resize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::resize, "C++: mrpt::math::CMatrixDynamic::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixDynamic::*)(size_t)) &mrpt::math::CMatrixDynamic::resize, "C++: mrpt::math::CMatrixDynamic::resize(size_t) --> void", pybind11::arg("vectorLen")); + cl.def("derived", (class mrpt::math::CMatrixDynamic & (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::derived, "C++: mrpt::math::CMatrixDynamic::derived() --> class mrpt::math::CMatrixDynamic &", pybind11::return_value_policy::automatic); + cl.def("conservativeResize", (void (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::conservativeResize, "C++: mrpt::math::CMatrixDynamic::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("data", (double * (mrpt::math::CMatrixDynamic::*)()) &mrpt::math::CMatrixDynamic::data, "C++: mrpt::math::CMatrixDynamic::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixDynamic::*)(size_t, size_t)) &mrpt::math::CMatrixDynamic::operator(), "C++: mrpt::math::CMatrixDynamic::operator()(size_t, size_t) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("cast_float", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_float, "C++: mrpt::math::CMatrixDynamic::cast_float() const --> class mrpt::math::CMatrixDynamic"); + cl.def("cast_double", (class mrpt::math::CMatrixDynamic (mrpt::math::CMatrixDynamic::*)() const) &mrpt::math::CMatrixDynamic::cast_double, "C++: mrpt::math::CMatrixDynamic::cast_double() const --> class mrpt::math::CMatrixDynamic"); + cl.def("llt_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::llt_solve, "C++: mrpt::math::CMatrixDynamic::llt_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); + cl.def("lu_solve", (class mrpt::math::CVectorDynamic (mrpt::math::CMatrixDynamic::*)(const class mrpt::math::CVectorDynamic &) const) &mrpt::math::CMatrixDynamic::lu_solve, "C++: mrpt::math::CMatrixDynamic::lu_solve(const class mrpt::math::CVectorDynamic &) const --> class mrpt::math::CVectorDynamic", pybind11::arg("b")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixDynamic; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", [](const size_t N) -> mat_t { return mat_t::Identity(N); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", [](const size_t nRows, const size_t nCols) -> mat_t { return mat_t::Zero(nRows,nCols); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, PyCallBack_mrpt_math_CMatrixD, mrpt::serialization::CSerializable, mrpt::math::CMatrixDynamic> 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 &>(), pybind11::arg("m") ); + + cl.def( pybind11::init &>(), pybind11::arg("m") ); + + 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("assign", (class mrpt::math::CMatrixD & (mrpt::math::CMatrixD::*)(const class mrpt::math::CMatrixDynamic &)) &mrpt::math::CMatrixD::operator=>, "C++: mrpt::math::CMatrixD::operator=(const class mrpt::math::CMatrixDynamic &) --> class mrpt::math::CMatrixD &", pybind11::return_value_policy::automatic, pybind11::arg("other")); + 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("other")); + 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/src/mrpt/math/CMatrixFixed.cpp b/python/src/mrpt/math/CMatrixFixed.cpp index 877ac0cb49..2168c4bf9e 100644 --- a/python/src/mrpt/math/CMatrixFixed.cpp +++ b/python/src/mrpt/math/CMatrixFixed.cpp @@ -18,71 +18,6 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_2UL_2UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_3UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - // Manually-added matrix methods: - using dat_t = double; - using mat_t = mrpt::math::CMatrixFixed; - cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); - cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); - cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); - cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); - cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); - cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); - cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_4UL_4UL_t", ""); cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); @@ -159,6 +94,69 @@ void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string c cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_7UL_7UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_1UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = double; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r &M) { - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_7UL_7UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_1UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - // Manually-added matrix methods: - using dat_t = double; - using mat_t = mrpt::math::CMatrixFixed; - cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); - cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); - cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); - cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); - cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); - cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_3UL_4UL_t", ""); cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); @@ -132,4 +68,55 @@ void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_2UL_1UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_6UL_1UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } } diff --git a/python/src/mrpt/math/CMatrixFixed_2.cpp b/python/src/mrpt/math/CMatrixFixed_2.cpp index 88d8935ca9..2f75fb4ea9 100644 --- a/python/src/mrpt/math/CMatrixFixed_2.cpp +++ b/python/src/mrpt/math/CMatrixFixed_2.cpp @@ -18,57 +18,6 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_2UL_1UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_6UL_1UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_7UL_1UL_t", ""); cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); @@ -132,4 +81,66 @@ void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_4UL_3UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_3UL_3UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const float *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const float *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); + cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r &M) { - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_4UL_3UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_3UL_3UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const float *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const float *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - - // Manually-added matrix methods: - using dat_t = float; - using mat_t = mrpt::math::CMatrixFixed; - cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); - cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); - cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); - cl.def_static("Identity", []() -> mat_t { return mat_t::Identity(); }, "Returns the NxN identity matrix"); - cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); - cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); - cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_4UL_4UL_t", ""); cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); @@ -141,7 +79,6 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); @@ -157,6 +94,68 @@ void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_12UL_1UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + } + { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 + pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_4UL_1UL_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); + cl.def( pybind11::init(), pybind11::arg("") ); + + cl.def( pybind11::init(), pybind11::arg("data") ); + cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); + + cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); + cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const float *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const float *) --> void", pybind11::arg("data")); + cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); + cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); + cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); + cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); + cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); + cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); + cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); + cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); + cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); + cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); + cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); + cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); + cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); + + // Manually-added matrix methods: + using dat_t = float; + using mat_t = mrpt::math::CMatrixFixed; + cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); + cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); + cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); + cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); + cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); + cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); + cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r -#include -#include -#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_math_CMatrixFixed_4(std::function< pybind11::module &(std::string const &namespace_) > &M) -{ - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_double_12UL_1UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const double *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const double *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (double * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> double *", pybind11::return_value_policy::automatic); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("__getitem__", (double & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator[], "C++: mrpt::math::CMatrixFixed::operator[](int) --> double &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - } - { // mrpt::math::CMatrixFixed file:mrpt/math/CMatrixFixed.h line:34 - pybind11::class_, std::shared_ptr>> cl(M("mrpt::math"), "CMatrixFixed_float_4UL_1UL_t", ""); - cl.def( pybind11::init( [](){ return new mrpt::math::CMatrixFixed(); } ) ); - cl.def( pybind11::init(), pybind11::arg("") ); - - cl.def( pybind11::init(), pybind11::arg("data") ); - - cl.def( pybind11::init(), pybind11::arg("rows"), pybind11::arg("cols") ); - - cl.def( pybind11::init( [](mrpt::math::CMatrixFixed const &o){ return new mrpt::math::CMatrixFixed(o); } ) ); - cl.def("loadFromRawPointer", (void (mrpt::math::CMatrixFixed::*)(const float *)) &mrpt::math::CMatrixFixed::loadFromRawPointer, "C++: mrpt::math::CMatrixFixed::loadFromRawPointer(const float *) --> void", pybind11::arg("data")); - cl.def("setSize", [](mrpt::math::CMatrixFixed &o, size_t const & a0, size_t const & a1) -> void { return o.setSize(a0, a1); }, "", pybind11::arg("row"), pybind11::arg("col")); - cl.def("setSize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t, bool)) &mrpt::math::CMatrixFixed::setSize, "C++: mrpt::math::CMatrixFixed::setSize(size_t, size_t, bool) --> void", pybind11::arg("row"), pybind11::arg("col"), pybind11::arg("zeroNewElements")); - cl.def("swap", (void (mrpt::math::CMatrixFixed::*)(class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::swap, "C++: mrpt::math::CMatrixFixed::swap(class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("o")); - cl.def("conservativeResize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::conservativeResize, "C++: mrpt::math::CMatrixFixed::conservativeResize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t) --> void", pybind11::arg("n")); - cl.def("resize", (void (mrpt::math::CMatrixFixed::*)(size_t, size_t)) &mrpt::math::CMatrixFixed::resize, "C++: mrpt::math::CMatrixFixed::resize(size_t, size_t) --> void", pybind11::arg("row"), pybind11::arg("col")); - cl.def("rows", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::rows, "C++: mrpt::math::CMatrixFixed::rows() const --> int"); - cl.def("cols", (int (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cols, "C++: mrpt::math::CMatrixFixed::cols() const --> int"); - cl.def("data", (float * (mrpt::math::CMatrixFixed::*)()) &mrpt::math::CMatrixFixed::data, "C++: mrpt::math::CMatrixFixed::data() --> float *", pybind11::return_value_policy::automatic); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int, int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int, int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("row"), pybind11::arg("col")); - cl.def("__call__", (float & (mrpt::math::CMatrixFixed::*)(int)) &mrpt::math::CMatrixFixed::operator(), "C++: mrpt::math::CMatrixFixed::operator()(int) --> float &", pybind11::return_value_policy::reference, pybind11::arg("i")); - cl.def("cast_float", (class mrpt::math::CMatrixFixed (mrpt::math::CMatrixFixed::*)() const) &mrpt::math::CMatrixFixed::cast_float, "C++: mrpt::math::CMatrixFixed::cast_float() const --> class mrpt::math::CMatrixFixed"); - cl.def("sum_At", (void (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::sum_At, "C++: mrpt::math::CMatrixFixed::sum_At(const class mrpt::math::CMatrixFixed &) --> void", pybind11::arg("A")); - cl.def("assign", (class mrpt::math::CMatrixFixed & (mrpt::math::CMatrixFixed::*)(const class mrpt::math::CMatrixFixed &)) &mrpt::math::CMatrixFixed::operator=, "C++: mrpt::math::CMatrixFixed::operator=(const class mrpt::math::CMatrixFixed &) --> class mrpt::math::CMatrixFixed &", pybind11::return_value_policy::automatic, pybind11::arg("")); - - // Manually-added matrix methods: - using dat_t = float; - using mat_t = mrpt::math::CMatrixFixed; - cl.def("__getitem__", [](const mat_t&self, pybind11::tuple coord) -> dat_t { if (coord.size()==2) return self.coeff(coord[0].cast(), coord[1].cast()); else if (coord.size()==1) return self[coord[0].cast()]; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__setitem__", [](mat_t&self, pybind11::tuple coord, dat_t val) { if (coord.size()==2) self.coeffRef(coord[0].cast(), coord[1].cast())=val; else if (coord.size()==1) self[coord[0].cast()]=val; else throw std::invalid_argument("Access with [idx] or [row,col]"); }); - cl.def("__str__", [](const mat_t& o) -> std::string { return o.asString(); } ); - cl.def("inMatlabFormat", [](const mat_t& o) -> std::string { return o.inMatlabFormat(); } ); - cl.def("size", [](const mat_t&self) -> pybind11::tuple { return pybind11::make_tuple(self.cols(),self.rows()); }); - cl.def_static("Zero", []() -> mat_t { return mat_t::Zero(); }, "Returns a matrix with zeroes"); - cl.def(pybind11::init( [](pybind11::list vals){ auto m = new mat_t(); const auto nR = vals.size(); if (!nR) return m; const auto nC = vals[0].cast().size(); m->setSize(nR,nC); for (size_t r=0;r(); for (size_t c=0;ccoeffRef(r,c) = row[c].cast(); } return m; })); - cl.def("to_list", [](const mat_t&self) -> pybind11::list { auto l = pybind11::list(); const auto nR = self.rows(), nC = self.cols(); for (size_t r=0;r(M("mrpt::math"), "TMatrixTextFileFormat", pybind11::arithmetic(), "Selection of the number format in MatrixVectorBase::saveToTextFile()\n \n") - .value("MATRIX_FORMAT_ENG", mrpt::math::MATRIX_FORMAT_ENG) - .value("MATRIX_FORMAT_FIXED", mrpt::math::MATRIX_FORMAT_FIXED) - .value("MATRIX_FORMAT_INT", mrpt::math::MATRIX_FORMAT_INT) - .export_values(); - -; - -} diff --git a/python/src/mrpt/math/MatrixBase.cpp b/python/src/mrpt/math/MatrixBase.cpp new file mode 100644 index 0000000000..118a85c885 --- /dev/null +++ b/python/src/mrpt/math/MatrixBase.cpp @@ -0,0 +1,88 @@ +#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_MatrixBase(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + { // mrpt::math::MatrixBase file:mrpt/math/MatrixBase.h line:23 + pybind11::class_,mrpt::math::CMatrixDynamic >>, std::shared_ptr,mrpt::math::CMatrixDynamic >>>, mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>> cl(M("mrpt::math"), "MatrixBase_mrpt_math_TPoint3D_float_mrpt_math_CMatrixDynamic_mrpt_math_TPoint3D_float_t", ""); + cl.def( pybind11::init( [](){ return new mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>(); } ) ); + cl.def( pybind11::init( [](mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >> const &o){ return new mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>(o); } ) ); + cl.def("mbDerived", (class mrpt::math::CMatrixDynamic > & (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)()) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::mbDerived, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::mbDerived() --> class mrpt::math::CMatrixDynamic > &", pybind11::return_value_policy::automatic); + cl.def("setDiagonal", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal(const unsigned long, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("N"), pybind11::arg("value")); + cl.def("setDiagonal", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setDiagonal(const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("value")); + cl.def("setIdentity", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)()) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity() --> void"); + cl.def("setIdentity", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::setIdentity(const unsigned long) --> void", pybind11::arg("N")); + cl.def_static("Identity", (class mrpt::math::CMatrixDynamic > (*)()) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity() --> class mrpt::math::CMatrixDynamic >"); + cl.def_static("Identity", (class mrpt::math::CMatrixDynamic > (*)(const unsigned long)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::Identity(const unsigned long) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("N")); + cl.def("matProductOf_AB", (void (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &, const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::matProductOf_AB, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::matProductOf_AB(const class mrpt::math::CMatrixDynamic > &, const class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("A"), pybind11::arg("B")); + cl.def("det", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::det, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::det() const --> struct mrpt::math::TPoint3D_"); + cl.def("inverse", (class mrpt::math::CMatrixDynamic > (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse() const --> class mrpt::math::CMatrixDynamic >"); + cl.def("inverse_LLt", (class mrpt::math::CMatrixDynamic > (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse_LLt, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::inverse_LLt() const --> class mrpt::math::CMatrixDynamic >"); + cl.def("rank", [](mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >> const &o) -> int { return o.rank(); }, ""); + cl.def("rank", (int (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_) const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::rank, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::rank(struct mrpt::math::TPoint3D_) const --> int", pybind11::arg("threshold")); + cl.def("chol", (bool (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(class mrpt::math::CMatrixDynamic > &) const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::chol, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::chol(class mrpt::math::CMatrixDynamic > &) const --> bool", pybind11::arg("U")); + cl.def("maximumDiagonal", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::maximumDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::maximumDiagonal() const --> struct mrpt::math::TPoint3D_"); + cl.def("minimumDiagonal", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::minimumDiagonal, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::minimumDiagonal() const --> struct mrpt::math::TPoint3D_"); + cl.def("trace", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::trace, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::trace() const --> struct mrpt::math::TPoint3D_"); + cl.def("assign", (class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > & (mrpt::math::MatrixBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > &)) &mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::operator=, "C++: mrpt::math::MatrixBase, mrpt::math::CMatrixDynamic>>::operator=(const class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > &) --> class mrpt::math::MatrixBase, class mrpt::math::CMatrixDynamic > > &", pybind11::return_value_policy::automatic, pybind11::arg("")); + cl.def("fill", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const struct mrpt::math::TPoint3D_ &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::fill, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::fill(const struct mrpt::math::TPoint3D_ &) --> void", pybind11::arg("val")); + cl.def("setConstant", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant(const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("value")); + cl.def("setConstant", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t, size_t, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant(size_t, size_t, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("nrows"), pybind11::arg("ncols"), pybind11::arg("value")); + cl.def("setConstant", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setConstant(size_t, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("nrows"), pybind11::arg("value")); + cl.def_static("Constant", (class mrpt::math::CMatrixDynamic > (*)(const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant(const struct mrpt::math::TPoint3D_) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("value")); + cl.def_static("Constant", (class mrpt::math::CMatrixDynamic > (*)(size_t, size_t, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Constant(size_t, size_t, const struct mrpt::math::TPoint3D_) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("nrows"), pybind11::arg("ncols"), pybind11::arg("value")); + cl.def("assign", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long, const struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::assign, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::assign(const unsigned long, const struct mrpt::math::TPoint3D_) --> void", pybind11::arg("N"), pybind11::arg("value")); + cl.def("setZero", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)()) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero() --> void"); + cl.def("setZero", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t, size_t)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero(size_t, size_t) --> void", pybind11::arg("nrows"), pybind11::arg("ncols")); + cl.def("setZero", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(size_t)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::setZero(size_t) --> void", pybind11::arg("nrows")); + cl.def_static("Zero", (class mrpt::math::CMatrixDynamic > (*)()) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero() --> class mrpt::math::CMatrixDynamic >"); + cl.def_static("Zero", (class mrpt::math::CMatrixDynamic > (*)(size_t, size_t)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::Zero(size_t, size_t) --> class mrpt::math::CMatrixDynamic >", pybind11::arg("nrows"), pybind11::arg("ncols")); + cl.def("coeffRef", (struct mrpt::math::TPoint3D_ & (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(int, int)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeffRef, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeffRef(int, int) --> struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::automatic, pybind11::arg("r"), pybind11::arg("c")); + cl.def("coeff", (const struct mrpt::math::TPoint3D_ & (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(int, int) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeff, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::coeff(int, int) const --> const struct mrpt::math::TPoint3D_ &", pybind11::return_value_policy::automatic, pybind11::arg("r"), pybind11::arg("c")); + cl.def("isSquare", (bool (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::isSquare, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::isSquare() const --> bool"); + cl.def("empty", (bool (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::empty, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::empty() const --> bool"); + cl.def("norm_inf", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm_inf, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm_inf() const --> struct mrpt::math::TPoint3D_"); + cl.def("norm", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::norm() const --> struct mrpt::math::TPoint3D_"); + cl.def("__iadd__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=(struct mrpt::math::TPoint3D_) --> void", pybind11::arg("s")); + cl.def("__isub__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=(struct mrpt::math::TPoint3D_) --> void", pybind11::arg("s")); + cl.def("__imul__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(struct mrpt::math::TPoint3D_)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator*=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator*=(struct mrpt::math::TPoint3D_) --> void", pybind11::arg("s")); + cl.def("__add__", (class mrpt::math::CMatrixDynamic > (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+(const class mrpt::math::CMatrixDynamic > &) const --> class mrpt::math::CMatrixDynamic >", pybind11::arg("m2")); + cl.def("__iadd__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator+=(const class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("m2")); + cl.def("__isub__", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::CMatrixDynamic > &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator-=(const class mrpt::math::CMatrixDynamic > &) --> void", pybind11::arg("m2")); + cl.def("sum", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum() const --> struct mrpt::math::TPoint3D_"); + cl.def("sum_abs", (struct mrpt::math::TPoint3D_ (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum_abs, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::sum_abs() const --> struct mrpt::math::TPoint3D_"); + cl.def("asString", (std::string (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)() const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::asString, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::asString() const --> std::string"); + cl.def("inMatlabFormat", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o) -> std::string { return o.inMatlabFormat(); }, ""); + cl.def("inMatlabFormat", (std::string (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const unsigned long) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::inMatlabFormat, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::inMatlabFormat(const unsigned long) const --> std::string", pybind11::arg("decimal_digits")); + cl.def("saveToTextFile", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o, const std::string & a0) -> void { return o.saveToTextFile(a0); }, "", pybind11::arg("file")); + cl.def("saveToTextFile", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o, const std::string & a0, enum mrpt::math::TMatrixTextFileFormat const & a1) -> void { return o.saveToTextFile(a0, a1); }, "", pybind11::arg("file"), pybind11::arg("fileFormat")); + cl.def("saveToTextFile", [](mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >> const &o, const std::string & a0, enum mrpt::math::TMatrixTextFileFormat const & a1, bool const & a2) -> void { return o.saveToTextFile(a0, a1, a2); }, "", pybind11::arg("file"), pybind11::arg("fileFormat"), pybind11::arg("appendMRPTHeader")); + cl.def("saveToTextFile", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const std::string &, enum mrpt::math::TMatrixTextFileFormat, bool, const std::string &) const) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::saveToTextFile, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::saveToTextFile(const std::string &, enum mrpt::math::TMatrixTextFileFormat, bool, const std::string &) const --> void", pybind11::arg("file"), pybind11::arg("fileFormat"), pybind11::arg("appendMRPTHeader"), pybind11::arg("userHeader")); + cl.def("loadFromTextFile", (void (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const std::string &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::loadFromTextFile, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::loadFromTextFile(const std::string &) --> void", pybind11::arg("file")); + cl.def("assign", (class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > & (mrpt::math::MatrixVectorBase,mrpt::math::CMatrixDynamic >>::*)(const class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > &)) &mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator=, "C++: mrpt::math::MatrixVectorBase, mrpt::math::CMatrixDynamic>>::operator=(const class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > &) --> class mrpt::math::MatrixVectorBase, class mrpt::math::CMatrixDynamic > > &", pybind11::return_value_policy::automatic, pybind11::arg("")); + } +} diff --git a/python/src/mrpt/math/MatrixVectorBase.cpp b/python/src/mrpt/math/MatrixVectorBase.cpp new file mode 100644 index 0000000000..c70a428674 --- /dev/null +++ b/python/src/mrpt/math/MatrixVectorBase.cpp @@ -0,0 +1,27 @@ +#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_MatrixVectorBase(std::function< pybind11::module &(std::string const &namespace_) > &M) +{ + // mrpt::math::TMatrixTextFileFormat file:mrpt/math/MatrixVectorBase.h line:35 + pybind11::enum_(M("mrpt::math"), "TMatrixTextFileFormat", pybind11::arithmetic(), "Selection of the number format in MatrixVectorBase::saveToTextFile()\n \n") + .value("MATRIX_FORMAT_ENG", mrpt::math::MATRIX_FORMAT_ENG) + .value("MATRIX_FORMAT_FIXED", mrpt::math::MATRIX_FORMAT_FIXED) + .value("MATRIX_FORMAT_INT", mrpt::math::MATRIX_FORMAT_INT) + .export_values(); + +; + +} diff --git a/python/src/mrpt/obs/CObservationPointCloud.cpp b/python/src/mrpt/obs/CObservationPointCloud.cpp index b9a7ce709e..cc98b7a085 100644 --- a/python/src/mrpt/obs/CObservationPointCloud.cpp +++ b/python/src/mrpt/obs/CObservationPointCloud.cpp @@ -250,7 +250,7 @@ struct PyCallBack_mrpt_obs_CObservationPointCloud : public mrpt::obs::CObservati } }; -// mrpt::obs::CObservationRotatingScan file:mrpt/obs/CObservationRotatingScan.h line:61 +// mrpt::obs::CObservationRotatingScan file:mrpt/obs/CObservationRotatingScan.h line:53 struct PyCallBack_mrpt_obs_CObservationRotatingScan : public mrpt::obs::CObservationRotatingScan { using mrpt::obs::CObservationRotatingScan::CObservationRotatingScan; @@ -319,6 +319,32 @@ struct PyCallBack_mrpt_obs_CObservationRotatingScan : public mrpt::obs::CObserva } return CObservationRotatingScan::serializeFrom(a0, a1); } + 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 CObservationRotatingScan::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 CObservationRotatingScan::unload(); + } using _binder_ret_0 = mrpt::Clock::time_point; _binder_ret_0 getOriginalReceivedTimeStamp() const override { pybind11::gil_scoped_acquire gil; @@ -411,32 +437,6 @@ struct PyCallBack_mrpt_obs_CObservationRotatingScan : public mrpt::obs::CObserva } 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_CObservationPointCloud(std::function< pybind11::module &(std::string const &namespace_) > &M) @@ -471,14 +471,21 @@ void bind_mrpt_obs_CObservationPointCloud(std::function< pybind11::module &(std: cl.def("overrideExternalStorageFormatFlag", (void (mrpt::obs::CObservationPointCloud::*)(const enum mrpt::obs::CObservationPointCloud::ExternalStorageFormat)) &mrpt::obs::CObservationPointCloud::overrideExternalStorageFormatFlag, "C++: mrpt::obs::CObservationPointCloud::overrideExternalStorageFormatFlag(const enum mrpt::obs::CObservationPointCloud::ExternalStorageFormat) --> void", pybind11::arg("fmt")); cl.def("assign", (class mrpt::obs::CObservationPointCloud & (mrpt::obs::CObservationPointCloud::*)(const class mrpt::obs::CObservationPointCloud &)) &mrpt::obs::CObservationPointCloud::operator=, "C++: mrpt::obs::CObservationPointCloud::operator=(const class mrpt::obs::CObservationPointCloud &) --> class mrpt::obs::CObservationPointCloud &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::obs::CObservationRotatingScan file:mrpt/obs/CObservationRotatingScan.h line:61 - pybind11::class_, PyCallBack_mrpt_obs_CObservationRotatingScan, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationRotatingScan", "A `CObservation`-derived class for raw range data from a 2D or 3D\n rotating scanner. This class is the preferred alternative to\n CObservationVelodyneScan and CObservation2DRangeScan in MRPT 2.x, since it\n exposes range data as an organized matrix, more convenient for feature\n detection directly on \"range images\".\n This class can also import data from KITTI dataset-like binary files\n containing unorganized (non \"undistorted\", i.e. without compensation for\n lidar motion) point clouds, which get organized into a 2D range image for\n easier filtering and postprocessing.\n\n Check out the main data fields in the list of members below.\n\n Note that this object has timestamp fields:\n - The standard `CObservation::timestamp` field in the base class, which\n should contain the accurate satellite-based UTC timestamp if available,\n and\n - the field originalReceivedTimestamp, with the\n local computer-based timestamp based on the reception of the message in\n the computer.\n\n Both timestamps correspond to the firing of the first laser in\n the first CObservationRotatingScan::scan_packets packet.\n\n \n\n API for accurate reconstruction of point clouds from raw range images:\n - generatePointCloud()\n - generatePointCloudAlongSE3Trajectory()\n\n \n New in MRPT 2.0.0\n \n\n CObservation, mrpt::hwdrivers::CVelodyneScanner"); + { // mrpt::obs::CObservationRotatingScan file:mrpt/obs/CObservationRotatingScan.h line:53 + pybind11::class_, PyCallBack_mrpt_obs_CObservationRotatingScan, mrpt::obs::CObservation> cl(M("mrpt::obs"), "CObservationRotatingScan", "A `CObservation`-derived class for raw range data from a 2D or 3D\n rotating scanner. This class is the preferred alternative to\n CObservationVelodyneScan and CObservation2DRangeScan in MRPT 2.x, since it\n exposes range data as an organized matrix, more convenient for feature\n detection directly on \"range images\" and on points stored as a matrix in the\n member organizedPoints.\n\n Check out the main data fields in the list of members below.\n\n Note that this object has timestamp fields:\n - The standard `CObservation::timestamp` field in the base class, which\n should contain the accurate satellite-based UTC timestamp if available,\n and\n - the field originalReceivedTimestamp, with the\n local computer-based timestamp based on the reception of the message in\n the computer.\n\n Both timestamps correspond to the firing of the **first** laser in\n the scan, i.e. the first column in organizedPoints.\n\n The reference frame for the 3D LIDAR is with +X pointing forward, +Z up.\n\n \n New in MRPT 2.0.0\n \n\n CObservation, mrpt::hwdrivers::CVelodyneScanner"); cl.def( pybind11::init( [](){ return new mrpt::obs::CObservationRotatingScan(); }, [](){ return new PyCallBack_mrpt_obs_CObservationRotatingScan(); } ) ); cl.def( pybind11::init( [](PyCallBack_mrpt_obs_CObservationRotatingScan const &o){ return new PyCallBack_mrpt_obs_CObservationRotatingScan(o); } ) ); cl.def( pybind11::init( [](mrpt::obs::CObservationRotatingScan const &o){ return new mrpt::obs::CObservationRotatingScan(o); } ) ); + + pybind11::enum_(cl, "ExternalStorageFormat", "") + .value("None", mrpt::obs::CObservationRotatingScan::ExternalStorageFormat::None) + .value("MRPT_Serialization", mrpt::obs::CObservationRotatingScan::ExternalStorageFormat::MRPT_Serialization) + .value("PlainTextFile", mrpt::obs::CObservationRotatingScan::ExternalStorageFormat::PlainTextFile); + cl.def_readwrite("rowCount", &mrpt::obs::CObservationRotatingScan::rowCount); cl.def_readwrite("columnCount", &mrpt::obs::CObservationRotatingScan::columnCount); cl.def_readwrite("rangeImage", &mrpt::obs::CObservationRotatingScan::rangeImage); + cl.def_readwrite("organizedPoints", &mrpt::obs::CObservationRotatingScan::organizedPoints); cl.def_readwrite("intensityImage", &mrpt::obs::CObservationRotatingScan::intensityImage); cl.def_readwrite("rangeOtherLayers", &mrpt::obs::CObservationRotatingScan::rangeOtherLayers); cl.def_readwrite("rangeResolution", &mrpt::obs::CObservationRotatingScan::rangeResolution); @@ -497,8 +504,15 @@ void bind_mrpt_obs_CObservationPointCloud(std::function< pybind11::module &(std: cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::obs::CObservationRotatingScan::CreateObject, "C++: mrpt::obs::CObservationRotatingScan::CreateObject() --> class std::shared_ptr"); cl.def("fromVelodyne", (void (mrpt::obs::CObservationRotatingScan::*)(const class mrpt::obs::CObservationVelodyneScan &)) &mrpt::obs::CObservationRotatingScan::fromVelodyne, "@{ \n\nC++: mrpt::obs::CObservationRotatingScan::fromVelodyne(const class mrpt::obs::CObservationVelodyneScan &) --> void", pybind11::arg("o")); cl.def("fromScan2D", (void (mrpt::obs::CObservationRotatingScan::*)(const class mrpt::obs::CObservation2DRangeScan &)) &mrpt::obs::CObservationRotatingScan::fromScan2D, "C++: mrpt::obs::CObservationRotatingScan::fromScan2D(const class mrpt::obs::CObservation2DRangeScan &) --> void", pybind11::arg("o")); - cl.def("fromPointCloud", (void (mrpt::obs::CObservationRotatingScan::*)(const class mrpt::obs::CObservationPointCloud &)) &mrpt::obs::CObservationRotatingScan::fromPointCloud, "C++: mrpt::obs::CObservationRotatingScan::fromPointCloud(const class mrpt::obs::CObservationPointCloud &) --> void", pybind11::arg("o")); - cl.def("fromGeneric", (bool (mrpt::obs::CObservationRotatingScan::*)(const class mrpt::obs::CObservation &)) &mrpt::obs::CObservationRotatingScan::fromGeneric, "Will convert from another observation if it's any of the supported\n source types (see fromVelodyne(), fromScan2D(), fromPointCloud()) and\n return true, or will return false otherwise if there is no known way to\n convert from the passed object. \n\nC++: mrpt::obs::CObservationRotatingScan::fromGeneric(const class mrpt::obs::CObservation &) --> bool", pybind11::arg("o")); + cl.def("fromGeneric", (bool (mrpt::obs::CObservationRotatingScan::*)(const class mrpt::obs::CObservation &)) &mrpt::obs::CObservationRotatingScan::fromGeneric, "Will convert from another observation if it's any of the supported\n source types (see fromVelodyne(), fromScan2D()) and\n return true, or will return false otherwise if there is no known way to\n convert from the passed object. \n\nC++: mrpt::obs::CObservationRotatingScan::fromGeneric(const class mrpt::obs::CObservation &) --> bool", pybind11::arg("o")); + cl.def("load", (void (mrpt::obs::CObservationRotatingScan::*)() const) &mrpt::obs::CObservationRotatingScan::load, " @{ \n\nC++: mrpt::obs::CObservationRotatingScan::load() const --> void"); + cl.def("unload", (void (mrpt::obs::CObservationRotatingScan::*)() const) &mrpt::obs::CObservationRotatingScan::unload, "C++: mrpt::obs::CObservationRotatingScan::unload() const --> void"); + cl.def("isExternallyStored", (bool (mrpt::obs::CObservationRotatingScan::*)() const) &mrpt::obs::CObservationRotatingScan::isExternallyStored, "@{ \n\nC++: mrpt::obs::CObservationRotatingScan::isExternallyStored() const --> bool"); + cl.def("getExternalStorageFile", (const std::string & (mrpt::obs::CObservationRotatingScan::*)() const) &mrpt::obs::CObservationRotatingScan::getExternalStorageFile, "C++: mrpt::obs::CObservationRotatingScan::getExternalStorageFile() const --> const std::string &", pybind11::return_value_policy::automatic); + cl.def("setAsExternalStorage", (void (mrpt::obs::CObservationRotatingScan::*)(const std::string &, const enum mrpt::obs::CObservationRotatingScan::ExternalStorageFormat)) &mrpt::obs::CObservationRotatingScan::setAsExternalStorage, "C++: mrpt::obs::CObservationRotatingScan::setAsExternalStorage(const std::string &, const enum mrpt::obs::CObservationRotatingScan::ExternalStorageFormat) --> void", pybind11::arg("fileName"), pybind11::arg("fmt")); + cl.def("overrideExternalStorageFormatFlag", (void (mrpt::obs::CObservationRotatingScan::*)(const enum mrpt::obs::CObservationRotatingScan::ExternalStorageFormat)) &mrpt::obs::CObservationRotatingScan::overrideExternalStorageFormatFlag, "C++: mrpt::obs::CObservationRotatingScan::overrideExternalStorageFormatFlag(const enum mrpt::obs::CObservationRotatingScan::ExternalStorageFormat) --> void", pybind11::arg("fmt")); + cl.def("saveToTextFile", (bool (mrpt::obs::CObservationRotatingScan::*)(const std::string &) const) &mrpt::obs::CObservationRotatingScan::saveToTextFile, "Write scan data to a plain text, each line has:\n `x y z range intensity row_idx col_idx`\n\n For each point in the organized point cloud.\n Invalid points (e.g. no lidar return) are stored as (x,y,z)=(0,0,0) and\n range=0.\n\n \n true on success\n\nC++: mrpt::obs::CObservationRotatingScan::saveToTextFile(const std::string &) const --> bool", pybind11::arg("filename")); + cl.def("loadFromTextFile", (bool (mrpt::obs::CObservationRotatingScan::*)(const std::string &)) &mrpt::obs::CObservationRotatingScan::loadFromTextFile, "Loads the range, intensity, and organizedPoints members from a plain\n text file in the format describd in saveToTextFile()\n\nC++: mrpt::obs::CObservationRotatingScan::loadFromTextFile(const std::string &) --> bool", pybind11::arg("filename")); cl.def("getOriginalReceivedTimeStamp", (mrpt::Clock::time_point (mrpt::obs::CObservationRotatingScan::*)() const) &mrpt::obs::CObservationRotatingScan::getOriginalReceivedTimeStamp, "@} \n\nC++: mrpt::obs::CObservationRotatingScan::getOriginalReceivedTimeStamp() const --> mrpt::Clock::time_point"); cl.def("getSensorPose", (void (mrpt::obs::CObservationRotatingScan::*)(class mrpt::poses::CPose3D &) const) &mrpt::obs::CObservationRotatingScan::getSensorPose, "C++: mrpt::obs::CObservationRotatingScan::getSensorPose(class mrpt::poses::CPose3D &) const --> void", pybind11::arg("out_sensorPose")); cl.def("setSensorPose", (void (mrpt::obs::CObservationRotatingScan::*)(const class mrpt::poses::CPose3D &)) &mrpt::obs::CObservationRotatingScan::setSensorPose, "C++: mrpt::obs::CObservationRotatingScan::setSensorPose(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newSensorPose")); diff --git a/python/src/mrpt/obs/customizable_obs_viz.cpp b/python/src/mrpt/obs/customizable_obs_viz.cpp index 9898e46737..fd840c1b4e 100644 --- a/python/src/mrpt/obs/customizable_obs_viz.cpp +++ b/python/src/mrpt/obs/customizable_obs_viz.cpp @@ -32,6 +32,7 @@ #include #include #include +#include #include #include #include @@ -83,7 +84,7 @@ void bind_mrpt_obs_customizable_obs_viz(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::obs::VisualizationParameters file:mrpt/obs/customizable_obs_viz.h line:30 + { // mrpt::obs::VisualizationParameters file:mrpt/obs/customizable_obs_viz.h line:31 pybind11::class_> cl(M("mrpt::obs"), "VisualizationParameters", "Here we can customize the way observations will be rendered as 3D objects\n in obs_to_viz(), obs3Dscan_to_viz(), etc.\n \n\n obs_to_viz(), obs3Dscan_to_viz()"); cl.def( pybind11::init( [](){ return new mrpt::obs::VisualizationParameters(); } ) ); cl.def( pybind11::init( [](mrpt::obs::VisualizationParameters const &o){ return new mrpt::obs::VisualizationParameters(o); } ) ); @@ -109,25 +110,28 @@ void bind_mrpt_obs_customizable_obs_viz(std::function< pybind11::module &(std::s cl.def("load_from_ini_file", (void (mrpt::obs::VisualizationParameters::*)(const class mrpt::config::CConfigFileBase &, const std::string &)) &mrpt::obs::VisualizationParameters::load_from_ini_file, "C++: mrpt::obs::VisualizationParameters::load_from_ini_file(const class mrpt::config::CConfigFileBase &, const std::string &) --> void", pybind11::arg("cfg"), pybind11::arg("section")); cl.def("assign", (struct mrpt::obs::VisualizationParameters & (mrpt::obs::VisualizationParameters::*)(const struct mrpt::obs::VisualizationParameters &)) &mrpt::obs::VisualizationParameters::operator=, "C++: mrpt::obs::VisualizationParameters::operator=(const struct mrpt::obs::VisualizationParameters &) --> struct mrpt::obs::VisualizationParameters &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - // mrpt::obs::obs_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:71 + // mrpt::obs::obs_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:72 M("mrpt::obs").def("obs_to_viz", (bool (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obs_to_viz, "Clears `out` and creates a visualization of the given observation,\n dispatching the call according to the actual observation class.\n \n\n true if type has known visualizer, false if it does not (then, `out`\n will be empty)\n\n \n This and the accompanying functions are defined in namespace\n mrpt::obs, but you must link against mrpt::maps too to have their\n definitions.\n\nC++: mrpt::obs::obs_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> bool", pybind11::arg("obs"), pybind11::arg("p"), pybind11::arg("out")); - // mrpt::obs::obs_to_viz(const class mrpt::obs::CSensoryFrame &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:86 + // mrpt::obs::obs_to_viz(const class mrpt::obs::CSensoryFrame &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:87 M("mrpt::obs").def("obs_to_viz", (bool (*)(const class mrpt::obs::CSensoryFrame &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obs_to_viz, "Clears `out` and creates a visualization of the given sensory-frame,\n dispatching the call according to the actual observation classes inside the\n SF.\n\n \n true if type has known visualizer, false if it does not (then, `out`\n will be empty)\n\n \n This and the accompanying functions are defined in namespace\n mrpt::obs, but you must link against mrpt::maps too to have their\n definitions.\n\nC++: mrpt::obs::obs_to_viz(const class mrpt::obs::CSensoryFrame &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> bool", pybind11::arg("sf"), pybind11::arg("p"), pybind11::arg("out")); - // mrpt::obs::obs3Dscan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:91 + // mrpt::obs::obs3Dscan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:92 M("mrpt::obs").def("obs3Dscan_to_viz", (void (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obs3Dscan_to_viz, "Clears `out` and creates a visualization of the given observation.\n\nC++: mrpt::obs::obs3Dscan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> void", pybind11::arg("obs"), pybind11::arg("p"), pybind11::arg("out")); - // mrpt::obs::obsVelodyne_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:96 + // mrpt::obs::obsVelodyne_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:97 M("mrpt::obs").def("obsVelodyne_to_viz", (void (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obsVelodyne_to_viz, "Clears `out` and creates a visualization of the given observation.\n\nC++: mrpt::obs::obsVelodyne_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> void", pybind11::arg("obs"), pybind11::arg("p"), pybind11::arg("out")); - // mrpt::obs::obsPointCloud_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:101 + // mrpt::obs::obsPointCloud_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:102 M("mrpt::obs").def("obsPointCloud_to_viz", (void (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obsPointCloud_to_viz, "Clears `out` and creates a visualization of the given observation.\n\nC++: mrpt::obs::obsPointCloud_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> void", pybind11::arg("obs"), pybind11::arg("p"), pybind11::arg("out")); - // mrpt::obs::obs2Dscan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:106 + // mrpt::obs::obsRotatingScan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:106 + M("mrpt::obs").def("obsRotatingScan_to_viz", (void (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obsRotatingScan_to_viz, "C++: mrpt::obs::obsRotatingScan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> void", pybind11::arg("obs"), pybind11::arg("p"), pybind11::arg("out")); + + // mrpt::obs::obs2Dscan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) file:mrpt/obs/customizable_obs_viz.h line:111 M("mrpt::obs").def("obs2Dscan_to_viz", (void (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &)) &mrpt::obs::obs2Dscan_to_viz, "Clears `out` and creates a visualization of the given observation.\n\nC++: mrpt::obs::obs2Dscan_to_viz(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &, class mrpt::opengl::CSetOfObjects &) --> void", pybind11::arg("obs"), pybind11::arg("p"), pybind11::arg("out")); - // mrpt::obs::recolorize3Dpc(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &) file:mrpt/obs/customizable_obs_viz.h line:111 + // mrpt::obs::recolorize3Dpc(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &) file:mrpt/obs/customizable_obs_viz.h line:116 M("mrpt::obs").def("recolorize3Dpc", (void (*)(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &)) &mrpt::obs::recolorize3Dpc, "Recolorize a pointcloud according to the given parameters\n\nC++: mrpt::obs::recolorize3Dpc(const class std::shared_ptr &, const struct mrpt::obs::VisualizationParameters &) --> void", pybind11::arg("pnts"), pybind11::arg("p")); } diff --git a/python/src/mrpt/opengl/CGridPlaneXY.cpp b/python/src/mrpt/opengl/CGridPlaneXY.cpp index a29db89bf6..9d56458c56 100644 --- a/python/src/mrpt/opengl/CGridPlaneXY.cpp +++ b/python/src/mrpt/opengl/CGridPlaneXY.cpp @@ -382,6 +382,19 @@ struct PyCallBack_mrpt_opengl_CPointCloud : public mrpt::opengl::CPointCloud { } return CPointCloud::PLY_import_set_vertex_count(a0); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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 CPointCloud::PLY_import_set_vertex_timestamp(a0, a1); + } void PLY_import_set_face_count(size_t a0) override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_face_count"); diff --git a/python/src/mrpt/opengl/CPointCloud.cpp b/python/src/mrpt/opengl/CPointCloud.cpp index da91e72aa1..f670924aa6 100644 --- a/python/src/mrpt/opengl/CPointCloud.cpp +++ b/python/src/mrpt/opengl/CPointCloud.cpp @@ -293,7 +293,7 @@ struct PyCallBack_mrpt_opengl_CText3D : public mrpt::opengl::CText3D { void bind_mrpt_opengl_CPointCloud(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::PointCloudAdapter file:mrpt/opengl/CPointCloud.h line:344 + { // mrpt::opengl::PointCloudAdapter file:mrpt/opengl/CPointCloud.h line:351 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_opengl_CPointCloud_t", "Specialization mrpt::opengl::PointCloudAdapter\n \n"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/opengl/CPointCloudColoured.cpp b/python/src/mrpt/opengl/CPointCloudColoured.cpp index e5fb82f803..503bc885ae 100644 --- a/python/src/mrpt/opengl/CPointCloudColoured.cpp +++ b/python/src/mrpt/opengl/CPointCloudColoured.cpp @@ -196,6 +196,19 @@ struct PyCallBack_mrpt_opengl_CPointCloudColoured : public mrpt::opengl::CPointC } return CPointCloudColoured::PLY_import_set_face_count(a0); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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 CPointCloudColoured::PLY_import_set_vertex_timestamp(a0, a1); + } void PLY_import_set_vertex(size_t a0, const struct mrpt::math::TPoint3D_ & a1, const struct mrpt::img::TColorf * a2) override { pybind11::gil_scoped_acquire gil; pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex"); @@ -407,7 +420,7 @@ void bind_mrpt_opengl_CPointCloudColoured(std::function< pybind11::module &(std: cl.def("recolorizeByCoordinate", (void (mrpt::opengl::CPointCloudColoured::*)(const float, const float, const int, const enum mrpt::img::TColormap)) &mrpt::opengl::CPointCloudColoured::recolorizeByCoordinate, "Regenerates the color of each point according the one coordinate\n (coord_index:0,1,2 for X,Y,Z) and the given color map. \n\nC++: mrpt::opengl::CPointCloudColoured::recolorizeByCoordinate(const float, const float, const int, const enum mrpt::img::TColormap) --> void", pybind11::arg("coord_min"), pybind11::arg("coord_max"), pybind11::arg("coord_index"), pybind11::arg("color_map")); cl.def("toYAMLMap", (void (mrpt::opengl::CPointCloudColoured::*)(class mrpt::containers::yaml &) const) &mrpt::opengl::CPointCloudColoured::toYAMLMap, "C++: mrpt::opengl::CPointCloudColoured::toYAMLMap(class mrpt::containers::yaml &) const --> void", pybind11::arg("propertiesMap")); } - { // mrpt::opengl::PointCloudAdapter file:mrpt/opengl/CPointCloudColoured.h line:275 + { // mrpt::opengl::PointCloudAdapter file:mrpt/opengl/CPointCloudColoured.h line:281 pybind11::class_, std::shared_ptr>> cl(M("mrpt::opengl"), "PointCloudAdapter_mrpt_opengl_CPointCloudColoured_t", "Specialization\n mrpt::opengl::PointCloudAdapter \n\n\n mrpt_adapters_grp"); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/opengl/CTexturedPlane.cpp b/python/src/mrpt/opengl/CTexturedPlane.cpp index 66a69c3e4c..ffdce432e8 100644 --- a/python/src/mrpt/opengl/CTexturedPlane.cpp +++ b/python/src/mrpt/opengl/CTexturedPlane.cpp @@ -457,12 +457,15 @@ void bind_mrpt_opengl_CTexturedPlane(std::function< pybind11::module &(std::stri cl.def("clone", (class mrpt::rtti::CObject * (mrpt::opengl::Viewport::*)() const) &mrpt::opengl::Viewport::clone, "C++: mrpt::opengl::Viewport::clone() const --> class mrpt::rtti::CObject *", pybind11::return_value_policy::automatic); cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::opengl::Viewport::CreateObject, "C++: mrpt::opengl::Viewport::CreateObject() --> class std::shared_ptr"); cl.def("setCloneView", (void (mrpt::opengl::Viewport::*)(const std::string &)) &mrpt::opengl::Viewport::setCloneView, "Set this viewport as a clone of some other viewport, given its name - as\n a side effect, current list of internal OpenGL objects is cleared.\n By default, only the objects are cloned, not the camera. See\n \n\n resetCloneView\n\nC++: mrpt::opengl::Viewport::setCloneView(const std::string &) --> void", pybind11::arg("clonedViewport")); - cl.def("setImageView", (void (mrpt::opengl::Viewport::*)(const class mrpt::img::CImage &)) &mrpt::opengl::Viewport::setImageView, "Set this viewport into \"image view\"-mode, where an image is efficiently\n drawn (fitting the viewport area) using an OpenGL textured quad.\n Call this method with the new image to update the displayed image (but\n recall to first lock the parent openglscene's critical section, then do\n the update, then release the lock, and then issue a window repaint).\n Internally, the texture is drawn using a mrpt::opengl::CTexturedPlane\n The viewport can be reverted to behave like a normal viewport by\n calling setNormalMode()\n\nC++: mrpt::opengl::Viewport::setImageView(const class mrpt::img::CImage &) --> void", pybind11::arg("img")); + cl.def("setImageView", [](mrpt::opengl::Viewport &o, const class mrpt::img::CImage & a0) -> void { return o.setImageView(a0); }, "", pybind11::arg("img")); + cl.def("setImageView", (void (mrpt::opengl::Viewport::*)(const class mrpt::img::CImage &, bool)) &mrpt::opengl::Viewport::setImageView, "Set this viewport into \"image view\"-mode, where an image is efficiently\n drawn (fitting the viewport area) using an OpenGL textured quad.\n Call this method with the new image to update the displayed image (but\n recall to first lock the parent openglscene's critical section, then do\n the update, then release the lock, and then issue a window repaint).\n Internally, the texture is drawn using a mrpt::opengl::CTexturedPlane\n The viewport can be reverted to behave like a normal viewport by\n calling setNormalMode()\n\n \n This method can also make the viewport\n transparent (default), so the area not filled with the image still allows\n seeing an underlying viewport.\n\nC++: mrpt::opengl::Viewport::setImageView(const class mrpt::img::CImage &, bool) --> void", pybind11::arg("img"), pybind11::arg("transparentBackground")); cl.def("isImageViewMode", (bool (mrpt::opengl::Viewport::*)() const) &mrpt::opengl::Viewport::isImageViewMode, "Returns true if setImageView() has been called on this viewport \n\nC++: mrpt::opengl::Viewport::isImageViewMode() const --> bool"); cl.def("resetCloneView", (void (mrpt::opengl::Viewport::*)()) &mrpt::opengl::Viewport::resetCloneView, "Reset the viewport to normal mode: rendering its own objects.\n \n\n setCloneView, setNormalMode\n\nC++: mrpt::opengl::Viewport::resetCloneView() --> void"); cl.def("setCloneCamera", (void (mrpt::opengl::Viewport::*)(bool)) &mrpt::opengl::Viewport::setCloneCamera, "If set to true, and setCloneView() has been called, this viewport will\n be rendered using the camera of the cloned viewport.\n\nC++: mrpt::opengl::Viewport::setCloneCamera(bool) --> void", pybind11::arg("enable")); cl.def("setClonedCameraFrom", (void (mrpt::opengl::Viewport::*)(const std::string &)) &mrpt::opengl::Viewport::setClonedCameraFrom, "Use the camera of another viewport.\n Note this works even for viewports not in \"clone\" mode, so you can\n render different scenes but using the same camera.\n\nC++: mrpt::opengl::Viewport::setClonedCameraFrom(const std::string &) --> void", pybind11::arg("viewPortName")); cl.def("setNormalMode", (void (mrpt::opengl::Viewport::*)()) &mrpt::opengl::Viewport::setNormalMode, "Resets the viewport to a normal 3D viewport \n setCloneView,\n setImageView \n\nC++: mrpt::opengl::Viewport::setNormalMode() --> void"); + cl.def("setViewportVisibility", (void (mrpt::opengl::Viewport::*)(bool)) &mrpt::opengl::Viewport::setViewportVisibility, "C++: mrpt::opengl::Viewport::setViewportVisibility(bool) --> void", pybind11::arg("visible")); + cl.def("getViewportVisibility", (bool (mrpt::opengl::Viewport::*)() const) &mrpt::opengl::Viewport::getViewportVisibility, "C++: mrpt::opengl::Viewport::getViewportVisibility() const --> bool"); cl.def("enablePolygonNicest", [](mrpt::opengl::Viewport &o) -> void { return o.enablePolygonNicest(); }, ""); cl.def("enablePolygonNicest", (void (mrpt::opengl::Viewport::*)(bool)) &mrpt::opengl::Viewport::enablePolygonNicest, "Sets glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST) is enabled, or GL_FASTEST\n otherwise. \n\nC++: mrpt::opengl::Viewport::enablePolygonNicest(bool) --> void", pybind11::arg("enable")); cl.def("isPolygonNicestEnabled", (bool (mrpt::opengl::Viewport::*)() const) &mrpt::opengl::Viewport::isPolygonNicestEnabled, "C++: mrpt::opengl::Viewport::isPolygonNicestEnabled() const --> bool"); diff --git a/python/src/mrpt/opengl/PLY_import_export.cpp b/python/src/mrpt/opengl/PLY_import_export.cpp index de8502a5cb..887e6ca569 100644 --- a/python/src/mrpt/opengl/PLY_import_export.cpp +++ b/python/src/mrpt/opengl/PLY_import_export.cpp @@ -69,9 +69,22 @@ struct PyCallBack_mrpt_opengl_PLY_Importer : public mrpt::opengl::PLY_Importer { } pybind11::pybind11_fail("Tried to call pure virtual function \"PLY_Importer::PLY_import_set_vertex\""); } + void PLY_import_set_vertex_timestamp(size_t a0, const double a1) override { + pybind11::gil_scoped_acquire gil; + pybind11::function overload = pybind11::get_overload(static_cast(this), "PLY_import_set_vertex_timestamp"); + 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)); + } + pybind11::pybind11_fail("Tried to call pure virtual function \"PLY_Importer::PLY_import_set_vertex_timestamp\""); + } }; -// mrpt::opengl::PLY_Exporter file:mrpt/opengl/PLY_import_export.h line:84 +// mrpt::opengl::PLY_Exporter file:mrpt/opengl/PLY_import_export.h line:87 struct PyCallBack_mrpt_opengl_PLY_Exporter : public mrpt::opengl::PLY_Exporter { using mrpt::opengl::PLY_Exporter::PLY_Exporter; @@ -128,7 +141,7 @@ void bind_mrpt_opengl_PLY_import_export(std::function< pybind11::module &(std::s cl.def("getLoadPLYErrorString", (std::string (mrpt::opengl::PLY_Importer::*)() const) &mrpt::opengl::PLY_Importer::getLoadPLYErrorString, "Return a description of the error if loadFromPlyFile() returned false,\n or an empty string if the file was loaded without problems. \n\nC++: mrpt::opengl::PLY_Importer::getLoadPLYErrorString() const --> std::string"); cl.def("assign", (class mrpt::opengl::PLY_Importer & (mrpt::opengl::PLY_Importer::*)(const class mrpt::opengl::PLY_Importer &)) &mrpt::opengl::PLY_Importer::operator=, "C++: mrpt::opengl::PLY_Importer::operator=(const class mrpt::opengl::PLY_Importer &) --> class mrpt::opengl::PLY_Importer &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::opengl::PLY_Exporter file:mrpt/opengl/PLY_import_export.h line:84 + { // mrpt::opengl::PLY_Exporter file:mrpt/opengl/PLY_import_export.h line:87 pybind11::class_, PyCallBack_mrpt_opengl_PLY_Exporter> cl(M("mrpt::opengl"), "PLY_Exporter", "A virtual base class that implements the capability of exporting 3D point\n clouds and faces to a file in the Stanford PLY format.\n \n\n https://www.mrpt.org/Support_for_the_Stanford_3D_models_file_format_PLY\n \n\n PLY_Importer\n \n\n\n "); cl.def(pybind11::init()); cl.def( pybind11::init( [](){ return new PyCallBack_mrpt_opengl_PLY_Exporter(); } ) ); diff --git a/python/src/mrpt/opengl/Viewport.cpp b/python/src/mrpt/opengl/Viewport.cpp index 661bdd0c16..fcbafe16bc 100644 --- a/python/src/mrpt/opengl/Viewport.cpp +++ b/python/src/mrpt/opengl/Viewport.cpp @@ -59,7 +59,7 @@ PYBIND11_MAKE_OPAQUE(std::shared_ptr) #endif -// mrpt::opengl::mrptEventGLPreRender file:mrpt/opengl/Viewport.h line:559 +// mrpt::opengl::mrptEventGLPreRender file:mrpt/opengl/Viewport.h line:564 struct PyCallBack_mrpt_opengl_mrptEventGLPreRender : public mrpt::opengl::mrptEventGLPreRender { using mrpt::opengl::mrptEventGLPreRender::mrptEventGLPreRender; @@ -78,7 +78,7 @@ struct PyCallBack_mrpt_opengl_mrptEventGLPreRender : public mrpt::opengl::mrptEv } }; -// mrpt::opengl::mrptEventGLPostRender file:mrpt/opengl/Viewport.h line:582 +// mrpt::opengl::mrptEventGLPostRender file:mrpt/opengl/Viewport.h line:587 struct PyCallBack_mrpt_opengl_mrptEventGLPostRender : public mrpt::opengl::mrptEventGLPostRender { using mrpt::opengl::mrptEventGLPostRender::mrptEventGLPostRender; @@ -170,12 +170,12 @@ struct PyCallBack_mrpt_opengl_Scene : public mrpt::opengl::Scene { void bind_mrpt_opengl_Viewport(std::function< pybind11::module &(std::string const &namespace_) > &M) { - { // mrpt::opengl::mrptEventGLPreRender file:mrpt/opengl/Viewport.h line:559 + { // mrpt::opengl::mrptEventGLPreRender file:mrpt/opengl/Viewport.h line:564 pybind11::class_, PyCallBack_mrpt_opengl_mrptEventGLPreRender, mrpt::system::mrptEvent> cl(M("mrpt::opengl"), "mrptEventGLPreRender", "An event sent by an mrpt::opengl::Viewport just after clearing the\n viewport and setting the GL_PROJECTION matrix, and before calling the scene\n OpenGL drawing primitives.\n\n While handling this event you can call OpenGL glDraw(), etc.\n\n IMPORTANTE NOTICE: Event handlers in your observer class will most likely be\n invoked from an internal GUI thread of MRPT, so all your code in the handler\n must be thread safe."); cl.def( pybind11::init(), pybind11::arg("obj") ); } - { // mrpt::opengl::mrptEventGLPostRender file:mrpt/opengl/Viewport.h line:582 + { // mrpt::opengl::mrptEventGLPostRender file:mrpt/opengl/Viewport.h line:587 pybind11::class_, PyCallBack_mrpt_opengl_mrptEventGLPostRender, mrpt::system::mrptEvent> cl(M("mrpt::opengl"), "mrptEventGLPostRender", "An event sent by an mrpt::opengl::Viewport after calling the scene\n OpenGL drawing primitives and before doing a glSwapBuffers\n\n While handling this event you can call OpenGL glBegin(),glEnd(),gl*\n functions or those in mrpt::opengl::gl_utils to draw stuff *on the top* of\n the normal\n objects contained in the Scene.\n\n IMPORTANTE NOTICE: Event handlers in your observer class will most likely\n be invoked from an internal GUI thread of MRPT,\n so all your code in the handler must be thread safe."); cl.def( pybind11::init(), pybind11::arg("obj") ); diff --git a/python/src/mrpt/poses/CPoseInterpolatorBase.cpp b/python/src/mrpt/poses/CPoseInterpolatorBase.cpp index fc1b4970ab..1a75c94bfb 100644 --- a/python/src/mrpt/poses/CPoseInterpolatorBase.cpp +++ b/python/src/mrpt/poses/CPoseInterpolatorBase.cpp @@ -68,8 +68,10 @@ void bind_mrpt_poses_CPoseInterpolatorBase(std::function< pybind11::module &(std cl.def("getPreviousPoseWithMinDistance", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const mrpt::Clock::time_point &, double, struct mrpt::math::TPose2D &)) &mrpt::poses::CPoseInterpolatorBase<2>::getPreviousPoseWithMinDistance, "C++: mrpt::poses::CPoseInterpolatorBase<2>::getPreviousPoseWithMinDistance(const mrpt::Clock::time_point &, double, struct mrpt::math::TPose2D &) --> bool", pybind11::arg("t"), pybind11::arg("distance"), pybind11::arg("out_pose")); cl.def("getPreviousPoseWithMinDistance", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const mrpt::Clock::time_point &, double, class mrpt::poses::CPose2D &)) &mrpt::poses::CPoseInterpolatorBase<2>::getPreviousPoseWithMinDistance, "C++: mrpt::poses::CPoseInterpolatorBase<2>::getPreviousPoseWithMinDistance(const mrpt::Clock::time_point &, double, class mrpt::poses::CPose2D &) --> bool", pybind11::arg("t"), pybind11::arg("distance"), pybind11::arg("out_pose")); cl.def("saveToTextFile", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const std::string &) const) &mrpt::poses::CPoseInterpolatorBase<2>::saveToTextFile, "C++: mrpt::poses::CPoseInterpolatorBase<2>::saveToTextFile(const std::string &) const --> bool", pybind11::arg("s")); + cl.def("saveToTextFile_TUM", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const std::string &) const) &mrpt::poses::CPoseInterpolatorBase<2>::saveToTextFile_TUM, "C++: mrpt::poses::CPoseInterpolatorBase<2>::saveToTextFile_TUM(const std::string &) const --> bool", pybind11::arg("s")); cl.def("saveInterpolatedToTextFile", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const std::string &, const struct std::chrono::duration> &) const) &mrpt::poses::CPoseInterpolatorBase<2>::saveInterpolatedToTextFile, "C++: mrpt::poses::CPoseInterpolatorBase<2>::saveInterpolatedToTextFile(const std::string &, const struct std::chrono::duration> &) const --> bool", pybind11::arg("s"), pybind11::arg("period")); cl.def("loadFromTextFile", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const std::string &)) &mrpt::poses::CPoseInterpolatorBase<2>::loadFromTextFile, "C++: mrpt::poses::CPoseInterpolatorBase<2>::loadFromTextFile(const std::string &) --> bool", pybind11::arg("s")); + cl.def("loadFromTextFile_TUM", (bool (mrpt::poses::CPoseInterpolatorBase<2>::*)(const std::string &)) &mrpt::poses::CPoseInterpolatorBase<2>::loadFromTextFile_TUM, "C++: mrpt::poses::CPoseInterpolatorBase<2>::loadFromTextFile_TUM(const std::string &) --> bool", pybind11::arg("s")); cl.def("getBoundingBox", (void (mrpt::poses::CPoseInterpolatorBase<2>::*)(struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &) const) &mrpt::poses::CPoseInterpolatorBase<2>::getBoundingBox, "C++: mrpt::poses::CPoseInterpolatorBase<2>::getBoundingBox(struct mrpt::math::TPoint2D_ &, struct mrpt::math::TPoint2D_ &) const --> void", pybind11::arg("minCorner"), pybind11::arg("maxCorner")); cl.def("setInterpolationMethod", (void (mrpt::poses::CPoseInterpolatorBase<2>::*)(enum mrpt::poses::TInterpolatorMethod)) &mrpt::poses::CPoseInterpolatorBase<2>::setInterpolationMethod, "C++: mrpt::poses::CPoseInterpolatorBase<2>::setInterpolationMethod(enum mrpt::poses::TInterpolatorMethod) --> void", pybind11::arg("method")); cl.def("getInterpolationMethod", (enum mrpt::poses::TInterpolatorMethod (mrpt::poses::CPoseInterpolatorBase<2>::*)() const) &mrpt::poses::CPoseInterpolatorBase<2>::getInterpolationMethod, "C++: mrpt::poses::CPoseInterpolatorBase<2>::getInterpolationMethod() const --> enum mrpt::poses::TInterpolatorMethod"); @@ -93,8 +95,10 @@ void bind_mrpt_poses_CPoseInterpolatorBase(std::function< pybind11::module &(std cl.def("getPreviousPoseWithMinDistance", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const mrpt::Clock::time_point &, double, struct mrpt::math::TPose3D &)) &mrpt::poses::CPoseInterpolatorBase<3>::getPreviousPoseWithMinDistance, "C++: mrpt::poses::CPoseInterpolatorBase<3>::getPreviousPoseWithMinDistance(const mrpt::Clock::time_point &, double, struct mrpt::math::TPose3D &) --> bool", pybind11::arg("t"), pybind11::arg("distance"), pybind11::arg("out_pose")); cl.def("getPreviousPoseWithMinDistance", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const mrpt::Clock::time_point &, double, class mrpt::poses::CPose3D &)) &mrpt::poses::CPoseInterpolatorBase<3>::getPreviousPoseWithMinDistance, "C++: mrpt::poses::CPoseInterpolatorBase<3>::getPreviousPoseWithMinDistance(const mrpt::Clock::time_point &, double, class mrpt::poses::CPose3D &) --> bool", pybind11::arg("t"), pybind11::arg("distance"), pybind11::arg("out_pose")); cl.def("saveToTextFile", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const std::string &) const) &mrpt::poses::CPoseInterpolatorBase<3>::saveToTextFile, "C++: mrpt::poses::CPoseInterpolatorBase<3>::saveToTextFile(const std::string &) const --> bool", pybind11::arg("s")); + cl.def("saveToTextFile_TUM", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const std::string &) const) &mrpt::poses::CPoseInterpolatorBase<3>::saveToTextFile_TUM, "C++: mrpt::poses::CPoseInterpolatorBase<3>::saveToTextFile_TUM(const std::string &) const --> bool", pybind11::arg("s")); cl.def("saveInterpolatedToTextFile", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const std::string &, const struct std::chrono::duration> &) const) &mrpt::poses::CPoseInterpolatorBase<3>::saveInterpolatedToTextFile, "C++: mrpt::poses::CPoseInterpolatorBase<3>::saveInterpolatedToTextFile(const std::string &, const struct std::chrono::duration> &) const --> bool", pybind11::arg("s"), pybind11::arg("period")); cl.def("loadFromTextFile", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const std::string &)) &mrpt::poses::CPoseInterpolatorBase<3>::loadFromTextFile, "C++: mrpt::poses::CPoseInterpolatorBase<3>::loadFromTextFile(const std::string &) --> bool", pybind11::arg("s")); + cl.def("loadFromTextFile_TUM", (bool (mrpt::poses::CPoseInterpolatorBase<3>::*)(const std::string &)) &mrpt::poses::CPoseInterpolatorBase<3>::loadFromTextFile_TUM, "C++: mrpt::poses::CPoseInterpolatorBase<3>::loadFromTextFile_TUM(const std::string &) --> bool", pybind11::arg("s")); cl.def("getBoundingBox", (void (mrpt::poses::CPoseInterpolatorBase<3>::*)(struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &) const) &mrpt::poses::CPoseInterpolatorBase<3>::getBoundingBox, "C++: mrpt::poses::CPoseInterpolatorBase<3>::getBoundingBox(struct mrpt::math::TPoint3D_ &, struct mrpt::math::TPoint3D_ &) const --> void", pybind11::arg("minCorner"), pybind11::arg("maxCorner")); cl.def("setInterpolationMethod", (void (mrpt::poses::CPoseInterpolatorBase<3>::*)(enum mrpt::poses::TInterpolatorMethod)) &mrpt::poses::CPoseInterpolatorBase<3>::setInterpolationMethod, "C++: mrpt::poses::CPoseInterpolatorBase<3>::setInterpolationMethod(enum mrpt::poses::TInterpolatorMethod) --> void", pybind11::arg("method")); cl.def("getInterpolationMethod", (enum mrpt::poses::TInterpolatorMethod (mrpt::poses::CPoseInterpolatorBase<3>::*)() const) &mrpt::poses::CPoseInterpolatorBase<3>::getInterpolationMethod, "C++: mrpt::poses::CPoseInterpolatorBase<3>::getInterpolationMethod() const --> enum mrpt::poses::TInterpolatorMethod"); diff --git a/python/src/pymrpt.cpp b/python/src/pymrpt.cpp index b7e61382cf..9bc222edb2 100644 --- a/python/src/pymrpt.cpp +++ b/python/src/pymrpt.cpp @@ -177,11 +177,12 @@ void bind_mrpt_obs_CObservationStereoImages(std::function< pybind11::module &(st void bind_mrpt_vision_CStereoRectifyMap(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_hwdrivers_CDUO3DCamera(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CMatrixDynamic(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CMatrixFixed(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CMatrixFixed_1(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CMatrixFixed_2(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CMatrixFixed_3(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_mrpt_math_CMatrixFixed_4(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_math_MatrixVectorBase(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_math_frwds(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_bayes_CProbabilityParticle_1(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_math_CMatrixF(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -233,7 +234,7 @@ void bind_mrpt_kinematics_CKinematicChain(std::function< pybind11::module &(std: void bind_mrpt_kinematics_CVehicleVelCmd(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_kinematics_CVehicleVelCmd_DiffDriven(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_poses_CPointPDF(std::function< pybind11::module &(std::string const &namespace_) > &M); -void bind_mrpt_math_CMatrixDynamic_1(std::function< pybind11::module &(std::string const &namespace_) > &M); +void bind_mrpt_math_CMatrixDynamic_2(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_poses_CPointPDFSOG(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_maps_CBeacon(std::function< pybind11::module &(std::string const &namespace_) > &M); void bind_mrpt_opengl_COctoMapVoxels(std::function< pybind11::module &(std::string const &namespace_) > &M); @@ -606,11 +607,12 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_vision_CStereoRectifyMap(M); bind_mrpt_hwdrivers_CDUO3DCamera(M); bind_mrpt_math_CMatrixDynamic(M); + bind_mrpt_math_CMatrixDynamic_1(M); bind_mrpt_math_CMatrixFixed(M); bind_mrpt_math_CMatrixFixed_1(M); bind_mrpt_math_CMatrixFixed_2(M); bind_mrpt_math_CMatrixFixed_3(M); - bind_mrpt_math_CMatrixFixed_4(M); + bind_mrpt_math_MatrixVectorBase(M); bind_mrpt_math_math_frwds(M); bind_mrpt_bayes_CProbabilityParticle_1(M); bind_mrpt_math_CMatrixF(M); @@ -662,7 +664,7 @@ PYBIND11_MODULE(pymrpt, root_module) { bind_mrpt_kinematics_CVehicleVelCmd(M); bind_mrpt_kinematics_CVehicleVelCmd_DiffDriven(M); bind_mrpt_poses_CPointPDF(M); - bind_mrpt_math_CMatrixDynamic_1(M); + bind_mrpt_math_CMatrixDynamic_2(M); bind_mrpt_poses_CPointPDFSOG(M); bind_mrpt_maps_CBeacon(M); bind_mrpt_opengl_COctoMapVoxels(M); diff --git a/python/src/pymrpt.sources b/python/src/pymrpt.sources index 293c3ffab3..5015a1f833 100644 --- a/python/src/pymrpt.sources +++ b/python/src/pymrpt.sources @@ -167,11 +167,12 @@ mrpt/obs/CObservationStereoImages.cpp mrpt/vision/CStereoRectifyMap.cpp mrpt/hwdrivers/CDUO3DCamera.cpp mrpt/math/CMatrixDynamic.cpp +mrpt/math/CMatrixDynamic_1.cpp mrpt/math/CMatrixFixed.cpp mrpt/math/CMatrixFixed_1.cpp mrpt/math/CMatrixFixed_2.cpp mrpt/math/CMatrixFixed_3.cpp -mrpt/math/CMatrixFixed_4.cpp +mrpt/math/MatrixVectorBase.cpp mrpt/math/math_frwds.cpp mrpt/bayes/CProbabilityParticle_1.cpp mrpt/math/CMatrixF.cpp @@ -223,7 +224,7 @@ mrpt/kinematics/CKinematicChain.cpp mrpt/kinematics/CVehicleVelCmd.cpp mrpt/kinematics/CVehicleVelCmd_DiffDriven.cpp mrpt/poses/CPointPDF.cpp -mrpt/math/CMatrixDynamic_1.cpp +mrpt/math/CMatrixDynamic_2.cpp mrpt/poses/CPointPDFSOG.cpp mrpt/maps/CBeacon.cpp mrpt/opengl/COctoMapVoxels.cpp diff --git a/version_prefix.txt b/version_prefix.txt index 94ecf1513d..c74d20affc 100644 --- a/version_prefix.txt +++ b/version_prefix.txt @@ -1,4 +1,4 @@ -2.11.3 +2.11.4 # 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