Class CSimpleMap

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public mrpt::serialization::CSerializable

Class Documentation

class CSimpleMap : public mrpt::serialization::CSerializable

A view-based map: a set of poses and what the robot saw from those poses.

A simplemap comprises a sequence of tuples, each containing:

  • The keyframe SE(3) pose of the robot, including (optionally) its uncertainty, as instances of mrpt::poses::CPose3DPDF

  • The raw observations from that keyframe, in a mrpt::obs::CSensoryFrame

  • Optionally, the twist (linear and angular velocity) of the robot in the local frame of reference, at that moment. It can be used to undistort data from a rotatory lidar, for example.

To generate an actual metric map (occupancy grid, point cloud, octomap, etc.) from a “simple map”, the user must instantiate the desired metric map class(es) and invoke its virtual method mrpt::maps::CMetricMap::loadFromSimpleMap().

Users can also use the new top-level library mp2p_icp_filters and its CLI application sm2mm (simple-map to metric-map) to generate metric maps including pre-processing of raw data in a flexible way.

To programatically change an existing simplemap, use the non-const get() method and modify the returned reference.

Copy constructor and copy operator makes shallow copies of all data. A makeDeepCopy() method is also provided which duplicates all internal data, if really needed.

Note

Objects of this class are serialized into GZ-compressed files with the extension .simplemap. See Robotics file formats.

Iterators API

using KeyframeList = std::deque<Keyframe>
using const_iterator = KeyframeList::const_iterator
using iterator = KeyframeList::iterator
using reverse_iterator = KeyframeList::reverse_iterator
using const_reverse_iterator = KeyframeList::const_reverse_iterator
inline const_iterator begin() const
inline const_iterator end() const
inline const_iterator cbegin() const
inline const_iterator cend() const
inline iterator begin()
inline iterator end()
inline const_reverse_iterator rbegin() const
inline const_reverse_iterator rend() const
inline const_reverse_iterator crbegin() const
inline const_reverse_iterator crend() const
inline reverse_iterator rbegin()
inline reverse_iterator rend()

Map access and modification

bool saveToFile(const std::string &filName, const mrpt::io::CompressionOptions &co = {mrpt::io::CompressionType::Zstd}) const

Save this object to a .simplemap binary file (compressed with gzip) See Robotics file formats.

See also

loadFromFile()

Returns:

false on any error.

bool loadFromFile(const std::string &filName)

Load the contents of this object from a .simplemap binary file (possibly compressed with gzip) See Robotics file formats.

See also

saveToFile()

Returns:

false on any error.

inline size_t size() const

Returns the number of keyframes in the map

inline bool empty() const

Returns size()!=0

inline const Keyframe &get(size_t index) const

const accessor

inline Keyframe &get(size_t index)

non-const accessor, returning a reference suitable for modification

void remove(size_t index)

Deletes the 0-based index i’th keyframe.

See also

insert, get, set

Throws:

std::exception – On index out of bounds.

void insert(const Keyframe &kf)

Adds a new keyframe (SE(3) pose) to the view-based map. Both shared pointers are copied (shallow object copies).

inline void insert(const mrpt::poses::CPose3DPDF::Ptr &in_posePDF, const mrpt::obs::CSensoryFrame::Ptr &in_SF, const std::optional<mrpt::math::TTwist3D> &twist = std::nullopt)

Adds a new keyframe (SE(3) pose) to the view-based map. Both shared pointers are copied (shallow object copies).

inline void clear()

Remove all stored keyframes.

See also

remove

void changeCoordinatesOrigin(const mrpt::poses::CPose3D &newOrigin)

Change the coordinate origin of all stored poses, that is, translates and rotates the map such that the old SE(3) origin (identity transformation) becomes the new provided one.

Public Functions

CSimpleMap() = default

Default ctor: empty map.

~CSimpleMap() = default
CSimpleMap makeDeepCopy()

makes a deep copy of all data

struct Keyframe

Public Functions

Keyframe() = default
~Keyframe() = default
inline Keyframe(const mrpt::poses::CPose3DPDF::Ptr &kfPose, const mrpt::obs::CSensoryFrame::Ptr &kfSf, const std::optional<mrpt::math::TTwist3D> &kflocalTwist = std::nullopt)

Public Members

mrpt::poses::CPose3DPDF::Ptr pose
mrpt::obs::CSensoryFrame::Ptr sf

raw observations

std::optional<mrpt::math::TTwist3D> localTwist