This namespace contains algorithms for SLAM, localization, map building, representation of robot's actions and observations, and representation of many kinds of metric maps.
|
class | CAction |
| Declares a class for storing a robot action. More...
|
|
class | CActionCollection |
| Declares a class for storing a collection of robot actions. More...
|
|
struct | CActionCollectionPtr |
|
struct | CActionPtr |
|
class | CActionRobotMovement2D |
| Represents a probabilistic 2D movement of the robot mobile base. More...
|
|
struct | CActionRobotMovement2DPtr |
|
class | CActionRobotMovement3D |
| Represents a probabilistic 3D (6D) movement. More...
|
|
struct | CActionRobotMovement3DPtr |
|
class | CBeacon |
| The class for storing individual "beacon landmarks" under a variety of 3D position PDF distributions. More...
|
|
class | CBeaconMap |
| A class for storing a map of 3D probabilistic beacons, using a Montecarlo, Gaussian, or Sum of Gaussians (SOG) representation (for range-only SLAM). More...
|
|
struct | CBeaconMapPtr |
|
struct | CBeaconPtr |
|
class | CColouredOctoMap |
| A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ library. More...
|
|
struct | CColouredOctoMapPtr |
|
class | CColouredPointsMap |
| A map of 2D/3D points with individual colours (RGB). More...
|
|
struct | CColouredPointsMapPtr |
|
class | CDetectorDoorCrossing |
|
class | CGasConcentrationGridMap2D |
| CGasConcentrationGridMap2D represents a PDF of gas concentrations over a 2D area. More...
|
|
struct | CGasConcentrationGridMap2DPtr |
|
class | CGridMapAligner |
| A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching. More...
|
|
class | CHeightGridMap2D |
| A mesh representation of a surface which keeps the estimated height for each (x,y) location. More...
|
|
struct | CHeightGridMap2DPtr |
|
class | CICP |
| Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a point map wrt a grid map. More...
|
|
class | CIncrementalMapPartitioner |
| This class can be used to make partitions on a map/graph build from observations taken at some poses/nodes. More...
|
|
struct | CIncrementalMapPartitionerPtr |
|
class | CLandmark |
| The class for storing "landmarks" (visual or laser-scan-extracted features,...) More...
|
|
struct | CLandmarkPtr |
|
class | CLandmarksMap |
| A class for storing a map of 3D probabilistic landmarks. More...
|
|
struct | CLandmarksMapPtr |
|
struct | CLogOddsGridMap2D |
| A generic provider of log-odds grid-map maintainance functions. More...
|
|
struct | CLogOddsGridMapLUT |
| One static instance of this struct should exist in any class implementing CLogOddsGridMap2D to hold the Look-up-tables (LUTs) for log-odss Bayesian update. More...
|
|
class | CMetricMap |
| Declares a virtual base class for all metric maps storage classes. More...
|
|
class | CMetricMapBuilder |
| This virtual class is the base for SLAM implementations. More...
|
|
class | CMetricMapBuilderICP |
| A class for very simple 2D SLAM based on ICP. More...
|
|
class | CMetricMapBuilderRBPF |
| This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM). More...
|
|
struct | CMetricMapPtr |
|
class | CMetricMapsAlignmentAlgorithm |
| A base class for any algorithm able of maps alignment. More...
|
|
class | CMonteCarloLocalization2D |
| Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,y,phi), using a set of weighted samples. More...
|
|
class | CMonteCarloLocalization3D |
| Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x,y,phi,yaw,pitch,roll), using a set of weighted samples. More...
|
|
class | CMultiMetricMap |
| This class stores any customizable set of metric maps. More...
|
|
class | CMultiMetricMapPDF |
| Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (This class is the base of RBPF-SLAM applications). More...
|
|
struct | CMultiMetricMapPDFPtr |
|
struct | CMultiMetricMapPtr |
|
class | CObservation |
| Declares a class that represents any robot's observation. More...
|
|
class | CObservation2DRangeScan |
| A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser scanner). More...
|
|
struct | CObservation2DRangeScanPtr |
|
class | CObservation3DRangeScan |
| Declares a class derived from "CObservation" that encapsules a 3D range scan measurement (e.g. More...
|
|
struct | CObservation3DRangeScanPtr |
|
class | CObservationBatteryState |
| This represents a measurement of the batteries on the robot. More...
|
|
struct | CObservationBatteryStatePtr |
|
class | CObservationBeaconRanges |
| Declares a class derived from "CObservation" that represents one (or more) range measurements to labeled beacons. More...
|
|
struct | CObservationBeaconRangesPtr |
|
class | CObservationBearingRange |
| This observation represents a number of range-bearing value pairs, each one for a detected landmark, which optionally can have identification IDs. More...
|
|
struct | CObservationBearingRangePtr |
|
class | CObservationCANBusJ1939 |
| This class stores a message from a CAN BUS with the protocol J1939. More...
|
|
struct | CObservationCANBusJ1939Ptr |
|
class | CObservationComment |
| This "observation" is actually a placeholder for a text block with comments or additional parameters attached to a given rawlog file. More...
|
|
struct | CObservationCommentPtr |
|
class | CObservationGasSensors |
| Declares a class derived from "CObservation" that represents a set of readings from gas sensors. More...
|
|
struct | CObservationGasSensorsPtr |
|
class | CObservationGPS |
| Declares a class derived from "CObservation" that represents a Global Positioning System (GPS) reading. More...
|
|
struct | CObservationGPSPtr |
|
class | CObservationImage |
| Declares a class derived from "CObservation" that encapsules an image from a camera, whose relative pose to robot is also stored. More...
|
|
struct | CObservationImagePtr |
|
class | CObservationIMU |
| This class stores measurements from an Inertial Measurement Unit (IMU) (attitude estimation, raw gyroscope and accelerometer values), altimeters or magnetometers. More...
|
|
struct | CObservationIMUPtr |
|
class | CObservationOdometry |
| An observation of the current (cumulative) odometry for a wheeled robot. More...
|
|
struct | CObservationOdometryPtr |
|
struct | CObservationPtr |
|
class | CObservationRange |
| Declares a class derived from "CObservation" that encapsules a single range measurement, and associated parameters. More...
|
|
struct | CObservationRangePtr |
|
class | CObservationRawDAQ |
| Store raw data from a Data Acquisition (DAQ) device, such that input or output analog and digital channels, counters from encoders, etc. More...
|
|
struct | CObservationRawDAQPtr |
|
class | CObservationReflectivity |
| Declares a class derived from "CObservation" that encapsules a single short-range reflectivity measurement. More...
|
|
struct | CObservationReflectivityPtr |
|
class | CObservationRFID |
| This represents one or more RFID tags observed by a receiver. More...
|
|
struct | CObservationRFIDPtr |
|
class | CObservationStereoImages |
| Observation class for either a pair of left+right or left+disparity images from a stereo camera. More...
|
|
class | CObservationStereoImagesFeatures |
| Declares a class derived from "CObservation" that encapsules a pair of cameras and a set of matched image features extracted from them. More...
|
|
struct | CObservationStereoImagesFeaturesPtr |
|
struct | CObservationStereoImagesPtr |
|
class | CObservationVisualLandmarks |
| Declares a class derived from "CObservation" that stores a Landmarks Map as seen from a stereo camera at a given instant of time. More...
|
|
struct | CObservationVisualLandmarksPtr |
|
class | CObservationWindSensor |
| Declares a class derived from "CObservation" that represents the wind measurements taken on the robot by an anemometer. More...
|
|
struct | CObservationWindSensorPtr |
|
class | CObservationWirelessPower |
| This represents a measurement of the wireless strength perceived by the robot. More...
|
|
struct | CObservationWirelessPowerPtr |
|
class | COccupancyGridMap2D |
| A class for storing an occupancy grid map. More...
|
|
struct | COccupancyGridMap2DPtr |
|
class | COccupancyGridMapFeatureExtractor |
| A class for detecting features from occupancy grid maps. More...
|
|
class | COctoMap |
| A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ library. More...
|
|
class | COctoMapBase |
| A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ library. More...
|
|
struct | COctoMapPtr |
|
class | CPathPlanningCircularRobot |
| An implementation of CPathPlanningMethod. More...
|
|
class | CPathPlanningMethod |
| A virtual base class for computing the optimal path for a robot from a origin location to a target point. More...
|
|
class | CPointsMap |
| A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors. More...
|
|
struct | CPointsMapPtr |
|
class | CRandomFieldGridMap2D |
| CRandomFieldGridMap2D represents a 2D grid map where each cell is associated one real-valued property which is estimated by this map, either as a simple value or as a probility distribution (for each cell). More...
|
|
struct | CRandomFieldGridMap2DPtr |
|
class | CRangeBearingKFSLAM |
| An implementation of EKF-based SLAM with range-bearing sensors, odometry, a full 6D robot pose, and 3D landmarks. More...
|
|
class | CRangeBearingKFSLAM2D |
| An implementation of EKF-based SLAM with range-bearing sensors, odometry, and a 2D (+heading) robot pose, and 2D landmarks. More...
|
|
class | CRawlog |
| This class stores a rawlog (robotic datasets) in one of two possible formats: More...
|
|
struct | CRawlogPtr |
|
class | CRBPFParticleData |
| Auxiliary class used in mrpt::slam::CMultiMetricMapPDF. More...
|
|
struct | CRBPFParticleDataPtr |
|
class | CReflectivityGridMap2D |
| A 2D grid map representing the reflectivity of the environment (for example, measured with an IR proximity sensor). More...
|
|
struct | CReflectivityGridMap2DPtr |
|
class | CRejectionSamplingRangeOnlyLocalization |
| An implementation of rejection sampling for generating 2D robot pose from range-only measurements within a landmarks (beacons) map. More...
|
|
class | CSensoryFrame |
| Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximately at the same time as one "snapshot" of the environment. More...
|
|
struct | CSensoryFramePtr |
|
class | CSimpleMap |
| This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be totally determined with this information. More...
|
|
struct | CSimpleMapPtr |
|
class | CSimplePointsMap |
| A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. More...
|
|
struct | CSimplePointsMapPtr |
|
class | CSinCosLookUpTableFor2DScans |
| A smart look-up-table (LUT) of sin/cos values for 2D laser scans. More...
|
|
class | CWeightedPointsMap |
| A cloud of points in 2D or 3D, which can be built from a sequence of laser scans. More...
|
|
struct | CWeightedPointsMapPtr |
|
class | CWirelessPowerGridMap2D |
| CWirelessPowerGridMap2D represents a PDF of wifi concentrations over a 2D area. More...
|
|
struct | CWirelessPowerGridMap2DPtr |
|
class | mrptEventMetricMapClear |
| Event emitted by a metric up upon call of clear() More...
|
|
class | mrptEventMetricMapInsert |
| Event emitted by a metric up upon a succesful call to insertObservation() More...
|
|
class | PF_implementation |
| A set of common data shared by PF implementations for both SLAM and localization. More...
|
|
struct | T2DScanProperties |
| Auxiliary struct that holds all the relevant geometry information about a 2D scan. More...
|
|
struct | TDataAssociationResults |
| The results from mrpt::slam::data_association. More...
|
|
struct | THeightGridmapCell |
| The contents of each cell in a CHeightGridMap2D map. More...
|
|
class | TKLDParams |
| Option set for KLD algorithm. More...
|
|
struct | TMatchingExtraResults |
| Additional results from the determination of matchings between point clouds, etc., apart from the pairings themselves. More...
|
|
struct | TMatchingParams |
| Parameters for the determination of matchings between point clouds, etc. More...
|
|
struct | TMetricMapInitializer |
| Each structure of this kind will determine the kind (and initial configuration) of one map to be build into a CMultiMetricMap object. More...
|
|
struct | TMonteCarloLocalizationParams |
| The struct for passing extra simulation parameters to the prediction stage when running a particle filter. More...
|
|
struct | TRandomFieldCell |
| The contents of each cell in a CRandomFieldGridMap2D map. More...
|
|
class | TSetOfMetricMapInitializers |
| A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap See the comments for TSetOfMetricMapInitializers::loadFromConfigFile, and "CMultiMetricMap::setListOfMaps" for effectively creating the list of desired maps. More...
|
|
struct | TStereoImageFeatures |
|
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CBeaconPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CBeaconMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CColouredOctoMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CColouredPointsMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CGasConcentrationGridMap2DPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CHeightGridMap2DPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, COccupancyGridMap2DPtr &pObj) |
|
bool | operator< (const COccupancyGridMap2D::TPairLikelihoodIndex &e1, const COccupancyGridMap2D::TPairLikelihoodIndex &e2) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, COctoMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CPointsMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CRandomFieldGridMap2DPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CReflectivityGridMap2DPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CSimplePointsMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CWeightedPointsMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CWirelessPowerGridMap2DPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CActionPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CActionCollectionPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CActionRobotMovement2DPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CActionRobotMovement3DPtr &pObj) |
|
bool OBS_IMPEXP | carmen_log_parse_line (std::istream &in_stream, std::vector< mrpt::slam::CObservationPtr > &out_imported_observations, const mrpt::system::TTimeStamp &time_start_log) |
| Parse one line from an text input stream and interpret it as a CARMEN log entry, returning its MRPT observation representation. More...
|
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CMetricMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationPtr &pObj) |
|
bool OBS_IMPEXP | operator< (const T2DScanProperties &a, const T2DScanProperties &b) |
| Order operator, so T2DScanProperties can appear in associative STL containers. More...
|
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservation2DRangeScanPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservation3DRangeScanPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationBatteryStatePtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationBeaconRangesPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationBearingRangePtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationCANBusJ1939Ptr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationCommentPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationGasSensorsPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationGPSPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationImagePtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationIMUPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationOdometryPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationRangePtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationRawDAQPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationReflectivityPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationRFIDPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationStereoImagesPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationStereoImagesFeaturesPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationWindSensorPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationWirelessPowerPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CRawlogPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CSensoryFramePtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CSimpleMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CIncrementalMapPartitionerPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CMultiMetricMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CRBPFParticleDataPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CMultiMetricMapPDFPtr &pObj) |
|
template<class PARTICLETYPE , class BINTYPE > |
void | KLF_loadBinFromParticle (BINTYPE &outBin, const TKLDParams &opts, const PARTICLETYPE *currentParticleValue=NULL, const TPose3D *newPoseToBeInserted=NULL) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CLandmarkPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CLandmarksMapPtr &pObj) |
|
::mrpt::utils::CStream & | operator>> (mrpt::utils::CStream &in, CObservationVisualLandmarksPtr &pObj) |
|
|
double SLAM_IMPEXP | observationsOverlap (const mrpt::slam::CObservation *o1, const mrpt::slam::CObservation *o2, const mrpt::poses::CPose3D *pose_o2_wrt_o1=NULL) |
| Estimates the "overlap" or "matching ratio" of two observations (range [0,1]), possibly taking into account their relative positions. More...
|
|
double | observationsOverlap (const mrpt::slam::CObservationPtr &o1, const mrpt::slam::CObservationPtr &o2, const mrpt::poses::CPose3D *pose_o2_wrt_o1=NULL) |
| Estimates the "overlap" or "matching ratio" of two observations (range [0,1]), possibly taking into account their relative positions. More...
|
|
double SLAM_IMPEXP | observationsOverlap (const mrpt::slam::CSensoryFrame &sf1, const mrpt::slam::CSensoryFrame &sf2, const mrpt::poses::CPose3D *pose_sf2_wrt_sf1=NULL) |
| Estimates the "overlap" or "matching ratio" of two set of observations (range [0,1]), possibly taking into account their relative positions. More...
|
|
double | observationsOverlap (const mrpt::slam::CSensoryFramePtr &sf1, const mrpt::slam::CSensoryFramePtr &sf2, const mrpt::poses::CPose3D *pose_sf2_wrt_sf1=NULL) |
| Estimates the "overlap" or "matching ratio" of two set of observations (range [0,1]), possibly taking into account their relative positions. More...
|
|