Skip to content

Commit

Permalink
docs fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Mar 19, 2022
1 parent 4434b20 commit 2fd5ffa
Show file tree
Hide file tree
Showing 8 changed files with 147 additions and 123 deletions.
125 changes: 125 additions & 0 deletions doc/source/doxygen-docs/maps-observations.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
\page maps_observations Maps and observations compatibility matrices

There exists many kinds of metric maps and observations in MRPT, but some operations
involving a map and an observation (for example "inserting" an observation in a map to update it)
only make sense for a small subset of map-observation combinations.

See:

- List of all observations: see derived classes from mrpt::obs::CObservation
- List of all metric maps: see derived classes from mrpt::maps::CMetricMap

The following tables summarize the valid combinations, as implemented so far:

# Valid implementations of insertObservation()

List of observations and the metric maps in which mrpt::maps::CMetricMaps::insertObservation() is
implemented for them:

- mrpt::obs::CObservation2DRangeScan
- mrpt::maps::CColouredOctoMap
- mrpt::maps::CHeightGridMap2D
- mrpt::maps::CHeightGridMap2D_MRF
- mrpt::maps::COccupancyGridMap2D
- mrpt::maps::COctoMap
- mrpt::maps::CPointsMap (any derived map)
- mrpt::obs::CObservation3DRangeScan
- mrpt::maps::CColouredOctoMap
- mrpt::maps::COctoMap
- mrpt::maps::CPointsMap (any derived map)
- mrpt::obs::CObservation6DFeatures
- (none)
- mrpt::obs::CObservationBeaconRanges
- mrpt::maps::CBeaconMap (see [RO-SLAM](http://www.mrpt.org/tutorials/slam-algorithms/rangeonly_slam/)) |
- mrpt::obs::CObservationBearingRange
- (none)
- mrpt::obs::CObservationGasSensors
- mrpt::maps::CGasConcentrationGridMap2D
- mrpt::obs::CObservationGPS
- (none)
- mrpt::obs::CObservationImage
- mrpt::maps::CLandmarksMap (Extract SIFT feats)
- mrpt::obs::CObservationIMU
- (none)
- mrpt::obs::CObservationOdometry
- (none)
- mrpt::obs::CObservationPointCloud
- mrpt::maps::CPointsMap (any derived map)
- mrpt::obs::CObservationRange
- mrpt::maps::CPointsMap (any derived map)
- mrpt::maps::COccupancyGridMap2D
- mrpt::obs::CObservationReflectivity
- mrpt::maps::CReflectivityGridMap2D
- mrpt::obs::CObservationRFID
- (none)
- mrpt::obs::CObservationRGBD360
- (none)
- mrpt::obs::CObservationRobotPose
- (none)
- mrpt::obs::CObservationStereoImages
- mrpt::maps::CLandmarksMap (Extract SIFT feats)
- mrpt::obs::CObservationStereoImagesFeatures
- mrpt::maps::CLandmarksMap (Append/fuse landmarks)
- mrpt::obs::CObservationVelodyneScan
- mrpt::maps::CPointsMap (any derived map), mrpt::maps::CHeightGridMap2D, mrpt::maps::CHeightGridMap2D_MRF |
- mrpt::obs::CObservationWindSensor
- (none)
- mrpt::obs::CObservationWirelessPower
- mrpt::maps::CWirelessPowerGridMap2D

# Valid implementations of computeObservationLikelihood()

Next follows the list of observations and the metric maps in which mrpt::maps::CMetricMaps::computeObservationLikelihood() is
implemented for them. That means that, for example, particle filter algorithms can use
those observations to localize a robot in the corresponding map, fusing the information from many sources if several
observation-map pairs are valid for a given robot.

- mrpt::obs::CObservation2DRangeScan
- mrpt::maps::CColouredOctoMap
- mrpt::maps::CPointsMap (any derived map)
- mrpt::maps::COccupancyGridMap2D
- mrpt::maps::COctoMap
- mrpt::maps::CLandmarksMap
- mrpt::obs::CObservation3DRangeScan
- mrpt::maps::CColouredOctoMap and mrpt::maps::COctoMap (must have pointcloud)
- mrpt::obs::CObservation6DFeatures
- (none)
- mrpt::obs::CObservationBeaconRanges
- mrpt::maps::CBeaconMap (Used for SLAM)
- mrpt::maps::CLandmarksMap (Used for localization-only)
- mrpt::obs::CObservationBearingRange
- (none, but check out the EKF-SLAM algorithms)
- mrpt::obs::CObservationGasSensors
- (none...check?)
- mrpt::obs::CObservationGPS
- mrpt::maps::CLandmarksMap (NMEA GGA datum)
- mrpt::obs::CObservationImage
- (none)
- mrpt::obs::CObservationIMU
- (none)
- mrpt::obs::CObservationOdometry
- (none, but it is explicitly used by most SLAM algorithms)
- mrpt::obs::CObservationPointCloud
- mrpt::maps::CPointsMap (any derived map)
- mrpt::maps::CColouredOctoMap & mrpt::maps::COctoMap
- mrpt::obs::CObservationRange
- (none)
- mrpt::obs::CObservationReflectivity
- mrpt::maps::CReflectivityGridMap2D
- mrpt::obs::CObservationRFID
- (none)
- mrpt::obs::CObservationRGBD360
- (none)
- mrpt::obs::CObservationRobotPose
- mrpt::maps::CLandmarksMap
- mrpt::obs::CObservationStereoImages
- mrpt::maps::CLandmarksMap (Convert to SIFT features)
- mrpt::obs::CObservationStereoImagesFeatures
- (none)
- mrpt::obs::CObservationVelodyneScan
- mrpt::maps::CPointsMap (any derived map)
- mrpt::maps::CColouredOctoMap & mrpt::maps::COctoMap
- mrpt::obs::CObservationWindSensor
- (none)
- mrpt::obs::CObservationWirelessPower
- (none)
2 changes: 1 addition & 1 deletion doc/source/mrpt_from_cmake.rst
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ or individually like:
For MRPT 1.x
-------------------------

Prior to MRPT 2.0.0, the correct way to find for MRPT was:
Prior to MRPT 2.0.0, the correct way to search for MRPT was:

.. code-block:: cmake
Expand Down
102 changes: 0 additions & 102 deletions doc/source/tutorial-maps-observations.rst

This file was deleted.

2 changes: 1 addition & 1 deletion doc/source/tutorials.rst
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ Note: This page is in the process of being imported from https://www.mrpt.org/tu
tutorial-mrpt-maps-model
range_only_localization_mapping
tutorial-icp-alignment
tutorial-maps-observations
page_maps_observations

.. toctree::
:maxdepth: 2
Expand Down
2 changes: 1 addition & 1 deletion libs/graphslam/include/mrpt/graphslam/CGraphSlamEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ class CGraphSlamEngine : public mrpt::system::COutputLogger
* interacting with the display window
* \param[in] rawlog_fname .rawlog dataset file, containing the robot
* measurements. CGraphSlamEngine supports both
* <a href="http://www.mrpt.org/Rawlog_Format"> MRPT rwalog formats </a>
* <a href="rawlog_format.html">MRPT rawlog formats</a>
* but in order for graphSLAM to work as expected the rawlog foromat has to
* be supported by the every decider/optimizer class that
* CGraphSlamEngine makes use of.
Expand Down
14 changes: 7 additions & 7 deletions libs/obs/include/mrpt/maps/CMetricMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ namespace mrpt::maps
*will NOT raise an event, inserting a laser scan will).
*
* To check what observations are supported by each metric map, see
* [Maps-observations matrix](tutorial-maps-observations.html).
* \ref maps_observations.
*
* \note All derived class must implement a static class factory
*`<metric_map_class>::MapDefinition()` that builds a default
Expand Down Expand Up @@ -116,7 +116,7 @@ class CMetricMap : public mrpt::serialization::CSerializable,

/** Insert the observation information into this map. This method must be
* implemented in derived classes.
* See: [Maps-observations matrix](tutorial-maps-observations.html)
* See: \ref maps_observations
*
* \param obs The observation
* \param robotPose The 3D pose of the robot mobile base in the map
Expand All @@ -130,15 +130,15 @@ class CMetricMap : public mrpt::serialization::CSerializable,
std::nullopt);

/** A wrapper for smart pointers, just calls the non-smart pointer version.
* See: [Maps-observations matrix](tutorial-maps-observations.html) */
* See: \ref maps_observations */
bool insertObservationPtr(
const mrpt::obs::CObservation::Ptr& obs,
const std::optional<const mrpt::poses::CPose3D>& robotPose =
std::nullopt);

/** Computes the log-likelihood of a given observation given an arbitrary
* robot 3D pose.
* See: [Maps-observations matrix](tutorial-maps-observations.html)
* See: \ref maps_observations
*
* \param takenFrom The robot's pose the observation is supposed to be taken
* from.
Expand All @@ -154,7 +154,7 @@ class CMetricMap : public mrpt::serialization::CSerializable,
/** Returns true if this map is able to compute a sensible likelihood
* function for this observation (i.e. an occupancy grid map cannot with an
* image).
* See: [Maps-observations matrix](tutorial-maps-observations.html)
* See: \ref maps_observations
*
* \param obs The observation.
* \sa computeObservationLikelihood,
Expand All @@ -165,7 +165,7 @@ class CMetricMap : public mrpt::serialization::CSerializable,

/** Returns the sum of the log-likelihoods of each individual observation
* within a mrpt::obs::CSensoryFrame.
* See: [Maps-observations matrix](tutorial-maps-observations.html)
* See: \ref maps_observations
*
* \param takenFrom The robot's pose the observation is supposed to be taken
* from.
Expand All @@ -180,7 +180,7 @@ class CMetricMap : public mrpt::serialization::CSerializable,
/** Returns true if this map is able to compute a sensible likelihood
* function for this observation (i.e. an occupancy grid map cannot with an
* image).
* See: [Maps-observations matrix](tutorial-maps-observations.html)
* See: \ref maps_observations
*
* \param sf The observations.
* \sa canComputeObservationLikelihood
Expand Down
12 changes: 5 additions & 7 deletions libs/obs/include/mrpt/obs/CObservation.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,9 @@
#include <mrpt/serialization/CSerializable.h>
#include <mrpt/system/datetime.h>

namespace mrpt
{
/** This namespace contains representation of robot actions and observations */
namespace obs
/** This namespace contains representation of robot actions and observations
* \ingroup mrpt_obs_grp */
namespace mrpt::obs
{
/** Used for CObservationBeaconRange, CBeacon, etc. \ingroup mrpt_obs_grp */
static constexpr int INVALID_BEACON_ID = -1;
Expand Down Expand Up @@ -97,7 +96,7 @@ class CObservation : public mrpt::serialization::CSerializable,
* has nothing to do with a metric map (for example, a sound
*observation).
*
* See: [Maps-observations matrix](tutorial-maps-observations.html)
* See: \ref maps_observations
*
* \sa CMetricMap, CMetricMap::insertObservation
*/
Expand Down Expand Up @@ -207,5 +206,4 @@ class CObservation : public mrpt::serialization::CSerializable,

}; // End of class def.

} // namespace obs
} // namespace mrpt
} // namespace mrpt::obs
11 changes: 7 additions & 4 deletions libs/obs/include/mrpt/obs/CObservationOdometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,13 @@
namespace mrpt::obs
{
/** An observation of the current (cumulative) odometry for a wheeled robot.
* This kind of observation will only occur in a "observation-only" rawlog
* file, otherwise
* odometry are modeled with actions. Refer to the <a
* href="http://www.mrpt.org/Rawlog_Format">page on rawlogs</a>.
* This provides the relative pose of the robot with respect to the `odom`
* frame of reference, in "ROS parlance".
*
* This kind of observation more naturally fits the "observation-only" rawlog
* format, since odometry increments are normally used in "sensory-frame based" datasets.
* However, the user is free to use them whenever it is useful.
* Refer to the [rawlog format description](rawlog_format.html).
*
* \sa CObservation, CActionRobotMovement2D
* \ingroup mrpt_obs_grp
Expand Down

0 comments on commit 2fd5ffa

Please sign in to comment.