#------------------------------------------------------------ # Config file for the "RBPF-SLAM" application # See: https://www.mrpt.org/list-of-mrpt-apps/application-rbpf-slam/ #------------------------------------------------------------ #======================================================= # Section: [MappingApplication] # Use: Here comes global parameters for the app. #======================================================= [MappingApplication] # The source file (RAW-LOG) with action/observation pairs rawlog_file=../../datasets/2006-01ENE-21-SENA_Telecom Faculty_one_loop_only.rawlog rawlog_offset=0 # The directory where the log files will be saved (left in blank if no log is required) logOutput_dir=LOG_GRIDMAPPING LOG_FREQUENCY=10 // The frequency of log files generation: GENERATE_LOG_JOINT_H=0 GENERATE_LOG_INFO=0 SAVE_MAP_IMAGES=1 SAVE_3D_SCENE=1 SAVE_POSE_LOG=0 SAVE_ENOSE_READINGS=0 CAMERA_3DSCENE_FOLLOWS_ROBOT=0 SHOW_PROGRESS_IN_WINDOW=1 insertionLinDistance = 1.0 // The distance threshold for inserting observations in the map (meters) insertionAngDistance_deg = 40.0 // The distance threshold for inserting observations in the map (degrees) localizeLinDistance = 1.0 // The distance threshold for actually running the PF, otherwise will rely on odometry (meters) localizeAngDistance_deg = 40.0 // The rotational threshold for actually running the PF, otherwise will rely on odometry (degrees) # Console verbosity level: # One of: DEBUG, INFO (default), WARN, ERROR verbosity_level = DEBUG #---------------------------------------------------------------------------------- # The Particle Filter algorithm: # 0: pfStandardProposal # 1: pfAuxiliaryPFStandard # 2: pfOptimalProposal *** (ICP-based (Grisetti's method),...) # 3: pfAuxiliaryPFOptimal *** (Optimal SAMPLING) # # See: http://babel.isa.uma.es/mrpt/index.php/Particle_Filter_Algorithms #---------------------------------------------------------------------------------- PF_algorithm = 3 adaptiveSampleSize = 0 // 0: Fixed # of particles, 1: KLD adaptive #---------------------------------------------------------------------------------- # The Particle Filter Resampling method: # 0: prMultinomial # 1: prResidual # 2: prStratified # 3: prSystematic # # See: http://babel.isa.uma.es/mrpt/index.php/Resampling_Schemes #---------------------------------------------------------------------------------- resamplingMethod=0 sampleSize=25 // Sample size (for fixed number) BETA=0.50 // Resampling ESS threshold # ======================================================== # MULTIMETRIC MAP CONFIGURATION # See docs for (Google for) mrpt::maps::CMultiMetricMap # ======================================================== # Creation of maps: occupancyGrid_count=1 gasGrid_count=0 beaconMap_count=0 pointsMap_count=0 # Selection of map for likelihood: (fuseAll=-1,occGrid=0, points=1,landmarks=2,gasGrid=3) likelihoodMapSelection=-1 # ==================================================== # CHybridMetricMapPDF::TPredictionParams # ==================================================== powFactor=0.01 // A "power factor" for updating weights pfAuxFilterOptimal_MaximumSearchSamples=400 // For PF algorithm=3 # ----------------------------------------------------------------- # pfOptimalProposal_mapSelection # Only for PF algorithm=2 (Exact "pfOptimalProposal") # Select the map on which to calculate the optimal # proposal distribution. Values: # 0: Gridmap -> Uses Scan matching-based approximation (based on Stachniss' work) # 1: Landmarks -> Uses matching to approximate optimal # 2: Beacons -> Used for exact optimal proposal in RO-SLAM # ----------------------------------------------------------------- pfOptimalProposal_mapSelection=0 # Adaptive sample size parameters ------------------ KLD_maxSampleSize=150 KLD_minSampleSize=15 KLD_binSize_XY=0.03 KLD_binSize_PHI_deg=1 KLD_delta=0.001 KLD_epsilon=0.5 # ==================================================== # MULTIMETRIC MAP: OccGrid #00 # ==================================================== # Creation Options for OccupancyGridMap 00: [MappingApplication_occupancyGrid_00_creationOpts] resolution=0.07 disableSaveAs3DObject=0 # Insertion Options for OccupancyGridMap 00: [MappingApplication_occupancyGrid_00_insertOpts] mapAltitude = 0 useMapAltitude = 0 maxDistanceInsertion = 35 maxOccupancyUpdateCertainty = 0.60 considerInvalidRangesAsFreeSpace = 1 minLaserScanNoiseStd = 0.001 wideningBeamsWithDistance = 0 # Likelihood Options for OccupancyGridMap 00: [MappingApplication_occupancyGrid_00_likelihoodOpts] likelihoodMethod=4 // 0=MI, 1=Beam Model, 2=RSLC, 3=Cells Difs, 4=LF_Trun, 5=LF_II LF_decimation=5 LF_stdHit=0.20 LF_maxCorrsDistance=0.30 LF_zHit=0.999 LF_zRandom=0.001 LF_maxRange=30 LF_alternateAverageMethod=0 enableLikelihoodCache=1