#include <Statistics.h>
Public Member Functions | |
void | addStatistic (const std::string &name, float value) |
const std::multimap< int, Link > & | constraints () const |
int | currentGoalId () const |
const std::map< std::string, float > & | data () const |
bool | extended () const |
const Signature & | getLastSignatureData () const |
const std::map< int, std::string > & | labels () const |
const std::map< int, float > & | likelihood () const |
const cv::Mat & | localizationCovariance () const |
const std::vector< int > & | localPath () const |
int | loopClosureId () const |
int | loopClosureMapId () const |
const Transform & | loopClosureTransform () const |
const Transform & | mapCorrection () const |
const std::map< int, Transform > & | poses () const |
const std::map< int, float > & | posterior () const |
int | proximityDetectionId () const |
int | proximityDetectionMapId () const |
const std::map< int, float > & | rawLikelihood () const |
const std::map< int, int > & | reducedIds () const |
int | refImageId () const |
int | refImageMapId () const |
void | setConstraints (const std::multimap< int, Link > &constraints) |
void | setCurrentGoalId (int goal) |
void | setExtended (bool extended) |
void | setLabels (const std::map< int, std::string > &labels) |
void | setLastSignatureData (const Signature &data) |
void | setLikelihood (const std::map< int, float > &likelihood) |
void | setLocalizationCovariance (const cv::Mat &covariance) |
void | setLocalPath (const std::vector< int > &localPath) |
void | setLoopClosureId (int id) |
void | setLoopClosureMapId (int id) |
void | setLoopClosureTransform (const Transform &loopClosureTransform) |
void | setMapCorrection (const Transform &mapCorrection) |
void | setPoses (const std::map< int, Transform > &poses) |
void | setPosterior (const std::map< int, float > &posterior) |
void | setProximityDetectionId (int id) |
void | setProximityDetectionMapId (int id) |
void | setRawLikelihood (const std::map< int, float > &rawLikelihood) |
void | setReducedIds (const std::map< int, int > &reducedIds) |
void | setRefImageId (int id) |
void | setRefImageMapId (int id) |
void | setStamp (double stamp) |
void | setWeights (const std::map< int, int > &weights) |
void | setWmState (const std::vector< int > &state) |
double | stamp () const |
Statistics () | |
const std::map< int, int > & | weights () const |
const std::vector< int > & | wmState () const |
virtual | ~Statistics () |
Static Public Member Functions | |
static const std::map< std::string, float > & | defaultData () |
static std::map< std::string, float > | deserializeData (const std::string &data) |
static std::string | serializeData (const std::map< std::string, float > &data) |
Private Member Functions | |
RTABMAP_STATS (Loop, Id,) | |
RTABMAP_STATS (Loop, RejectedHypothesis,) | |
RTABMAP_STATS (Loop, Accepted_hypothesis_id,) | |
RTABMAP_STATS (Loop, Suppressed_hypothesis_id,) | |
RTABMAP_STATS (Loop, Highest_hypothesis_id,) | |
RTABMAP_STATS (Loop, Highest_hypothesis_value,) | |
RTABMAP_STATS (Loop, Vp_hypothesis,) | |
RTABMAP_STATS (Loop, Reactivate_id,) | |
RTABMAP_STATS (Loop, Hypothesis_ratio,) | |
RTABMAP_STATS (Loop, Hypothesis_reactivated,) | |
RTABMAP_STATS (Loop, Map_id,) | |
RTABMAP_STATS (Loop, Visual_words,) | |
RTABMAP_STATS (Loop, Visual_inliers,) | |
RTABMAP_STATS (Loop, Visual_inliers_ratio,) | |
RTABMAP_STATS (Loop, Visual_matches,) | |
RTABMAP_STATS (Loop, Distance_since_last_loc,) | |
RTABMAP_STATS (Loop, Last_id,) | |
RTABMAP_STATS (Loop, Optimization_max_error, m) | |
RTABMAP_STATS (Loop, Optimization_max_error_ratio,) | |
RTABMAP_STATS (Loop, Optimization_error,) | |
RTABMAP_STATS (Loop, Optimization_iterations,) | |
RTABMAP_STATS (Loop, Linear_variance,) | |
RTABMAP_STATS (Loop, Angular_variance,) | |
RTABMAP_STATS (Loop, Landmark_detected,) | |
RTABMAP_STATS (Loop, Landmark_detected_node_ref,) | |
RTABMAP_STATS (Loop, Visual_inliers_mean_dist, m) | |
RTABMAP_STATS (Loop, Visual_inliers_distribution,) | |
RTABMAP_STATS (Loop, Odom_correction_norm, m) | |
RTABMAP_STATS (Loop, Odom_correction_angle, deg) | |
RTABMAP_STATS (Loop, Odom_correction_x, m) | |
RTABMAP_STATS (Loop, Odom_correction_y, m) | |
RTABMAP_STATS (Loop, Odom_correction_z, m) | |
RTABMAP_STATS (Loop, Odom_correction_roll, deg) | |
RTABMAP_STATS (Loop, Odom_correction_pitch, deg) | |
RTABMAP_STATS (Loop, Odom_correction_yaw, deg) | |
RTABMAP_STATS (Loop, Odom_correction_acc_norm, m) | |
RTABMAP_STATS (Loop, Odom_correction_acc_angle, deg) | |
RTABMAP_STATS (Loop, Odom_correction_acc_x, m) | |
RTABMAP_STATS (Loop, Odom_correction_acc_y, m) | |
RTABMAP_STATS (Loop, Odom_correction_acc_z, m) | |
RTABMAP_STATS (Loop, Odom_correction_acc_roll, deg) | |
RTABMAP_STATS (Loop, Odom_correction_acc_pitch, deg) | |
RTABMAP_STATS (Loop, Odom_correction_acc_yaw, deg) | |
RTABMAP_STATS (Loop, MapToOdom_norm, m) | |
RTABMAP_STATS (Loop, MapToOdom_angle, deg) | |
RTABMAP_STATS (Loop, MapToOdom_x, m) | |
RTABMAP_STATS (Loop, MapToOdom_y, m) | |
RTABMAP_STATS (Loop, MapToOdom_z, m) | |
RTABMAP_STATS (Loop, MapToOdom_roll, deg) | |
RTABMAP_STATS (Loop, MapToOdom_pitch, deg) | |
RTABMAP_STATS (Loop, MapToOdom_yaw, deg) | |
RTABMAP_STATS (Loop, MapToBase_x, m) | |
RTABMAP_STATS (Loop, MapToBase_y, m) | |
RTABMAP_STATS (Loop, MapToBase_z, m) | |
RTABMAP_STATS (Loop, MapToBase_roll, deg) | |
RTABMAP_STATS (Loop, MapToBase_pitch, deg) | |
RTABMAP_STATS (Loop, MapToBase_yaw, deg) | |
RTABMAP_STATS (Proximity, Time_detections,) | |
RTABMAP_STATS (Proximity, Space_last_detection_id,) | |
RTABMAP_STATS (Proximity, Space_paths,) | |
RTABMAP_STATS (Proximity, Space_visual_paths_checked,) | |
RTABMAP_STATS (Proximity, Space_scan_paths_checked,) | |
RTABMAP_STATS (Proximity, Space_detections_added_visually,) | |
RTABMAP_STATS (Proximity, Space_detections_added_icp_only,) | |
RTABMAP_STATS (NeighborLinkRefining, Accepted,) | |
RTABMAP_STATS (NeighborLinkRefining, Inliers,) | |
RTABMAP_STATS (NeighborLinkRefining, ICP_inliers_ratio,) | |
RTABMAP_STATS (NeighborLinkRefining, ICP_rotation, rad) | |
RTABMAP_STATS (NeighborLinkRefining, ICP_translation, m) | |
RTABMAP_STATS (NeighborLinkRefining, ICP_complexity,) | |
RTABMAP_STATS (NeighborLinkRefining, Variance,) | |
RTABMAP_STATS (NeighborLinkRefining, Pts,) | |
RTABMAP_STATS (Memory, Working_memory_size,) | |
RTABMAP_STATS (Memory, Short_time_memory_size,) | |
RTABMAP_STATS (Memory, Database_memory_used, MB) | |
RTABMAP_STATS (Memory, Signatures_removed,) | |
RTABMAP_STATS (Memory, Immunized_globally,) | |
RTABMAP_STATS (Memory, Immunized_locally,) | |
RTABMAP_STATS (Memory, Immunized_locally_max,) | |
RTABMAP_STATS (Memory, Signatures_retrieved,) | |
RTABMAP_STATS (Memory, Images_buffered,) | |
RTABMAP_STATS (Memory, Rehearsal_sim,) | |
RTABMAP_STATS (Memory, Rehearsal_id,) | |
RTABMAP_STATS (Memory, Rehearsal_merged,) | |
RTABMAP_STATS (Memory, Local_graph_size,) | |
RTABMAP_STATS (Memory, Small_movement,) | |
RTABMAP_STATS (Memory, Fast_movement,) | |
RTABMAP_STATS (Memory, Odometry_variance_ang,) | |
RTABMAP_STATS (Memory, Odometry_variance_lin,) | |
RTABMAP_STATS (Memory, Distance_travelled, m) | |
RTABMAP_STATS (Memory, RAM_usage, MB) | |
RTABMAP_STATS (Memory, RAM_estimated, MB) | |
RTABMAP_STATS (Memory, Triangulated_points,) | |
RTABMAP_STATS (Timing, Memory_update, ms) | |
RTABMAP_STATS (Timing, Neighbor_link_refining, ms) | |
RTABMAP_STATS (Timing, Proximity_by_time, ms) | |
RTABMAP_STATS (Timing, Proximity_by_space_visual, ms) | |
RTABMAP_STATS (Timing, Proximity_by_space, ms) | |
RTABMAP_STATS (Timing, Cleaning_neighbors, ms) | |
RTABMAP_STATS (Timing, Reactivation, ms) | |
RTABMAP_STATS (Timing, Add_loop_closure_link, ms) | |
RTABMAP_STATS (Timing, Map_optimization, ms) | |
RTABMAP_STATS (Timing, Likelihood_computation, ms) | |
RTABMAP_STATS (Timing, Posterior_computation, ms) | |
RTABMAP_STATS (Timing, Hypotheses_creation, ms) | |
RTABMAP_STATS (Timing, Hypotheses_validation, ms) | |
RTABMAP_STATS (Timing, Statistics_creation, ms) | |
RTABMAP_STATS (Timing, Memory_cleanup, ms) | |
RTABMAP_STATS (Timing, Total, ms) | |
RTABMAP_STATS (Timing, Forgetting, ms) | |
RTABMAP_STATS (Timing, Joining_trash, ms) | |
RTABMAP_STATS (Timing, Emptying_trash, ms) | |
RTABMAP_STATS (Timing, Finalizing_statistics, ms) | |
RTABMAP_STATS (Timing, RAM_estimation, ms) | |
RTABMAP_STATS (TimingMem, Pre_update, ms) | |
RTABMAP_STATS (TimingMem, Signature_creation, ms) | |
RTABMAP_STATS (TimingMem, Rehearsal, ms) | |
RTABMAP_STATS (TimingMem, Keypoints_detection, ms) | |
RTABMAP_STATS (TimingMem, Subpixel, ms) | |
RTABMAP_STATS (TimingMem, Stereo_correspondences, ms) | |
RTABMAP_STATS (TimingMem, Descriptors_extraction, ms) | |
RTABMAP_STATS (TimingMem, Rectification, ms) | |
RTABMAP_STATS (TimingMem, Keypoints_3D, ms) | |
RTABMAP_STATS (TimingMem, Keypoints_3D_motion, ms) | |
RTABMAP_STATS (TimingMem, Joining_dictionary_update, ms) | |
RTABMAP_STATS (TimingMem, Add_new_words, ms) | |
RTABMAP_STATS (TimingMem, Compressing_data, ms) | |
RTABMAP_STATS (TimingMem, Post_decimation, ms) | |
RTABMAP_STATS (TimingMem, Scan_filtering, ms) | |
RTABMAP_STATS (TimingMem, Occupancy_grid, ms) | |
RTABMAP_STATS (TimingMem, Markers_detection, ms) | |
RTABMAP_STATS (Keypoint, Dictionary_size, words) | |
RTABMAP_STATS (Keypoint, Current_frame, words) | |
RTABMAP_STATS (Keypoint, Indexed_words, words) | |
RTABMAP_STATS (Keypoint, Index_memory_usage, KB) | |
RTABMAP_STATS (Gt, Translational_rmse, m) | |
RTABMAP_STATS (Gt, Translational_mean, m) | |
RTABMAP_STATS (Gt, Translational_median, m) | |
RTABMAP_STATS (Gt, Translational_std, m) | |
RTABMAP_STATS (Gt, Translational_min, m) | |
RTABMAP_STATS (Gt, Translational_max, m) | |
RTABMAP_STATS (Gt, Rotational_rmse, deg) | |
RTABMAP_STATS (Gt, Rotational_mean, deg) | |
RTABMAP_STATS (Gt, Rotational_median, deg) | |
RTABMAP_STATS (Gt, Rotational_std, deg) | |
RTABMAP_STATS (Gt, Rotational_min, deg) | |
RTABMAP_STATS (Gt, Rotational_max, deg) | |
RTABMAP_STATS (Gt, Localization_linear_error, m) | |
RTABMAP_STATS (Gt, Localization_angular_error, deg) | |
Private Attributes | |
std::multimap< int, Link > | _constraints |
int | _currentGoalId |
std::map< std::string, float > | _data |
bool | _extended |
std::map< int, std::string > | _labels |
Signature | _lastSignatureData |
std::map< int, float > | _likelihood |
cv::Mat | _localizationCovariance |
std::vector< int > | _localPath |
int | _loopClosureId |
int | _loopClosureMapId |
Transform | _loopClosureTransform |
Transform | _mapCorrection |
std::map< int, Transform > | _poses |
std::map< int, float > | _posterior |
int | _proximiyDetectionId |
int | _proximiyDetectionMapId |
std::map< int, float > | _rawLikelihood |
std::map< int, int > | _reducedIds |
int | _refImageId |
int | _refImageMapId |
double | _stamp |
std::map< int, int > | _weights |
std::vector< int > | _wmState |
Static Private Attributes | |
static std::map< std::string, float > | _defaultData |
static bool | _defaultDataInitialized = false |
Definition at line 53 of file Statistics.h.
rtabmap::Statistics::Statistics | ( | ) |
Definition at line 74 of file Statistics.cpp.
|
virtual |
Definition at line 88 of file Statistics.cpp.
void rtabmap::Statistics::addStatistic | ( | const std::string & | name, |
float | value | ||
) |
Definition at line 93 of file Statistics.cpp.
|
inline |
Definition at line 268 of file Statistics.h.
|
inline |
Definition at line 278 of file Statistics.h.
|
inline |
Definition at line 282 of file Statistics.h.
|
static |
Definition at line 36 of file Statistics.cpp.
|
static |
Definition at line 57 of file Statistics.cpp.
|
inline |
Definition at line 256 of file Statistics.h.
|
inline |
Definition at line 265 of file Statistics.h.
|
inline |
Definition at line 272 of file Statistics.h.
|
inline |
Definition at line 275 of file Statistics.h.
|
inline |
Definition at line 271 of file Statistics.h.
|
inline |
Definition at line 277 of file Statistics.h.
|
inline |
Definition at line 259 of file Statistics.h.
|
inline |
Definition at line 260 of file Statistics.h.
|
inline |
Definition at line 270 of file Statistics.h.
|
inline |
Definition at line 269 of file Statistics.h.
|
inline |
Definition at line 267 of file Statistics.h.
|
inline |
Definition at line 274 of file Statistics.h.
|
inline |
Definition at line 261 of file Statistics.h.
|
inline |
Definition at line 262 of file Statistics.h.
|
inline |
Definition at line 276 of file Statistics.h.
|
inline |
Definition at line 279 of file Statistics.h.
|
inline |
Definition at line 257 of file Statistics.h.
|
inline |
Definition at line 258 of file Statistics.h.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
static |
Definition at line 42 of file Statistics.cpp.
|
inline |
Definition at line 241 of file Statistics.h.
|
inline |
Definition at line 251 of file Statistics.h.
|
inline |
Definition at line 229 of file Statistics.h.
|
inline |
Definition at line 245 of file Statistics.h.
|
inline |
Definition at line 238 of file Statistics.h.
|
inline |
Definition at line 248 of file Statistics.h.
|
inline |
Definition at line 244 of file Statistics.h.
|
inline |
Definition at line 250 of file Statistics.h.
|
inline |
Definition at line 232 of file Statistics.h.
|
inline |
Definition at line 233 of file Statistics.h.
|
inline |
Definition at line 243 of file Statistics.h.
|
inline |
Definition at line 242 of file Statistics.h.
|
inline |
Definition at line 240 of file Statistics.h.
|
inline |
Definition at line 247 of file Statistics.h.
|
inline |
Definition at line 234 of file Statistics.h.
|
inline |
Definition at line 235 of file Statistics.h.
|
inline |
Definition at line 249 of file Statistics.h.
|
inline |
Definition at line 252 of file Statistics.h.
|
inline |
Definition at line 230 of file Statistics.h.
|
inline |
Definition at line 231 of file Statistics.h.
|
inline |
Definition at line 236 of file Statistics.h.
|
inline |
Definition at line 246 of file Statistics.h.
|
inline |
Definition at line 253 of file Statistics.h.
|
inline |
Definition at line 263 of file Statistics.h.
|
inline |
Definition at line 273 of file Statistics.h.
|
inline |
Definition at line 280 of file Statistics.h.
|
private |
Definition at line 298 of file Statistics.h.
|
private |
Definition at line 310 of file Statistics.h.
|
private |
Definition at line 319 of file Statistics.h.
|
staticprivate |
Definition at line 320 of file Statistics.h.
|
staticprivate |
Definition at line 321 of file Statistics.h.
|
private |
Definition at line 285 of file Statistics.h.
|
private |
Definition at line 303 of file Statistics.h.
|
private |
Definition at line 295 of file Statistics.h.
|
private |
Definition at line 306 of file Statistics.h.
|
private |
Definition at line 301 of file Statistics.h.
|
private |
Definition at line 309 of file Statistics.h.
|
private |
Definition at line 289 of file Statistics.h.
|
private |
Definition at line 290 of file Statistics.h.
|
private |
Definition at line 300 of file Statistics.h.
|
private |
Definition at line 299 of file Statistics.h.
|
private |
Definition at line 297 of file Statistics.h.
|
private |
Definition at line 305 of file Statistics.h.
|
private |
Definition at line 291 of file Statistics.h.
|
private |
Definition at line 292 of file Statistics.h.
|
private |
Definition at line 307 of file Statistics.h.
|
private |
Definition at line 312 of file Statistics.h.
|
private |
Definition at line 287 of file Statistics.h.
|
private |
Definition at line 288 of file Statistics.h.
|
private |
Definition at line 293 of file Statistics.h.
|
private |
Definition at line 304 of file Statistics.h.
|
private |
Definition at line 314 of file Statistics.h.