Go to the documentation of this file.
20 class TSetOfMetricMapInitializers;
155 template <
typename T>
158 size_t foundCount = 0;
159 const auto* class_ID = &T::GetRuntimeClassIdStatic();
160 for (
const auto& it : *
this)
161 if (it->GetRuntimeClass()->derivedFrom(class_ID))
162 if (foundCount++ == ith)
163 return std::dynamic_pointer_cast<T>(it.get_ptr());
164 return typename T::Ptr();
168 template <
typename T>
171 size_t foundCount = 0;
172 const auto* class_ID = &T::GetRuntimeClassIdStatic();
173 for (
const auto& it : *
this)
174 if (it->GetRuntimeClass()->derivedFrom(class_ID)) foundCount++;
208 const std::string& filNamePrefix)
const override;
T::Ptr mapByClass(size_t ith=0) const
Returns the i'th map of a given class (or of a derived class), or empty smart pointer if there is no ...
std::shared_ptr< mrpt::opengl ::CSetOfObjects > Ptr
void determineMatching2D(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose2D &otherMapPose, mrpt::tfest::TMatchingPairList &correspondences, const mrpt::maps::TMatchingParams ¶ms, mrpt::maps::TMatchingExtraResults &extraResults) const override
Computes the matching between this and another 2D point map, which includes finding:
#define DEFINE_SERIALIZABLE(class_name, NS)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
bool isEmpty() const override
Returns true if all maps returns true in their isEmpty() method.
void auxParticleFilterCleanUp() override
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::...
Parameters for CMetricMap::compute3DMatchingRatio()
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
bool internal_canComputeObservationLikelihood(const mrpt::obs::CObservation &obs) const override
Declares a virtual base class for all metric maps storage classes.
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle.
This class stores any customizable set of metric maps.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
float compute3DMatchingRatio(const mrpt::maps::CMetricMap *otherMap, const mrpt::poses::CPose3D &otherMapPose, const TMatchingRatioParams ¶ms) const override
Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map,...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans.
std::shared_ptr< CMetricMap > Ptr
mrpt::maps::CMetricMap::Ptr mapByIndex(size_t idx) const
Gets the i-th map \excepmapByIndextime_error On out-of-bounds.
mrpt::vision::TStereoCalibParams params
Parameters for the determination of matchings between point clouds, etc.
TListMaps maps
The list of metric maps in this object.
void internal_clear() override
Internal method called by clear()
void setListOfMaps(const mrpt::maps::TSetOfMetricMapInitializers &init)
Sets the list of internal map according to the passed list of map initializers (current maps will be ...
const_iterator end() const
std::deque< mrpt::containers::deepcopy_poly_ptr< mrpt::maps::CMetricMap::Ptr > > TListMaps
const_iterator begin() const
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >,...
TListMaps::iterator iterator
std::size_t countMapsByClass() const
Count how many maps exist of the given class (or derived class)
CMultiMetricMap()=default
Default ctor: empty list of maps.
Declares a class that represents any robot's observation.
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
TListMaps::const_iterator const_iterator
bool internal_insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr) override
Internal method called by insertObservation()
const mrpt::maps::CSimplePointsMap * getAsSimplePointsMap() const override
If the map is a simple points map or it's a multi-metric map that contains EXACTLY one simple points ...
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Sun Jul 19 15:15:43 UTC 2020 | |