#include <mrpt/slam/CLandmarksMap.h>
Classes | |
struct | TCustomSequenceLandmarks |
The list of landmarks: the wrapper class is just for maintaining the KD-Tree representation. More... | |
struct | TFuseOptions |
With this struct options are provided to the fusion process. More... | |
struct | TInsertionOptions |
With this struct options are provided to the observation insertion process. More... | |
struct | TInsertionResults |
This struct stores extra results from invoking insertObservation. More... | |
struct | TLikelihoodOptions |
With this struct options are provided to the likelihood computations. More... | |
Public Member Functions | |
CLandmarksMap () | |
Constructor. | |
virtual | ~CLandmarksMap () |
Virtual destructor. | |
mrpt::slam::CLandmark::TLandmarkID | getMapMaxID () |
float | compute3DMatchingRatio (const CMetricMap *otherMap, const CPose3D &otherMapPose, float minDistForCorr=0.10f, float minMahaDistForCorr=2.0f) const |
Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps. | |
bool | saveToTextFile (std::string file) |
Save to a text file. | |
bool | saveToMATLABScript2D (std::string file, const char *style="b", float stdCount=2.0f) |
Save to a MATLAB script which displays 2D error ellipses for the map (top-view, projection on the XY plane). | |
bool | saveToMATLABScript3D (std::string file, const char *style="b", float confInterval=0.95f) const |
Save to a MATLAB script which displays 3D error ellipses for the map. | |
void | clear () |
Clear the map, erasing all landmarks. | |
size_t | size () const |
Returns the stored landmarks count. | |
double | computeLikelihood_RSLC_2007 (const CLandmarksMap *s, const CPose2D &sensorPose) |
Copy. | |
void | loadSiftFeaturesFromImageObservation (const CObservationImage &obs) |
Loads into this landmarks map the SIFT features extracted from an image observation (Previous contents of map will be erased) The robot is assumed to be at the origin of the map. | |
void | loadSiftFeaturesFromStereoImageObservation (const CObservationStereoImages &obs, mrpt::slam::CLandmark::TLandmarkID fID) |
Loads into this landmarks map the SIFT features extracted from an observation consisting of a pair of stereo-image (Previous contents of map will be erased) The robot is assumed to be at the origin of the map. | |
void | loadOccupancyFeaturesFrom2DRangeScan (const CObservation2DRangeScan &obs, const CPose3D *robotPose=NULL, unsigned int downSampleFactor=1) |
Loads into this landmarks-map a set of occupancy features according to a 2D range scan (Previous contents of map will be erased). | |
bool | insertObservation (const CObservation *obs, const CPose3D *robotPose=NULL) |
Insert the observation information into this map. | |
double | computeObservationLikelihood (const CObservation *obs, const CPose3D &takenFrom) |
Computes the (logarithmic) likelihood that a given observation was taken from a given pose in the world being modeled with this map. | |
void | computeMatchingWith2D (const CMetricMap *otherMap, const CPose2D &otherMapPose, float maxDistForCorrespondence, float maxAngularDistForCorrespondence, const CPose2D &angularDistPivotPoint, TMatchingPairList &correspondences, float &correspondencesRatio, float *sumSqrDist=NULL, bool onlyKeepTheClosest=false, bool onlyUniqueRobust=false) const |
Computes the matchings between this and another 2D points map. | |
void | computeMatchingWith3DLandmarks (const mrpt::slam::CLandmarksMap *otherMap, TMatchingPairList &correspondences, float &correspondencesRatio, std::vector< bool > &otherCorrespondences) const |
Perform a search for correspondences between "this" and another lansmarks map: In this class, the matching is established solely based on the landmarks' IDs. | |
void | changeCoordinatesReference (const CPose3D &newOrg) |
Changes the reference system of the map to a given 3D pose. | |
void | changeCoordinatesReference (const CPose3D &newOrg, const mrpt::slam::CLandmarksMap *otherMap) |
Changes the reference system of the map "otherMap" and save the result in "this" map. | |
void | fuseWith (CLandmarksMap &other, bool justInsertAllOfThem=false) |
Fuses the contents of another map with this one, updating "this" object with the result. | |
double | computeLikelihood_SIFT_LandmarkMap (CLandmarksMap *map, TMatchingPairList *correspondences=NULL, std::vector< bool > *otherCorrespondences=NULL) |
Returns the (logarithmic) likelihood of a set of landmarks "map" given "this" map. | |
bool | isEmpty () const |
Returns true if the map is empty/no observation has been inserted. | |
void | simulateBeaconReadings (const CPose3D &in_robotPose, const CPoint3D &in_sensorLocationOnRobot, CObservationBeaconRanges &out_Observations) const |
Simulates a noisy reading toward each of the beacons in the landmarks map, if any. | |
void | simulateRangeBearingReadings (const CPose3D &in_robotPose, const CPose3D &in_sensorLocationOnRobot, CObservationBearingRange &out_Observations, bool sensorDetectsIDs=true, const float &in_stdRange=0.01f, const float &in_stdYaw=DEG2RAD(0.1f), const float &in_stdPitch=DEG2RAD(0.1f)) const |
Simulates a noisy bearing-range observation of all the beacons (landamrks with type glBeacon) in the landmarks map, if any. | |
void | saveMetricMapRepresentationToFile (const std::string &filNamePrefix) const |
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface). | |
void | getAs3DObject (mrpt::opengl::CSetOfObjectsPtr &outObj) const |
Returns a 3D object representing the map. | |
void | auxParticleFilterCleanUp () |
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation". | |
Public Attributes | |
struct MRPTDLLIMPEXP mrpt::slam::CLandmarksMap::TCustomSequenceLandmarks | landmarks |
The list of landmarks: the wrapper class is just for maintaining the KD-Tree representation. | |
mrpt::slam::CLandmarksMap::TInsertionOptions | insertionOptions |
With this struct options are provided to the observation insertion process. | |
mrpt::slam::CLandmarksMap::TLikelihoodOptions | likelihoodOptions |
With this struct options are provided to the likelihood computations. | |
struct MRPTDLLIMPEXP mrpt::slam::CLandmarksMap::TInsertionResults | insertionResults |
This struct stores extra results from invoking insertObservation. | |
struct MRPTDLLIMPEXP mrpt::slam::CLandmarksMap::TFuseOptions | fuseOptions |
With this struct options are provided to the fusion process. | |
Static Public Attributes | |
static mrpt::utils::TColorf | COLOR_LANDMARKS_IN_3DSCENES |
The color of landmark ellipsoids in CLandmarksMap::getAs3DObject. | |
static std::map< std::pair < mrpt::slam::CLandmark::TLandmarkID, mrpt::slam::CLandmark::TLandmarkID > , double > | _mEDD |
Map of the Euclidean Distance between the descriptors of two SIFT-based landmarks. | |
static mrpt::slam::CLandmark::TLandmarkID | _mapMaxID |
static bool | _maxIDUpdated |
Private Attributes | |
mrpt::gui::CDisplayWindow * | wind1 |
Auxiliary windows for displaying images. | |
mrpt::gui::CDisplayWindow * | wind2 |
Currently these types of landmarks are defined: (see mrpt::slam::CLandmark)
Observation class: | Generated Landmarks: | Comments: |
CObservationImage | vlSIFT | 1) A SIFT feature is created for each SIFT detected in the image, 2) Correspondences between SIFTs features and existing ones are finded by computeMatchingWith3DLandmarks, 3) The corresponding feaures are fused, and the new ones added, with an initial uncertainty according to insertionOptions |
CObservationStereoImages | vlSIFT | Each image is separately procesed by the method for CObservationImage observations |
CObservationStereoImages | vlColor | TODO... |
CObservation2DRangeScan | glOccupancy | A landmark is added for each range in the scan, with its appropiate covariance matrix derived from the jacobians matrixes. |
Definition at line 84 of file CLandmarksMap.h.
mrpt::slam::CLandmarksMap::CLandmarksMap | ( | ) |
Constructor.
virtual mrpt::slam::CLandmarksMap::~CLandmarksMap | ( | ) | [virtual] |
Virtual destructor.
void mrpt::slam::CLandmarksMap::auxParticleFilterCleanUp | ( | ) | [virtual] |
This method is called at the end of each "prediction-update-map insertion" cycle within "mrpt::slam::CMetricMapBuilderRBPF::processActionObservation".
This method should normally do nothing, but in some cases can be used to free auxiliary cached variables.
Implements mrpt::slam::CMetricMap.
void mrpt::slam::CLandmarksMap::changeCoordinatesReference | ( | const CPose3D & | newOrg, | |
const mrpt::slam::CLandmarksMap * | otherMap | |||
) |
Changes the reference system of the map "otherMap" and save the result in "this" map.
void mrpt::slam::CLandmarksMap::changeCoordinatesReference | ( | const CPose3D & | newOrg | ) |
Changes the reference system of the map to a given 3D pose.
void mrpt::slam::CLandmarksMap::clear | ( | ) | [virtual] |
float mrpt::slam::CLandmarksMap::compute3DMatchingRatio | ( | const CMetricMap * | otherMap, | |
const CPose3D & | otherMapPose, | |||
float | minDistForCorr = 0.10f , |
|||
float | minMahaDistForCorr = 2.0f | |||
) | const [virtual] |
Computes the ratio in [0,1] of correspondences between "this" and the "otherMap" map, whose 6D pose relative to "this" is "otherMapPose" In the case of a multi-metric map, this returns the average between the maps.
This method always return 0 for grid maps.
otherMap | [IN] The other map to compute the matching with. | |
otherMapPose | [IN] The 6D pose of the other map as seen from "this". | |
minDistForCorr | [IN] The minimum distance between 2 non-probabilistic map elements for counting them as a correspondence. | |
minMahaDistForCorr | [IN] The minimum Mahalanobis distance between 2 probabilistic map elements for counting them as a correspondence. |
Implements mrpt::slam::CMetricMap.
double mrpt::slam::CLandmarksMap::computeLikelihood_RSLC_2007 | ( | const CLandmarksMap * | s, | |
const CPose2D & | sensorPose | |||
) |
Copy.
Computes the (logarithmic) likelihood function for a sensed observation "o" according to "this" map. This is the implementation of the algorithm reported in the paper: J.L. Blanco, J. Gonzalez, and J.A. Fernandez-Madrigal, "A Consensus-based Approach for Estimating the Observation Likelihood of Accurate Range Sensors", in IEEE International Conference on Robotics and Automation (ICRA), Rome (Italy), Apr 10-14, 2007
double mrpt::slam::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap | ( | CLandmarksMap * | map, | |
TMatchingPairList * | correspondences = NULL , |
|||
std::vector< bool > * | otherCorrespondences = NULL | |||
) |
Returns the (logarithmic) likelihood of a set of landmarks "map" given "this" map.
See paper: JJAA 2006
void mrpt::slam::CLandmarksMap::computeMatchingWith2D | ( | const CMetricMap * | otherMap, | |
const CPose2D & | otherMapPose, | |||
float | maxDistForCorrespondence, | |||
float | maxAngularDistForCorrespondence, | |||
const CPose2D & | angularDistPivotPoint, | |||
TMatchingPairList & | correspondences, | |||
float & | correspondencesRatio, | |||
float * | sumSqrDist = NULL , |
|||
bool | onlyKeepTheClosest = false , |
|||
bool | onlyUniqueRobust = false | |||
) | const [virtual] |
Computes the matchings between this and another 2D points map.
This includes finding:
otherMap | [IN] The other map to compute the matching with. | |
otherMapPose | [IN] The pose of the other map as seen from "this". | |
maxDistForCorrespondence | [IN] Maximum 2D linear distance between two points to be matched. | |
maxAngularDistForCorrespondence | [IN] In radians: The aim is to allow larger distances to more distant correspondences. | |
angularDistPivotPoint | [IN] The point used to calculate distances from in both maps. | |
correspondences | [OUT] The detected matchings pairs. | |
correspondencesRatio | [OUT] The ratio [0,1] of points in otherMap with at least one correspondence. | |
sumSqrDist | [OUT] The sum of all matched points squared distances.If undesired, set to NULL, as default. | |
onlyKeepTheClosest | [IN] If set to true, only the closest correspondence will be returned. If false (default) all are returned. |
Reimplemented from mrpt::slam::CMetricMap.
void mrpt::slam::CLandmarksMap::computeMatchingWith3DLandmarks | ( | const mrpt::slam::CLandmarksMap * | otherMap, | |
TMatchingPairList & | correspondences, | |||
float & | correspondencesRatio, | |||
std::vector< bool > & | otherCorrespondences | |||
) | const |
Perform a search for correspondences between "this" and another lansmarks map: In this class, the matching is established solely based on the landmarks' IDs.
otherMap | [IN] The other map. | |
correspondences | [OUT] The matched pairs between maps. | |
correspondencesRatio | [OUT] This is NumberOfMatchings / NumberOfLandmarksInTheAnotherMap | |
otherCorrespondences | [OUT] Will be returned with a vector containing "true" for the indexes of the other map's landmarks with a correspondence. |
double mrpt::slam::CLandmarksMap::computeObservationLikelihood | ( | const CObservation * | obs, | |
const CPose3D & | takenFrom | |||
) | [virtual] |
Computes the (logarithmic) likelihood that a given observation was taken from a given pose in the world being modeled with this map.
In the current implementation, this method behaves in a different way according to the nature of the observation's class:
takenFrom | The robot's pose the observation is supposed to be taken from. | |
obs | The observation. |
Implements mrpt::slam::CMetricMap.
void mrpt::slam::CLandmarksMap::fuseWith | ( | CLandmarksMap & | other, | |
bool | justInsertAllOfThem = false | |||
) |
Fuses the contents of another map with this one, updating "this" object with the result.
This process involves fusing corresponding landmarks, then adding the new ones.
other | The other landmarkmap, whose landmarks will be inserted into "this" | |
justInsertAllOfThem | If set to "true", all the landmarks in "other" will be inserted into "this" without checking for possible correspondences (may appear duplicates ones, etc...) |
void mrpt::slam::CLandmarksMap::getAs3DObject | ( | mrpt::opengl::CSetOfObjectsPtr & | outObj | ) | const [virtual] |
Returns a 3D object representing the map.
Implements mrpt::slam::CMetricMap.
mrpt::slam::CLandmark::TLandmarkID mrpt::slam::CLandmarksMap::getMapMaxID | ( | ) |
bool mrpt::slam::CLandmarksMap::insertObservation | ( | const CObservation * | obs, | |
const CPose3D * | robotPose = NULL | |||
) | [virtual] |
Insert the observation information into this map.
This method must be implemented in derived classes.
obs | The observation | |
robotPose | The 3D pose of the robot mobile base in the map reference system, or NULL (default) if you want to use CPose2D(0,0,deg) |
Implements mrpt::slam::CMetricMap.
bool mrpt::slam::CLandmarksMap::isEmpty | ( | ) | const [virtual] |
Returns true if the map is empty/no observation has been inserted.
Implements mrpt::slam::CMetricMap.
void mrpt::slam::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan | ( | const CObservation2DRangeScan & | obs, | |
const CPose3D * | robotPose = NULL , |
|||
unsigned int | downSampleFactor = 1 | |||
) |
Loads into this landmarks-map a set of occupancy features according to a 2D range scan (Previous contents of map will be erased).
obs | The observation | |
robotPose | The robot pose in the map (Default = the origin) Some options may be applicable from "insertionOptions" |
void mrpt::slam::CLandmarksMap::loadSiftFeaturesFromImageObservation | ( | const CObservationImage & | obs | ) |
Loads into this landmarks map the SIFT features extracted from an image observation (Previous contents of map will be erased) The robot is assumed to be at the origin of the map.
Some options may be applicable from "insertionOptions" (insertionOptions.SIFTsLoadDistanceOfTheMean)
void mrpt::slam::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation | ( | const CObservationStereoImages & | obs, | |
mrpt::slam::CLandmark::TLandmarkID | fID | |||
) |
Loads into this landmarks map the SIFT features extracted from an observation consisting of a pair of stereo-image (Previous contents of map will be erased) The robot is assumed to be at the origin of the map.
Some options may be applicable from "insertionOptions"
void mrpt::slam::CLandmarksMap::saveMetricMapRepresentationToFile | ( | const std::string & | filNamePrefix | ) | const [virtual] |
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >, as an image or in any other applicable way (Notice that other methods to save the map may be implemented in classes implementing this virtual interface).
In the case of this class, these files are generated:
Implements mrpt::slam::CMetricMap.
bool mrpt::slam::CLandmarksMap::saveToMATLABScript2D | ( | std::string | file, | |
const char * | style = "b" , |
|||
float | stdCount = 2.0f | |||
) |
Save to a MATLAB script which displays 2D error ellipses for the map (top-view, projection on the XY plane).
file | The name of the file to save the script to. | |
style | The MATLAB-like string for the style of the lines (see 'help plot' in MATLAB for posibilities) | |
stdCount | The ellipsoids will be drawn from the center to "stdCount" times the "standard deviations". (default is 2std = 95% confidence intervals) |
bool mrpt::slam::CLandmarksMap::saveToMATLABScript3D | ( | std::string | file, | |
const char * | style = "b" , |
|||
float | confInterval = 0.95f | |||
) | const |
Save to a MATLAB script which displays 3D error ellipses for the map.
file | The name of the file to save the script to. | |
style | The MATLAB-like string for the style of the lines (see 'help plot' in MATLAB for posibilities) | |
stdCount | The ellipsoids will be drawn from the center to a given confidence interval in [0,1], e.g. 2 sigmas=0.95 (default is 2std = 0.95 confidence intervals) |
bool mrpt::slam::CLandmarksMap::saveToTextFile | ( | std::string | file | ) |
Save to a text file.
In line "i" there are the (x,y,z) mean values of the i'th landmark + type of landmark + # times seen + timestamp + RGB/descriptor + ID
Returns false if any error occured, true elsewere.
void mrpt::slam::CLandmarksMap::simulateBeaconReadings | ( | const CPose3D & | in_robotPose, | |
const CPoint3D & | in_sensorLocationOnRobot, | |||
CObservationBeaconRanges & | out_Observations | |||
) | const |
Simulates a noisy reading toward each of the beacons in the landmarks map, if any.
in_robotPose | This robot pose is used to simulate the ranges to each beacon. | |
in_sensorLocationOnRobot | The 3D position of the sensor on the robot | |
out_Observations | The results will be stored here. NOTICE that the fields "CObservationBeaconRanges::minSensorDistance","CObservationBeaconRanges::maxSensorDistance" and "CObservationBeaconRanges::stdError" MUST BE FILLED OUT before calling this function. An observation will be generated for each beacon in the map, but notice that some of them may be missed if out of the sensor maximum range. |
void mrpt::slam::CLandmarksMap::simulateRangeBearingReadings | ( | const CPose3D & | in_robotPose, | |
const CPose3D & | in_sensorLocationOnRobot, | |||
CObservationBearingRange & | out_Observations, | |||
bool | sensorDetectsIDs = true , |
|||
const float & | in_stdRange = 0.01f , |
|||
const float & | in_stdYaw = DEG2RAD(0.1f) , |
|||
const float & | in_stdPitch = DEG2RAD(0.1f) | |||
) | const |
Simulates a noisy bearing-range observation of all the beacons (landamrks with type glBeacon) in the landmarks map, if any.
in_robotPose | The robot pose. | |
in_sensorLocationOnRobot | The 3D position of the sensor on the robot | |
out_Observations | The results will be stored here. | |
sensorDetectsIDs | If this is set to false, all the landmarks will be sensed with INVALID_LANDMARK_ID as ID. | |
in_stdRange | The sigma of the sensor noise in range (meters). | |
in_stdYaw | The sigma of the sensor noise in yaw (radians). | |
in_stdPitch | The sigma of the sensor noise in pitch (radians). |
size_t mrpt::slam::CLandmarksMap::size | ( | ) | const |
Returns the stored landmarks count.
Definition at line 178 of file CLandmarksMap.h.
bool mrpt::slam::CLandmarksMap::_maxIDUpdated [static] |
Definition at line 179 of file CLandmarksMap.h.
std::map<std::pair<mrpt::slam::CLandmark::TLandmarkID, mrpt::slam::CLandmark::TLandmarkID>, double> mrpt::slam::CLandmarksMap::_mEDD [static] |
Map of the Euclidean Distance between the descriptors of two SIFT-based landmarks.
Definition at line 177 of file CLandmarksMap.h.
The color of landmark ellipsoids in CLandmarksMap::getAs3DObject.
Definition at line 97 of file CLandmarksMap.h.
struct MRPTDLLIMPEXP mrpt::slam::CLandmarksMap::TFuseOptions mrpt::slam::CLandmarksMap::fuseOptions |
With this struct options are provided to the fusion process.
With this struct options are provided to the observation insertion process.
struct MRPTDLLIMPEXP mrpt::slam::CLandmarksMap::TInsertionResults mrpt::slam::CLandmarksMap::insertionResults |
This struct stores extra results from invoking insertObservation.
struct MRPTDLLIMPEXP mrpt::slam::CLandmarksMap::TCustomSequenceLandmarks mrpt::slam::CLandmarksMap::landmarks |
The list of landmarks: the wrapper class is just for maintaining the KD-Tree representation.
With this struct options are provided to the likelihood computations.
Definition at line 93 of file CLandmarksMap.h.
Page generated by Doxygen 1.5.7.1 for MRPT 0.7.1 SVN: at Mon Aug 17 23:10:56 EDT 2009 |