diff --git a/apps/robot-map-gui/gui/configWidget/CConfigWidget.cpp b/apps/robot-map-gui/gui/configWidget/CConfigWidget.cpp index 256e150f50..67cbb40f93 100644 --- a/apps/robot-map-gui/gui/configWidget/CConfigWidget.cpp +++ b/apps/robot-map-gui/gui/configWidget/CConfigWidget.cpp @@ -211,11 +211,11 @@ TSetOfMetricMapInitializers CConfigWidget::config() for (auto& map : it.second) { const std::string sMapName = map->getName().toStdString(); - TMetricMapInitializer* mi = mmr.factoryMapDefinition(sMapName); + auto mi = mmr.factoryMapDefinition(sMapName); ASSERT_(mi); - map->updateConfiguration(mi); - mapCfg.push_back(TMetricMapInitializer::Ptr(mi)); + map->updateConfiguration(mi.get()); + mapCfg.push_back(mi); ++index; } } diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 5c6ecd830a..66566c450e 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -10,6 +10,7 @@ - mrpt::maps::COccupancyGridMap2D - mrpt::maps::COccupancyGridMap2D - New virtual method mrpt::maps::CMetricMap::boundingBox() + - mrpt::maps::TMetricMapInitializer now returns `shared_ptr`s instead of plain pointers. - \ref mrpt_core_grp - Add the `[[nodiscard]]` attribute to all functions returning a value in `` diff --git a/libs/maps/src/maps/CBeaconMap.cpp b/libs/maps/src/maps/CBeaconMap.cpp index ca1c97db2d..3d7070f010 100644 --- a/libs/maps/src/maps/CBeaconMap.cpp +++ b/libs/maps/src/maps/CBeaconMap.cpp @@ -69,12 +69,12 @@ void CBeaconMap::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CBeaconMap::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CBeaconMap::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CBeaconMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CBeaconMap(); + auto obj = CBeaconMap::Create(); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CColouredOctoMap.cpp b/libs/maps/src/maps/CColouredOctoMap.cpp index cf9e126176..21167dc569 100644 --- a/libs/maps/src/maps/CColouredOctoMap.cpp +++ b/libs/maps/src/maps/CColouredOctoMap.cpp @@ -68,12 +68,12 @@ void CColouredOctoMap::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CColouredOctoMap::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CColouredOctoMap::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CColouredOctoMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CColouredOctoMap(def.resolution); + auto obj = CColouredOctoMap::Create(def.resolution); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CColouredPointsMap.cpp b/libs/maps/src/maps/CColouredPointsMap.cpp index c2a0ab3a57..1a2f8f4279 100644 --- a/libs/maps/src/maps/CColouredPointsMap.cpp +++ b/libs/maps/src/maps/CColouredPointsMap.cpp @@ -55,12 +55,13 @@ void CColouredPointsMap::TMapDefinition::dumpToTextStream_map_specific( this->colourOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CColouredPointsMap::internal_CreateFromMapDefinition( - const mrpt::maps::TMetricMapInitializer& _def) +mrpt::maps::CMetricMap::Ptr + CColouredPointsMap::internal_CreateFromMapDefinition( + const mrpt::maps::TMetricMapInitializer& _def) { const CColouredPointsMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CColouredPointsMap(); + auto obj = CColouredPointsMap::Create(); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; obj->colorScheme = def.colourOpts; diff --git a/libs/maps/src/maps/CGasConcentrationGridMap2D.cpp b/libs/maps/src/maps/CGasConcentrationGridMap2D.cpp index 74d5e3753b..29619ef3c3 100644 --- a/libs/maps/src/maps/CGasConcentrationGridMap2D.cpp +++ b/libs/maps/src/maps/CGasConcentrationGridMap2D.cpp @@ -80,13 +80,13 @@ void CGasConcentrationGridMap2D::TMapDefinition::dumpToTextStream_map_specific( this->insertionOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* +mrpt::maps::CMetricMap::Ptr CGasConcentrationGridMap2D::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CGasConcentrationGridMap2D::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CGasConcentrationGridMap2D( + auto obj = CGasConcentrationGridMap2D::Create( def.mapType, def.min_x, def.max_x, def.min_y, def.max_y, def.resolution); obj->insertionOptions = def.insertionOpts; diff --git a/libs/maps/src/maps/CHeightGridMap2D.cpp b/libs/maps/src/maps/CHeightGridMap2D.cpp index 0534e04c51..c9212cb793 100644 --- a/libs/maps/src/maps/CHeightGridMap2D.cpp +++ b/libs/maps/src/maps/CHeightGridMap2D.cpp @@ -70,12 +70,12 @@ void CHeightGridMap2D::TMapDefinition::dumpToTextStream_map_specific( this->insertionOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CHeightGridMap2D::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CHeightGridMap2D::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CHeightGridMap2D::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CHeightGridMap2D( + auto obj = CHeightGridMap2D::Create( def.mapType, def.min_x, def.max_x, def.min_y, def.max_y, def.resolution); obj->insertionOptions = def.insertionOpts; diff --git a/libs/maps/src/maps/CHeightGridMap2D_MRF.cpp b/libs/maps/src/maps/CHeightGridMap2D_MRF.cpp index ad208dcc60..da72444657 100644 --- a/libs/maps/src/maps/CHeightGridMap2D_MRF.cpp +++ b/libs/maps/src/maps/CHeightGridMap2D_MRF.cpp @@ -66,12 +66,13 @@ void CHeightGridMap2D_MRF::TMapDefinition::dumpToTextStream_map_specific( this->insertionOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CHeightGridMap2D_MRF::internal_CreateFromMapDefinition( - const mrpt::maps::TMetricMapInitializer& _def) +mrpt::maps::CMetricMap::Ptr + CHeightGridMap2D_MRF::internal_CreateFromMapDefinition( + const mrpt::maps::TMetricMapInitializer& _def) { const CHeightGridMap2D_MRF::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CHeightGridMap2D_MRF( + auto obj = CHeightGridMap2D_MRF::Create( def.mapType, def.min_x, def.max_x, def.min_y, def.max_y, def.resolution, def.run_map_estimation_at_ctor); obj->insertionOptions = def.insertionOpts; diff --git a/libs/maps/src/maps/CMultiMetricMap.cpp b/libs/maps/src/maps/CMultiMetricMap.cpp index 24ee56c873..da7d0433aa 100644 --- a/libs/maps/src/maps/CMultiMetricMap.cpp +++ b/libs/maps/src/maps/CMultiMetricMap.cpp @@ -123,7 +123,7 @@ void CMultiMetricMap::setListOfMaps(const TSetOfMetricMapInitializers& inits) for (const auto& i : inits) { // Create map from the list of all params: - auto* theMap = mmr.factoryMapObjectFromDefinition(*i.get()); + auto theMap = mmr.factoryMapObjectFromDefinition(*i.get()); ASSERT_(theMap); // Add to the list of maps: this->maps.emplace_back(theMap); diff --git a/libs/maps/src/maps/COccupancyGridMap2D_common.cpp b/libs/maps/src/maps/COccupancyGridMap2D_common.cpp index 185358bc0f..6ef5ae0cc4 100644 --- a/libs/maps/src/maps/COccupancyGridMap2D_common.cpp +++ b/libs/maps/src/maps/COccupancyGridMap2D_common.cpp @@ -69,12 +69,13 @@ void COccupancyGridMap2D::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* COccupancyGridMap2D::internal_CreateFromMapDefinition( - const mrpt::maps::TMetricMapInitializer& _def) +mrpt::maps::CMetricMap::Ptr + COccupancyGridMap2D::internal_CreateFromMapDefinition( + const mrpt::maps::TMetricMapInitializer& _def) { const COccupancyGridMap2D::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new COccupancyGridMap2D( + auto obj = COccupancyGridMap2D::Create( def.min_x, def.max_x, def.min_y, def.max_y, def.resolution); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; diff --git a/libs/maps/src/maps/COccupancyGridMap3D.cpp b/libs/maps/src/maps/COccupancyGridMap3D.cpp index 88af2bced9..8f32de28bc 100644 --- a/libs/maps/src/maps/COccupancyGridMap3D.cpp +++ b/libs/maps/src/maps/COccupancyGridMap3D.cpp @@ -63,11 +63,12 @@ void COccupancyGridMap3D::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* COccupancyGridMap3D::internal_CreateFromMapDefinition( - const mrpt::maps::TMetricMapInitializer& _def) +mrpt::maps::CMetricMap::Ptr + COccupancyGridMap3D::internal_CreateFromMapDefinition( + const mrpt::maps::TMetricMapInitializer& _def) { auto& def = dynamic_cast(_def); - auto* obj = new COccupancyGridMap3D( + auto obj = COccupancyGridMap3D::Create( mrpt::math::TPoint3D(def.min_x, def.min_y, def.min_z), mrpt::math::TPoint3D(def.max_x, def.max_y, def.max_z), def.resolution); obj->insertionOptions = def.insertionOpts; diff --git a/libs/maps/src/maps/COctoMap.cpp b/libs/maps/src/maps/COctoMap.cpp index 6ce25f846a..d86f6de1f5 100644 --- a/libs/maps/src/maps/COctoMap.cpp +++ b/libs/maps/src/maps/COctoMap.cpp @@ -60,12 +60,12 @@ void COctoMap::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* COctoMap::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr COctoMap::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const COctoMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new COctoMap(def.resolution); + auto obj = COctoMap::Create(def.resolution); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CPointsMapXYZI.cpp b/libs/maps/src/maps/CPointsMapXYZI.cpp index 47212a6273..ad18ee6321 100644 --- a/libs/maps/src/maps/CPointsMapXYZI.cpp +++ b/libs/maps/src/maps/CPointsMapXYZI.cpp @@ -56,12 +56,12 @@ void CPointsMapXYZI::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CPointsMapXYZI::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CPointsMapXYZI::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CPointsMapXYZI::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CPointsMapXYZI(); + auto obj = CPointsMapXYZI::Create(); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CReflectivityGridMap2D.cpp b/libs/maps/src/maps/CReflectivityGridMap2D.cpp index 81154e3b7c..315c50ac09 100644 --- a/libs/maps/src/maps/CReflectivityGridMap2D.cpp +++ b/libs/maps/src/maps/CReflectivityGridMap2D.cpp @@ -65,13 +65,13 @@ void CReflectivityGridMap2D::TMapDefinition::dumpToTextStream_map_specific( this->insertionOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* +mrpt::maps::CMetricMap::Ptr CReflectivityGridMap2D::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CReflectivityGridMap2D::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CReflectivityGridMap2D( + auto obj = CReflectivityGridMap2D::Create( def.min_x, def.max_x, def.min_y, def.max_y, def.resolution); obj->insertionOptions = def.insertionOpts; return obj; diff --git a/libs/maps/src/maps/CSimplePointsMap.cpp b/libs/maps/src/maps/CSimplePointsMap.cpp index 38ed822245..6f213c80b8 100644 --- a/libs/maps/src/maps/CSimplePointsMap.cpp +++ b/libs/maps/src/maps/CSimplePointsMap.cpp @@ -43,12 +43,12 @@ void CSimplePointsMap::TMapDefinition::dumpToTextStream_map_specific( this->renderOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CSimplePointsMap::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CSimplePointsMap::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CSimplePointsMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CSimplePointsMap(); + auto obj = CSimplePointsMap::Create(); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; obj->renderOptions = def.renderOpts; diff --git a/libs/maps/src/maps/CVoxelMap.cpp b/libs/maps/src/maps/CVoxelMap.cpp index dadea25917..6472c359ff 100644 --- a/libs/maps/src/maps/CVoxelMap.cpp +++ b/libs/maps/src/maps/CVoxelMap.cpp @@ -45,12 +45,12 @@ void CVoxelMap::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CVoxelMap::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CVoxelMap::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CVoxelMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CVoxelMap(def.resolution); + auto obj = CVoxelMap::Create(def.resolution); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CVoxelMapRGB.cpp b/libs/maps/src/maps/CVoxelMapRGB.cpp index 7b65b584c5..95ad5c9871 100644 --- a/libs/maps/src/maps/CVoxelMapRGB.cpp +++ b/libs/maps/src/maps/CVoxelMapRGB.cpp @@ -47,12 +47,12 @@ void CVoxelMapRGB::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CVoxelMapRGB::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CVoxelMapRGB::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CVoxelMapRGB::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CVoxelMapRGB(def.resolution); + auto obj = CVoxelMapRGB::Create(def.resolution); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CWeightedPointsMap.cpp b/libs/maps/src/maps/CWeightedPointsMap.cpp index a2bb117880..8a8671348c 100644 --- a/libs/maps/src/maps/CWeightedPointsMap.cpp +++ b/libs/maps/src/maps/CWeightedPointsMap.cpp @@ -45,12 +45,13 @@ void CWeightedPointsMap::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CWeightedPointsMap::internal_CreateFromMapDefinition( - const mrpt::maps::TMetricMapInitializer& _def) +mrpt::maps::CMetricMap::Ptr + CWeightedPointsMap::internal_CreateFromMapDefinition( + const mrpt::maps::TMetricMapInitializer& _def) { const CWeightedPointsMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CWeightedPointsMap(); + auto obj = CWeightedPointsMap::Create(); obj->insertionOptions = def.insertionOpts; obj->likelihoodOptions = def.likelihoodOpts; return obj; diff --git a/libs/maps/src/maps/CWirelessPowerGridMap2D.cpp b/libs/maps/src/maps/CWirelessPowerGridMap2D.cpp index 7fb1160506..017015fe50 100644 --- a/libs/maps/src/maps/CWirelessPowerGridMap2D.cpp +++ b/libs/maps/src/maps/CWirelessPowerGridMap2D.cpp @@ -67,13 +67,13 @@ void CWirelessPowerGridMap2D::TMapDefinition::dumpToTextStream_map_specific( this->insertionOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* +mrpt::maps::CMetricMap::Ptr CWirelessPowerGridMap2D::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CWirelessPowerGridMap2D::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CWirelessPowerGridMap2D( + auto obj = CWirelessPowerGridMap2D::Create( def.mapType, def.min_x, def.max_x, def.min_y, def.max_y, def.resolution); obj->insertionOptions = def.insertionOpts; diff --git a/libs/obs/include/mrpt/maps/TMetricMapInitializer.h b/libs/obs/include/mrpt/maps/TMetricMapInitializer.h index 77c2e18364..bd03f10aa6 100644 --- a/libs/obs/include/mrpt/maps/TMetricMapInitializer.h +++ b/libs/obs/include/mrpt/maps/TMetricMapInitializer.h @@ -64,7 +64,7 @@ struct TMetricMapInitializer : public mrpt::config::CLoadableOptions /** Looks up in the registry of known map types and call the corresponding * `::MapDefinition()`. */ - static TMetricMapInitializer* factory(const std::string& mapClassName); + static Ptr factory(const std::string& mapClassName); protected: TMetricMapInitializer(const mrpt::rtti::TRuntimeClassId* classID); @@ -97,7 +97,7 @@ class TSetOfMetricMapInitializers : public mrpt::config::CLoadableOptions template void push_back(const MAP_DEFINITION& o) { - m_list.push_back(TMetricMapInitializer::Ptr(new MAP_DEFINITION(o))); + m_list.push_back(std::make_shared(o)); } void push_back(const TMetricMapInitializer::Ptr& o) { m_list.push_back(o); } diff --git a/libs/obs/include/mrpt/maps/TMetricMapTypesRegistry.h b/libs/obs/include/mrpt/maps/TMetricMapTypesRegistry.h index 890476b845..8be37572db 100644 --- a/libs/obs/include/mrpt/maps/TMetricMapTypesRegistry.h +++ b/libs/obs/include/mrpt/maps/TMetricMapTypesRegistry.h @@ -13,6 +13,7 @@ #include #include +#include #include namespace mrpt @@ -23,9 +24,10 @@ struct TMetricMapInitializer; namespace internal { using MapDefCtorFunctor = - std::function; -using MapCtorFromDefFunctor = std::function; + std::function(void)>; +using MapCtorFromDefFunctor = + std::function( + const mrpt::maps::TMetricMapInitializer&)>; /** Class factory & registry for map classes. Used from * mrpt::maps::TMetricMapInitializer */ @@ -38,14 +40,30 @@ struct TMetricMapTypesRegistry size_t doRegister( const std::string& name, MapDefCtorFunctor func1, MapCtorFromDefFunctor func2); + /** Return nullptr if not found */ - mrpt::maps::TMetricMapInitializer* factoryMapDefinition( + std::shared_ptr factoryMapDefinition( const std::string& className) const; + /** Return nullptr if not found */ - mrpt::maps::CMetricMap* factoryMapObjectFromDefinition( + std::shared_ptr factoryMapObjectFromDefinition( const mrpt::maps::TMetricMapInitializer& mi) const; - using TListRegisteredMaps = std::map< - std::string, std::pair>; + + struct InfoPerMapClass + { + InfoPerMapClass() = default; + InfoPerMapClass( + const MapDefCtorFunctor& DefCtor, + const MapCtorFromDefFunctor& MapCtor) + : defCtor(DefCtor), mapCtor(MapCtor) + { + } + + MapDefCtorFunctor defCtor; + MapCtorFromDefFunctor mapCtor; + }; + + using TListRegisteredMaps = std::map; const TListRegisteredMaps& getAllRegistered() const { return m_registry; } private: @@ -78,13 +96,14 @@ struct TMetricMapTypesRegistry ; \ /** Returns default map definition initializer. See \ * mrpt::maps::TMetricMapInitializer */ \ - static mrpt::maps::TMetricMapInitializer* MapDefinition(); \ + static std::shared_ptr MapDefinition(); \ /** Constructor from a map definition structure: initializes the map and \ * its parameters accordingly */ \ - static _CLASS_NAME_* CreateFromMapDefinition( \ - const mrpt::maps::TMetricMapInitializer& def); \ - static mrpt::maps::CMetricMap* internal_CreateFromMapDefinition( \ + static std::shared_ptr<_CLASS_NAME_> CreateFromMapDefinition( \ const mrpt::maps::TMetricMapInitializer& def); \ + static std::shared_ptr \ + internal_CreateFromMapDefinition( \ + const mrpt::maps::TMetricMapInitializer& def); \ /** ID used to initialize class registration (just ignore it) */ \ static const size_t m_private_map_register_id; \ /** @} */ @@ -97,17 +116,18 @@ struct TMetricMapTypesRegistry mrpt::maps::internal::TMetricMapTypesRegistry::Instance().doRegister( \ _CLASSNAME_STRINGS, &_CLASSNAME_WITH_NS::MapDefinition, \ &_CLASSNAME_WITH_NS::internal_CreateFromMapDefinition); \ - mrpt::maps::TMetricMapInitializer* _CLASSNAME_WITH_NS::MapDefinition() \ + std::shared_ptr \ + _CLASSNAME_WITH_NS::MapDefinition() \ { \ - return new _CLASSNAME_WITH_NS::TMapDefinition; \ + return std::make_shared<_CLASSNAME_WITH_NS::TMapDefinition>(); \ } \ - _CLASSNAME_WITH_NS* _CLASSNAME_WITH_NS::CreateFromMapDefinition( \ - const mrpt::maps::TMetricMapInitializer& def) \ + std::shared_ptr<_CLASSNAME_WITH_NS> \ + _CLASSNAME_WITH_NS::CreateFromMapDefinition( \ + const mrpt::maps::TMetricMapInitializer& def) \ { \ - return dynamic_cast<_CLASSNAME_WITH_NS*>( \ + return std::dynamic_pointer_cast<_CLASSNAME_WITH_NS>( \ _CLASSNAME_WITH_NS::internal_CreateFromMapDefinition(def)); \ } - } // namespace internal } // namespace maps } // namespace mrpt diff --git a/libs/obs/src/TMetricMapInitializer.cpp b/libs/obs/src/TMetricMapInitializer.cpp index 7789874e49..b0a662664c 100644 --- a/libs/obs/src/TMetricMapInitializer.cpp +++ b/libs/obs/src/TMetricMapInitializer.cpp @@ -19,7 +19,7 @@ using namespace mrpt::maps; /** Looks up in the registry of known map types and call the corresponding * `::MapDefinition()`. */ -TMetricMapInitializer* TMetricMapInitializer::factory( +TMetricMapInitializer::Ptr TMetricMapInitializer::factory( const std::string& mapClassName) { using mrpt::maps::internal::TMetricMapTypesRegistry; @@ -72,6 +72,7 @@ void TSetOfMetricMapInitializers::loadFromConfigFile( MRPT_START using mrpt::maps::internal::TMetricMapTypesRegistry; + using namespace std::string_literals; // Delete previous contents: clear(); @@ -86,10 +87,10 @@ void TSetOfMetricMapInitializers::loadFromConfigFile( const std::string sMapName = allMapKind.first; unsigned int n = - ini.read_uint64_t(sectionName, sMapName + string("_count"), 0); + ini.read_uint64_t(sectionName, sMapName + "_count"s, 0); for (unsigned int i = 0; i < n; i++) { - TMetricMapInitializer* mi = mmr.factoryMapDefinition(sMapName); + TMetricMapInitializer::Ptr mi = mmr.factoryMapDefinition(sMapName); ASSERT_(mi); // Load from sections formatted like this: @@ -103,7 +104,7 @@ void TSetOfMetricMapInitializers::loadFromConfigFile( mi->loadFromConfigFile(ini, sMapSectionsPrefix); // Add the params to the list: - this->push_back(TMetricMapInitializer::Ptr(mi)); + this->push_back(mi); } } // end for each map kind diff --git a/libs/obs/src/TMetricMapTypesRegistry.cpp b/libs/obs/src/TMetricMapTypesRegistry.cpp index bff5a65244..f4604a018b 100644 --- a/libs/obs/src/TMetricMapTypesRegistry.cpp +++ b/libs/obs/src/TMetricMapTypesRegistry.cpp @@ -45,16 +45,15 @@ size_t TMetricMapTypesRegistry::doRegister( mrpt::system::tokenize(names, " \t\r\n,", lstNames); for (const auto& lstName : lstNames) { - const auto p = std::make_pair(func1, func2); - m_registry[lstName] = p; + m_registry[lstName] = {func1, func2}; // register also the version without the "mrpt::NS::" prefix, for // backwards compatibility: - m_registry[stripNamespace(lstName)] = p; + m_registry[stripNamespace(lstName)] = {func1, func2}; } return m_registry.size(); } -mrpt::maps::TMetricMapInitializer* +mrpt::maps::TMetricMapInitializer::Ptr TMetricMapTypesRegistry::factoryMapDefinition( const std::string& className) const { @@ -64,12 +63,13 @@ mrpt::maps::TMetricMapInitializer* if (it == m_registry.end()) it = m_registry.find(stripNamespace(className)); if (it == m_registry.end()) return nullptr; - ASSERT_(it->second.first); - return (it->second.first)(); + ASSERT_(it->second.defCtor); + return (it->second.defCtor)(); } -mrpt::maps::CMetricMap* TMetricMapTypesRegistry::factoryMapObjectFromDefinition( - const mrpt::maps::TMetricMapInitializer& mi) const +mrpt::maps::CMetricMap::Ptr + TMetricMapTypesRegistry::factoryMapObjectFromDefinition( + const mrpt::maps::TMetricMapInitializer& mi) const { auto it = m_registry.find(mi.getMetricMapClassType()->className); if (it == m_registry.end()) @@ -80,8 +80,8 @@ mrpt::maps::CMetricMap* TMetricMapTypesRegistry::factoryMapObjectFromDefinition( mi.getMetricMapClassType()->className); } - ASSERT_(it->second.second); - mrpt::maps::CMetricMap* theMap = (it->second.second)(mi); + ASSERT_(it->second.mapCtor); + mrpt::maps::CMetricMap::Ptr theMap = (it->second.mapCtor)(mi); // Common params for all maps: theMap->genericMapParams = mi.genericMapParams; diff --git a/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h b/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h index 6a76f6011d..ca3c4572e2 100644 --- a/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h +++ b/libs/poses/include/mrpt/poses/CPose3DQuatPDF.h @@ -59,7 +59,7 @@ class CPose3DQuatPDF * anymore. * \sa copyFrom */ - static CPose3DQuatPDF* createFrom2D(const CPosePDF& o); + static CPose3DQuatPDF::Ptr createFrom2D(const CPosePDF& o); /** Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF */ virtual void inverse(CPose3DQuatPDF& o) const = 0; diff --git a/libs/poses/src/CPose3DQuatPDF.cpp b/libs/poses/src/CPose3DQuatPDF.cpp index cafddb5c27..2caa18789d 100644 --- a/libs/poses/src/CPose3DQuatPDF.cpp +++ b/libs/poses/src/CPose3DQuatPDF.cpp @@ -25,14 +25,14 @@ IMPLEMENTS_VIRTUAL_SERIALIZABLE(CPose3DQuatPDF, CSerializable, mrpt::poses) /*--------------------------------------------------------------- copyFrom2D ---------------------------------------------------------------*/ -CPose3DQuatPDF* CPose3DQuatPDF::createFrom2D(const CPosePDF& o) +CPose3DQuatPDF::Ptr CPose3DQuatPDF::createFrom2D(const CPosePDF& o) { MRPT_START CPose3DPDFGaussian q; q.copyFrom(o); - return new CPose3DQuatPDFGaussian(q); + return std::make_shared(q); MRPT_END } diff --git a/libs/rtti/src/rtti_unittest.cpp b/libs/rtti/src/rtti_unittest.cpp index d31b040b62..4e67237407 100644 --- a/libs/rtti/src/rtti_unittest.cpp +++ b/libs/rtti/src/rtti_unittest.cpp @@ -64,7 +64,7 @@ TEST(rtti, MyDerived1_CLASSID) // RTTI IS_DERIVED(*) { - auto p = mrpt::rtti::CObject::Ptr(new MyNS::MyDerived1); + auto p = mrpt::rtti::CObject::Ptr(std::make_shared()); EXPECT_TRUE(IS_DERIVED(*p, MyNS::MyDerived1)); EXPECT_TRUE(IS_DERIVED(*p, mrpt::rtti::CObject)); } diff --git a/libs/serialization/include/mrpt/serialization/CArchive.h b/libs/serialization/include/mrpt/serialization/CArchive.h index 31d67dabab..ea4a5863fd 100644 --- a/libs/serialization/include/mrpt/serialization/CArchive.h +++ b/libs/serialization/include/mrpt/serialization/CArchive.h @@ -568,7 +568,7 @@ CArchive& operator>>(CArchive& in, std::shared_ptr& pObj) else { ASSERT_EQUAL_(expected_name, stored_name); - pObj.reset(new T); + pObj = std::make_shared(); in >> *pObj; } return in; diff --git a/libs/vision/src/maps/CLandmarksMap.cpp b/libs/vision/src/maps/CLandmarksMap.cpp index 1943dea086..cf29137000 100644 --- a/libs/vision/src/maps/CLandmarksMap.cpp +++ b/libs/vision/src/maps/CLandmarksMap.cpp @@ -99,12 +99,12 @@ void CLandmarksMap::TMapDefinition::dumpToTextStream_map_specific( this->likelihoodOpts.dumpToTextStream(out); } -mrpt::maps::CMetricMap* CLandmarksMap::internal_CreateFromMapDefinition( +mrpt::maps::CMetricMap::Ptr CLandmarksMap::internal_CreateFromMapDefinition( const mrpt::maps::TMetricMapInitializer& _def) { const CLandmarksMap::TMapDefinition& def = *dynamic_cast(&_def); - auto* obj = new CLandmarksMap(); + auto obj = CLandmarksMap::Create(); for (const auto& initialBeacon : def.initialBeacons) { diff --git a/python/src/mrpt/maps/CBeacon.cpp b/python/src/mrpt/maps/CBeacon.cpp index fe6deb1367..18745ef11b 100644 --- a/python/src/mrpt/maps/CBeacon.cpp +++ b/python/src/mrpt/maps/CBeacon.cpp @@ -585,7 +585,7 @@ struct PyCallBack_mrpt_maps_CBeaconMap_TInsertionOptions : public mrpt::maps::CB } }; -// mrpt::maps::CBeaconMap::TMapDefinition file: line:67 +// mrpt::maps::CBeaconMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CBeaconMap_TMapDefinition : public mrpt::maps::CBeaconMap::TMapDefinition { using mrpt::maps::CBeaconMap::TMapDefinition::TMapDefinition; @@ -737,12 +737,12 @@ void bind_mrpt_maps_CBeacon(std::function< pybind11::module &(std::string const cl.def("assign", (struct mrpt::maps::CBeaconMap::TInsertionOptions & (mrpt::maps::CBeaconMap::TInsertionOptions::*)(const struct mrpt::maps::CBeaconMap::TInsertionOptions &)) &mrpt::maps::CBeaconMap::TInsertionOptions::operator=, "C++: mrpt::maps::CBeaconMap::TInsertionOptions::operator=(const struct mrpt::maps::CBeaconMap::TInsertionOptions &) --> struct mrpt::maps::CBeaconMap::TInsertionOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CBeaconMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::CBeaconMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CBeaconMap::TMapDefinition file: line:67 + { // mrpt::maps::CBeaconMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CBeaconMap_TMapDefinition, mrpt::maps::CBeaconMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CBeaconMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CBeaconMap_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CColouredOctoMap.cpp b/python/src/mrpt/maps/CColouredOctoMap.cpp index 64fcaf132e..69357914cb 100644 --- a/python/src/mrpt/maps/CColouredOctoMap.cpp +++ b/python/src/mrpt/maps/CColouredOctoMap.cpp @@ -534,7 +534,7 @@ struct PyCallBack_mrpt_maps_CColouredOctoMap : public mrpt::maps::CColouredOctoM } }; -// mrpt::maps::CColouredOctoMap::TMapDefinition file: line:67 +// mrpt::maps::CColouredOctoMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CColouredOctoMap_TMapDefinition : public mrpt::maps::CColouredOctoMap::TMapDefinition { using mrpt::maps::CColouredOctoMap::TMapDefinition::TMapDefinition; @@ -1137,7 +1137,7 @@ struct PyCallBack_mrpt_maps_CColouredPointsMap_TColourOptions : public mrpt::map } }; -// mrpt::maps::CColouredPointsMap::TMapDefinition file: line:67 +// mrpt::maps::CColouredPointsMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CColouredPointsMap_TMapDefinition : public mrpt::maps::CColouredPointsMap::TMapDefinition { using mrpt::maps::CColouredPointsMap::TMapDefinition::TMapDefinition; @@ -1240,12 +1240,12 @@ void bind_mrpt_maps_CColouredOctoMap(std::function< pybind11::module &(std::stri cl.def("getClampingThresMaxLog", (float (mrpt::maps::CColouredOctoMap::*)() const) &mrpt::maps::CColouredOctoMap::getClampingThresMaxLog, "C++: mrpt::maps::CColouredOctoMap::getClampingThresMaxLog() const --> float"); cl.def("assign", (class mrpt::maps::CColouredOctoMap & (mrpt::maps::CColouredOctoMap::*)(const class mrpt::maps::CColouredOctoMap &)) &mrpt::maps::CColouredOctoMap::operator=, "C++: mrpt::maps::CColouredOctoMap::operator=(const class mrpt::maps::CColouredOctoMap &) --> class mrpt::maps::CColouredOctoMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::maps::CColouredOctoMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::CColouredOctoMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CColouredOctoMap::TMapDefinition file: line:67 + { // mrpt::maps::CColouredOctoMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CColouredOctoMap_TMapDefinition, mrpt::maps::CColouredOctoMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CColouredOctoMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CColouredOctoMap_TMapDefinition(); } ) ); @@ -1312,12 +1312,12 @@ void bind_mrpt_maps_CColouredOctoMap(std::function< pybind11::module &(std::stri cl.def("assign", (struct mrpt::maps::CColouredPointsMap::TColourOptions & (mrpt::maps::CColouredPointsMap::TColourOptions::*)(const struct mrpt::maps::CColouredPointsMap::TColourOptions &)) &mrpt::maps::CColouredPointsMap::TColourOptions::operator=, "C++: mrpt::maps::CColouredPointsMap::TColourOptions::operator=(const struct mrpt::maps::CColouredPointsMap::TColourOptions &) --> struct mrpt::maps::CColouredPointsMap::TColourOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CColouredPointsMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::CColouredPointsMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CColouredPointsMap::TMapDefinition file: line:67 + { // mrpt::maps::CColouredPointsMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CColouredPointsMap_TMapDefinition, mrpt::maps::CColouredPointsMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CColouredPointsMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CColouredPointsMap_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp b/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp index 8cb788b707..8c1dfcf1d9 100644 --- a/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp +++ b/python/src/mrpt/maps/CGasConcentrationGridMap2D.cpp @@ -508,7 +508,7 @@ struct PyCallBack_mrpt_maps_CGasConcentrationGridMap2D_TInsertionOptions : publi } }; -// mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition file: line:67 +// mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CGasConcentrationGridMap2D_TMapDefinition : public mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition { using mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition::TMapDefinition; @@ -625,12 +625,12 @@ void bind_mrpt_maps_CGasConcentrationGridMap2D(std::function< pybind11::module & cl.def("assign", (struct mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable & (mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable::*)(const struct mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable &)) &mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable::operator=, "C++: mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable::operator=(const struct mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable &) --> struct mrpt::maps::CGasConcentrationGridMap2D::TGaussianWindTable &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CGasConcentrationGridMap2D::TMapDefinitionBase file: line:62 + { // mrpt::maps::CGasConcentrationGridMap2D::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition file: line:67 + { // mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CGasConcentrationGridMap2D_TMapDefinition, mrpt::maps::CGasConcentrationGridMap2D::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CGasConcentrationGridMap2D::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CGasConcentrationGridMap2D_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp b/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp index b398b02b0c..6b186ccc6f 100644 --- a/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp +++ b/python/src/mrpt/maps/CHeightGridMap2D_Base.cpp @@ -583,7 +583,7 @@ struct PyCallBack_mrpt_maps_CHeightGridMap2D_TInsertionOptions : public mrpt::ma } }; -// mrpt::maps::CHeightGridMap2D::TMapDefinition file: line:67 +// mrpt::maps::CHeightGridMap2D::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CHeightGridMap2D_TMapDefinition : public mrpt::maps::CHeightGridMap2D::TMapDefinition { using mrpt::maps::CHeightGridMap2D::TMapDefinition::TMapDefinition; @@ -723,12 +723,12 @@ void bind_mrpt_maps_CHeightGridMap2D_Base(std::function< pybind11::module &(std: cl.def("assign", (struct mrpt::maps::CHeightGridMap2D::TInsertionOptions & (mrpt::maps::CHeightGridMap2D::TInsertionOptions::*)(const struct mrpt::maps::CHeightGridMap2D::TInsertionOptions &)) &mrpt::maps::CHeightGridMap2D::TInsertionOptions::operator=, "C++: mrpt::maps::CHeightGridMap2D::TInsertionOptions::operator=(const struct mrpt::maps::CHeightGridMap2D::TInsertionOptions &) --> struct mrpt::maps::CHeightGridMap2D::TInsertionOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CHeightGridMap2D::TMapDefinitionBase file: line:62 + { // mrpt::maps::CHeightGridMap2D::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CHeightGridMap2D::TMapDefinition file: line:67 + { // mrpt::maps::CHeightGridMap2D::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CHeightGridMap2D_TMapDefinition, mrpt::maps::CHeightGridMap2D::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CHeightGridMap2D::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CHeightGridMap2D_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp b/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp index 12c3dbf64b..9ad25e11dc 100644 --- a/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp +++ b/python/src/mrpt/maps/CHeightGridMap2D_MRF.cpp @@ -587,7 +587,7 @@ struct PyCallBack_mrpt_maps_CHeightGridMap2D_MRF_TInsertionOptions : public mrpt } }; -// mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition file: line:67 +// mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CHeightGridMap2D_MRF_TMapDefinition : public mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition { using mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition::TMapDefinition; @@ -677,12 +677,12 @@ void bind_mrpt_maps_CHeightGridMap2D_MRF(std::function< pybind11::module &(std:: cl.def("assign", (struct mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions & (mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::*)(const struct mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions &)) &mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::operator=, "C++: mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions::operator=(const struct mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions &) --> struct mrpt::maps::CHeightGridMap2D_MRF::TInsertionOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CHeightGridMap2D_MRF::TMapDefinitionBase file: line:62 + { // mrpt::maps::CHeightGridMap2D_MRF::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition file: line:67 + { // mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CHeightGridMap2D_MRF_TMapDefinition, mrpt::maps::CHeightGridMap2D_MRF::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CHeightGridMap2D_MRF::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CHeightGridMap2D_MRF_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CLandmarksMap.cpp b/python/src/mrpt/maps/CLandmarksMap.cpp index 9bd68adfab..5a5dc8fcb9 100644 --- a/python/src/mrpt/maps/CLandmarksMap.cpp +++ b/python/src/mrpt/maps/CLandmarksMap.cpp @@ -390,7 +390,7 @@ struct PyCallBack_mrpt_maps_CLandmarksMap_TLikelihoodOptions : public mrpt::maps } }; -// mrpt::maps::CLandmarksMap::TMapDefinition file: line:67 +// mrpt::maps::CLandmarksMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CLandmarksMap_TMapDefinition : public mrpt::maps::CLandmarksMap::TMapDefinition { using mrpt::maps::CLandmarksMap::TMapDefinition::TMapDefinition; @@ -583,12 +583,12 @@ void bind_mrpt_maps_CLandmarksMap(std::function< pybind11::module &(std::string cl.def("assign", (struct mrpt::maps::CLandmarksMap::TFuseOptions & (mrpt::maps::CLandmarksMap::TFuseOptions::*)(const struct mrpt::maps::CLandmarksMap::TFuseOptions &)) &mrpt::maps::CLandmarksMap::TFuseOptions::operator=, "C++: mrpt::maps::CLandmarksMap::TFuseOptions::operator=(const struct mrpt::maps::CLandmarksMap::TFuseOptions &) --> struct mrpt::maps::CLandmarksMap::TFuseOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CLandmarksMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::CLandmarksMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CLandmarksMap::TMapDefinition file: line:67 + { // mrpt::maps::CLandmarksMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CLandmarksMap_TMapDefinition, mrpt::maps::CLandmarksMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CLandmarksMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CLandmarksMap_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/COccupancyGridMap2D.cpp b/python/src/mrpt/maps/COccupancyGridMap2D.cpp index f9ff15c651..e6e7c25944 100644 --- a/python/src/mrpt/maps/COccupancyGridMap2D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap2D.cpp @@ -453,7 +453,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap2D_TLikelihoodOptions : public mrpt } }; -// mrpt::maps::COccupancyGridMap2D::TMapDefinition file: line:67 +// mrpt::maps::COccupancyGridMap2D::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_COccupancyGridMap2D_TMapDefinition : public mrpt::maps::COccupancyGridMap2D::TMapDefinition { using mrpt::maps::COccupancyGridMap2D::TMapDefinition::TMapDefinition; @@ -769,12 +769,12 @@ void bind_mrpt_maps_COccupancyGridMap2D(std::function< pybind11::module &(std::s cl.def("assign", (struct mrpt::maps::COccupancyGridMap2D::TCriticalPointsList & (mrpt::maps::COccupancyGridMap2D::TCriticalPointsList::*)(const struct mrpt::maps::COccupancyGridMap2D::TCriticalPointsList &)) &mrpt::maps::COccupancyGridMap2D::TCriticalPointsList::operator=, "C++: mrpt::maps::COccupancyGridMap2D::TCriticalPointsList::operator=(const struct mrpt::maps::COccupancyGridMap2D::TCriticalPointsList &) --> struct mrpt::maps::COccupancyGridMap2D::TCriticalPointsList &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::COccupancyGridMap2D::TMapDefinitionBase file: line:62 + { // mrpt::maps::COccupancyGridMap2D::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::COccupancyGridMap2D::TMapDefinition file: line:67 + { // mrpt::maps::COccupancyGridMap2D::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_COccupancyGridMap2D_TMapDefinition, mrpt::maps::COccupancyGridMap2D::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::COccupancyGridMap2D::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_COccupancyGridMap2D_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/COccupancyGridMap3D.cpp b/python/src/mrpt/maps/COccupancyGridMap3D.cpp index 579c80a3c5..7a271082ac 100644 --- a/python/src/mrpt/maps/COccupancyGridMap3D.cpp +++ b/python/src/mrpt/maps/COccupancyGridMap3D.cpp @@ -446,7 +446,7 @@ struct PyCallBack_mrpt_maps_COccupancyGridMap3D_TLikelihoodOptions : public mrpt } }; -// mrpt::maps::COccupancyGridMap3D::TMapDefinition file: line:67 +// mrpt::maps::COccupancyGridMap3D::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_COccupancyGridMap3D_TMapDefinition : public mrpt::maps::COccupancyGridMap3D::TMapDefinition { using mrpt::maps::COccupancyGridMap3D::TMapDefinition::TMapDefinition; @@ -598,12 +598,12 @@ void bind_mrpt_maps_COccupancyGridMap3D(std::function< pybind11::module &(std::s cl.def("assign", (struct mrpt::maps::COccupancyGridMap3D::TRenderingOptions & (mrpt::maps::COccupancyGridMap3D::TRenderingOptions::*)(const struct mrpt::maps::COccupancyGridMap3D::TRenderingOptions &)) &mrpt::maps::COccupancyGridMap3D::TRenderingOptions::operator=, "C++: mrpt::maps::COccupancyGridMap3D::TRenderingOptions::operator=(const struct mrpt::maps::COccupancyGridMap3D::TRenderingOptions &) --> struct mrpt::maps::COccupancyGridMap3D::TRenderingOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::COccupancyGridMap3D::TMapDefinitionBase file: line:62 + { // mrpt::maps::COccupancyGridMap3D::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::COccupancyGridMap3D::TMapDefinition file: line:67 + { // mrpt::maps::COccupancyGridMap3D::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_COccupancyGridMap3D_TMapDefinition, mrpt::maps::COccupancyGridMap3D::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::COccupancyGridMap3D::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_COccupancyGridMap3D_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/COctoMap.cpp b/python/src/mrpt/maps/COctoMap.cpp index aaf6de25a4..67a8016c31 100644 --- a/python/src/mrpt/maps/COctoMap.cpp +++ b/python/src/mrpt/maps/COctoMap.cpp @@ -533,7 +533,7 @@ struct PyCallBack_mrpt_maps_COctoMap : public mrpt::maps::COctoMap { } }; -// mrpt::maps::COctoMap::TMapDefinition file: line:67 +// mrpt::maps::COctoMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_COctoMap_TMapDefinition : public mrpt::maps::COctoMap::TMapDefinition { using mrpt::maps::COctoMap::TMapDefinition::TMapDefinition; @@ -1136,7 +1136,7 @@ struct PyCallBack_mrpt_maps_CSimplePointsMap : public mrpt::maps::CSimplePointsM } }; -// mrpt::maps::CSimplePointsMap::TMapDefinition file: line:67 +// mrpt::maps::CSimplePointsMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CSimplePointsMap_TMapDefinition : public mrpt::maps::CSimplePointsMap::TMapDefinition { using mrpt::maps::CSimplePointsMap::TMapDefinition::TMapDefinition; @@ -1228,12 +1228,12 @@ void bind_mrpt_maps_COctoMap(std::function< pybind11::module &(std::string const cl.def("getClampingThresMaxLog", (float (mrpt::maps::COctoMap::*)() const) &mrpt::maps::COctoMap::getClampingThresMaxLog, "C++: mrpt::maps::COctoMap::getClampingThresMaxLog() const --> float"); cl.def("assign", (class mrpt::maps::COctoMap & (mrpt::maps::COctoMap::*)(const class mrpt::maps::COctoMap &)) &mrpt::maps::COctoMap::operator=, "C++: mrpt::maps::COctoMap::operator=(const class mrpt::maps::COctoMap &) --> class mrpt::maps::COctoMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::maps::COctoMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::COctoMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::COctoMap::TMapDefinition file: line:67 + { // mrpt::maps::COctoMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_COctoMap_TMapDefinition, mrpt::maps::COctoMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::COctoMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_COctoMap_TMapDefinition(); } ) ); @@ -1282,12 +1282,12 @@ void bind_mrpt_maps_COctoMap(std::function< pybind11::module &(std::string const cl.def("insertPointFast", (void (mrpt::maps::CSimplePointsMap::*)(float, float, float)) &mrpt::maps::CSimplePointsMap::insertPointFast, "The virtual method for *without* calling\n mark_as_modified() \n\nC++: mrpt::maps::CSimplePointsMap::insertPointFast(float, float, float) --> void", pybind11::arg("x"), pybind11::arg("y"), pybind11::arg("z")); cl.def("getAsSimplePointsMap", (const class mrpt::maps::CSimplePointsMap * (mrpt::maps::CSimplePointsMap::*)() const) &mrpt::maps::CSimplePointsMap::getAsSimplePointsMap, "@} \n\nC++: mrpt::maps::CSimplePointsMap::getAsSimplePointsMap() const --> const class mrpt::maps::CSimplePointsMap *", pybind11::return_value_policy::automatic); - { // mrpt::maps::CSimplePointsMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::CSimplePointsMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CSimplePointsMap::TMapDefinition file: line:67 + { // mrpt::maps::CSimplePointsMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CSimplePointsMap_TMapDefinition, mrpt::maps::CSimplePointsMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CSimplePointsMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CSimplePointsMap_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp index d4a317511a..53a2c31ed3 100644 --- a/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp +++ b/python/src/mrpt/maps/CPointCloudFilterByDistance.cpp @@ -674,7 +674,7 @@ struct PyCallBack_mrpt_maps_CPointsMapXYZI : public mrpt::maps::CPointsMapXYZI { } }; -// mrpt::maps::CPointsMapXYZI::TMapDefinition file: line:67 +// mrpt::maps::CPointsMapXYZI::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CPointsMapXYZI_TMapDefinition : public mrpt::maps::CPointsMapXYZI::TMapDefinition { using mrpt::maps::CPointsMapXYZI::TMapDefinition::TMapDefinition; @@ -780,12 +780,12 @@ void bind_mrpt_maps_CPointCloudFilterByDistance(std::function< pybind11::module cl.def("hasColorPoints", (bool (mrpt::maps::CPointsMapXYZI::*)() const) &mrpt::maps::CPointsMapXYZI::hasColorPoints, "Returns true if the point map has a color field for each point \n\nC++: mrpt::maps::CPointsMapXYZI::hasColorPoints() const --> bool"); cl.def("getVisualizationInto", (void (mrpt::maps::CPointsMapXYZI::*)(class mrpt::opengl::CSetOfObjects &) const) &mrpt::maps::CPointsMapXYZI::getVisualizationInto, "Override of the default 3D scene builder to account for the individual\n points' color.\n\nC++: mrpt::maps::CPointsMapXYZI::getVisualizationInto(class mrpt::opengl::CSetOfObjects &) const --> void", pybind11::arg("outObj")); - { // mrpt::maps::CPointsMapXYZI::TMapDefinitionBase file: line:62 + { // mrpt::maps::CPointsMapXYZI::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CPointsMapXYZI::TMapDefinition file: line:67 + { // mrpt::maps::CPointsMapXYZI::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CPointsMapXYZI_TMapDefinition, mrpt::maps::CPointsMapXYZI::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CPointsMapXYZI::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CPointsMapXYZI_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp index 918619c56d..8b5a2b8185 100644 --- a/python/src/mrpt/maps/CReflectivityGridMap2D.cpp +++ b/python/src/mrpt/maps/CReflectivityGridMap2D.cpp @@ -398,7 +398,7 @@ struct PyCallBack_mrpt_maps_CReflectivityGridMap2D_TInsertionOptions : public mr } }; -// mrpt::maps::CReflectivityGridMap2D::TMapDefinition file: line:67 +// mrpt::maps::CReflectivityGridMap2D::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CReflectivityGridMap2D_TMapDefinition : public mrpt::maps::CReflectivityGridMap2D::TMapDefinition { using mrpt::maps::CReflectivityGridMap2D::TMapDefinition::TMapDefinition; @@ -969,7 +969,7 @@ struct PyCallBack_mrpt_maps_CWeightedPointsMap : public mrpt::maps::CWeightedPoi } }; -// mrpt::maps::CWeightedPointsMap::TMapDefinition file: line:67 +// mrpt::maps::CWeightedPointsMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CWeightedPointsMap_TMapDefinition : public mrpt::maps::CWeightedPointsMap::TMapDefinition { using mrpt::maps::CWeightedPointsMap::TMapDefinition::TMapDefinition; @@ -1055,12 +1055,12 @@ void bind_mrpt_maps_CReflectivityGridMap2D(std::function< pybind11::module &(std cl.def("assign", (struct mrpt::maps::CReflectivityGridMap2D::TInsertionOptions & (mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::*)(const struct mrpt::maps::CReflectivityGridMap2D::TInsertionOptions &)) &mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::operator=, "C++: mrpt::maps::CReflectivityGridMap2D::TInsertionOptions::operator=(const struct mrpt::maps::CReflectivityGridMap2D::TInsertionOptions &) --> struct mrpt::maps::CReflectivityGridMap2D::TInsertionOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CReflectivityGridMap2D::TMapDefinitionBase file: line:62 + { // mrpt::maps::CReflectivityGridMap2D::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CReflectivityGridMap2D::TMapDefinition file: line:67 + { // mrpt::maps::CReflectivityGridMap2D::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CReflectivityGridMap2D_TMapDefinition, mrpt::maps::CReflectivityGridMap2D::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CReflectivityGridMap2D::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CReflectivityGridMap2D_TMapDefinition(); } ) ); @@ -1094,12 +1094,12 @@ void bind_mrpt_maps_CReflectivityGridMap2D(std::function< pybind11::module &(std 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("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:62 + { // mrpt::maps::CWeightedPointsMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CWeightedPointsMap::TMapDefinition file: line:67 + { // mrpt::maps::CWeightedPointsMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CWeightedPointsMap_TMapDefinition, mrpt::maps::CWeightedPointsMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CWeightedPointsMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CWeightedPointsMap_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CVoxelMap.cpp b/python/src/mrpt/maps/CVoxelMap.cpp index 60f6c61eaf..1ba095dce0 100644 --- a/python/src/mrpt/maps/CVoxelMap.cpp +++ b/python/src/mrpt/maps/CVoxelMap.cpp @@ -396,7 +396,7 @@ struct PyCallBack_mrpt_maps_CVoxelMap : public mrpt::maps::CVoxelMap { } }; -// mrpt::maps::CVoxelMap::TMapDefinition file: line:67 +// mrpt::maps::CVoxelMap::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CVoxelMap_TMapDefinition : public mrpt::maps::CVoxelMap::TMapDefinition { using mrpt::maps::CVoxelMap::TMapDefinition::TMapDefinition; @@ -746,7 +746,7 @@ struct PyCallBack_mrpt_maps_CVoxelMapRGB : public mrpt::maps::CVoxelMapRGB { } }; -// mrpt::maps::CVoxelMapRGB::TMapDefinition file: line:67 +// mrpt::maps::CVoxelMapRGB::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CVoxelMapRGB_TMapDefinition : public mrpt::maps::CVoxelMapRGB::TMapDefinition { using mrpt::maps::CVoxelMapRGB::TMapDefinition::TMapDefinition; @@ -814,12 +814,12 @@ void bind_mrpt_maps_CVoxelMap(std::function< pybind11::module &(std::string cons cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::maps::CVoxelMap::CreateObject, "C++: mrpt::maps::CVoxelMap::CreateObject() --> class std::shared_ptr"); cl.def("assign", (class mrpt::maps::CVoxelMap & (mrpt::maps::CVoxelMap::*)(const class mrpt::maps::CVoxelMap &)) &mrpt::maps::CVoxelMap::operator=, "C++: mrpt::maps::CVoxelMap::operator=(const class mrpt::maps::CVoxelMap &) --> class mrpt::maps::CVoxelMap &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::maps::CVoxelMap::TMapDefinitionBase file: line:62 + { // mrpt::maps::CVoxelMap::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CVoxelMap::TMapDefinition file: line:67 + { // mrpt::maps::CVoxelMap::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CVoxelMap_TMapDefinition, mrpt::maps::CVoxelMap::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CVoxelMap::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CVoxelMap_TMapDefinition(); } ) ); @@ -866,12 +866,12 @@ void bind_mrpt_maps_CVoxelMap(std::function< pybind11::module &(std::string cons cl.def_static("CreateObject", (class std::shared_ptr (*)()) &mrpt::maps::CVoxelMapRGB::CreateObject, "C++: mrpt::maps::CVoxelMapRGB::CreateObject() --> class std::shared_ptr"); cl.def("assign", (class mrpt::maps::CVoxelMapRGB & (mrpt::maps::CVoxelMapRGB::*)(const class mrpt::maps::CVoxelMapRGB &)) &mrpt::maps::CVoxelMapRGB::operator=, "C++: mrpt::maps::CVoxelMapRGB::operator=(const class mrpt::maps::CVoxelMapRGB &) --> class mrpt::maps::CVoxelMapRGB &", pybind11::return_value_policy::automatic, pybind11::arg("")); - { // mrpt::maps::CVoxelMapRGB::TMapDefinitionBase file: line:62 + { // mrpt::maps::CVoxelMapRGB::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CVoxelMapRGB::TMapDefinition file: line:67 + { // mrpt::maps::CVoxelMapRGB::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CVoxelMapRGB_TMapDefinition, mrpt::maps::CVoxelMapRGB::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CVoxelMapRGB::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CVoxelMapRGB_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp b/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp index 05c473597e..0f9d9bbd61 100644 --- a/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp +++ b/python/src/mrpt/maps/CWirelessPowerGridMap2D.cpp @@ -495,7 +495,7 @@ struct PyCallBack_mrpt_maps_CWirelessPowerGridMap2D_TInsertionOptions : public m } }; -// mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition file: line:67 +// mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition file: line:85 struct PyCallBack_mrpt_maps_CWirelessPowerGridMap2D_TMapDefinition : public mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition { using mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition::TMapDefinition; @@ -572,12 +572,12 @@ void bind_mrpt_maps_CWirelessPowerGridMap2D(std::function< pybind11::module &(st cl.def("assign", (struct mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions & (mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::*)(const struct mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions &)) &mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::operator=, "C++: mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions::operator=(const struct mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions &) --> struct mrpt::maps::CWirelessPowerGridMap2D::TInsertionOptions &", pybind11::return_value_policy::automatic, pybind11::arg("")); } - { // mrpt::maps::CWirelessPowerGridMap2D::TMapDefinitionBase file: line:62 + { // mrpt::maps::CWirelessPowerGridMap2D::TMapDefinitionBase file: line:80 auto & enclosing_class = cl; pybind11::class_> cl(enclosing_class, "TMapDefinitionBase", ""); } - { // mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition file: line:67 + { // mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition file: line:85 auto & enclosing_class = cl; pybind11::class_, PyCallBack_mrpt_maps_CWirelessPowerGridMap2D_TMapDefinition, mrpt::maps::CWirelessPowerGridMap2D::TMapDefinitionBase> cl(enclosing_class, "TMapDefinition", ""); cl.def( pybind11::init( [](){ return new mrpt::maps::CWirelessPowerGridMap2D::TMapDefinition(); }, [](){ return new PyCallBack_mrpt_maps_CWirelessPowerGridMap2D_TMapDefinition(); } ) ); diff --git a/python/src/mrpt/nav/planners/TMoveTree.cpp b/python/src/mrpt/nav/planners/TMoveTree.cpp index 4afdf81341..1370ac6c59 100644 --- a/python/src/mrpt/nav/planners/TMoveTree.cpp +++ b/python/src/mrpt/nav/planners/TMoveTree.cpp @@ -17,7 +17,6 @@ #include #include #include -#include #include #include #include @@ -42,7 +41,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/nav/reactive/CReactiveNavigationSystem3D.cpp b/python/src/mrpt/nav/reactive/CReactiveNavigationSystem3D.cpp index 3a2ea1fa42..b5633004de 100644 --- a/python/src/mrpt/nav/reactive/CReactiveNavigationSystem3D.cpp +++ b/python/src/mrpt/nav/reactive/CReactiveNavigationSystem3D.cpp @@ -19,7 +19,6 @@ #include #include #include -#include #include #include #include @@ -51,7 +50,6 @@ #include #include #include -#include #include #include #include diff --git a/python/src/mrpt/poses/CPose3DPDFSOG.cpp b/python/src/mrpt/poses/CPose3DPDFSOG.cpp index 168b9e1d1f..1a3582710c 100644 --- a/python/src/mrpt/poses/CPose3DPDFSOG.cpp +++ b/python/src/mrpt/poses/CPose3DPDFSOG.cpp @@ -682,7 +682,7 @@ void bind_mrpt_poses_CPose3DPDFSOG(std::function< pybind11::module &(std::string cl.def("GetRuntimeClass", (const struct mrpt::rtti::TRuntimeClassId * (mrpt::poses::CPose3DQuatPDF::*)() const) &mrpt::poses::CPose3DQuatPDF::GetRuntimeClass, "C++: mrpt::poses::CPose3DQuatPDF::GetRuntimeClass() const --> const struct mrpt::rtti::TRuntimeClassId *", pybind11::return_value_policy::automatic); cl.def_static("GetRuntimeClassIdStatic", (const struct mrpt::rtti::TRuntimeClassId & (*)()) &mrpt::poses::CPose3DQuatPDF::GetRuntimeClassIdStatic, "C++: mrpt::poses::CPose3DQuatPDF::GetRuntimeClassIdStatic() --> const struct mrpt::rtti::TRuntimeClassId &", pybind11::return_value_policy::automatic); cl.def("copyFrom", (void (mrpt::poses::CPose3DQuatPDF::*)(const class mrpt::poses::CPose3DQuatPDF &)) &mrpt::poses::CPose3DQuatPDF::copyFrom, "Copy operator, translating if necesary (for example, between particles\n and gaussian representations)\n \n\n createFrom2D\n\nC++: mrpt::poses::CPose3DQuatPDF::copyFrom(const class mrpt::poses::CPose3DQuatPDF &) --> void", pybind11::arg("o")); - cl.def_static("createFrom2D", (class mrpt::poses::CPose3DQuatPDF * (*)(const class mrpt::poses::CPosePDF &)) &mrpt::poses::CPose3DQuatPDF::createFrom2D, "This is a static transformation method from 2D poses to 3D PDFs,\n preserving the representation type (particles->particles,\n Gaussians->Gaussians,etc)\n It returns a new object of any of the derived classes of\n CPose3DQuatPDF. This object must be deleted by the user when not required\n anymore.\n \n\n copyFrom\n\nC++: mrpt::poses::CPose3DQuatPDF::createFrom2D(const class mrpt::poses::CPosePDF &) --> class mrpt::poses::CPose3DQuatPDF *", pybind11::return_value_policy::automatic, pybind11::arg("o")); + cl.def_static("createFrom2D", (class std::shared_ptr (*)(const class mrpt::poses::CPosePDF &)) &mrpt::poses::CPose3DQuatPDF::createFrom2D, "This is a static transformation method from 2D poses to 3D PDFs,\n preserving the representation type (particles->particles,\n Gaussians->Gaussians,etc)\n It returns a new object of any of the derived classes of\n CPose3DQuatPDF. This object must be deleted by the user when not required\n anymore.\n \n\n copyFrom\n\nC++: mrpt::poses::CPose3DQuatPDF::createFrom2D(const class mrpt::poses::CPosePDF &) --> class std::shared_ptr", pybind11::arg("o")); cl.def("inverse", (void (mrpt::poses::CPose3DQuatPDF::*)(class mrpt::poses::CPose3DQuatPDF &) const) &mrpt::poses::CPose3DQuatPDF::inverse, "Returns a new PDF such as: NEW_PDF = (0,0,0) - THIS_PDF \n\nC++: mrpt::poses::CPose3DQuatPDF::inverse(class mrpt::poses::CPose3DQuatPDF &) const --> void", pybind11::arg("o")); cl.def("changeCoordinatesReference", (void (mrpt::poses::CPose3DQuatPDF::*)(const class mrpt::poses::CPose3D &)) &mrpt::poses::CPose3DQuatPDF::changeCoordinatesReference, "C++: mrpt::poses::CPose3DQuatPDF::changeCoordinatesReference(const class mrpt::poses::CPose3D &) --> void", pybind11::arg("newReferenceBase")); cl.def_static("jacobiansPoseComposition", [](const class mrpt::poses::CPose3DQuat & a0, const class mrpt::poses::CPose3DQuat & a1, class mrpt::math::CMatrixFixed & a2, class mrpt::math::CMatrixFixed & a3) -> void { return mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(a0, a1, a2, a3); }, "", pybind11::arg("x"), pybind11::arg("u"), pybind11::arg("df_dx"), pybind11::arg("df_du"));