Class LifelongSlamToolbox
Defined in File slam_toolbox_lifelong.hpp
Inheritance Relationships
Base Type
public slam_toolbox::SlamToolbox
(Class SlamToolbox)
Class Documentation
-
class LifelongSlamToolbox : public slam_toolbox::SlamToolbox
Public Functions
-
explicit LifelongSlamToolbox(rclcpp::NodeOptions options)
-
inline ~LifelongSlamToolbox()
-
double computeObjectiveScore(const double &intersect_over_union, const double &area_overlap, const double &reading_overlap, const int &num_constraints, const double &initial_score, const int &num_candidates) const
Public Static Functions
-
static double computeIntersect(LocalizedRangeScan *s1, LocalizedRangeScan *s2)
-
static double computeIntersectOverUnion(LocalizedRangeScan *s1, LocalizedRangeScan *s2)
-
static double computeAreaOverlapRatio(LocalizedRangeScan *ref_scan, LocalizedRangeScan *candidate_scan)
-
static double computeReadingOverlapRatio(LocalizedRangeScan *ref_scan, LocalizedRangeScan *candidate_scan)
-
static void computeIntersectBounds(LocalizedRangeScan *s1, LocalizedRangeScan *s2, double &x_l, double &x_u, double &y_l, double &y_u)
Protected Functions
-
void evaluateNodeDepreciation(LocalizedRangeScan *range_scan)
-
void removeFromSlamGraph(Vertex<LocalizedRangeScan> *vertex)
-
double computeScore(LocalizedRangeScan *reference_scan, Vertex<LocalizedRangeScan> *candidate, const double &initial_score, const int &num_candidates)
-
ScoredVertices computeScores(Vertices &near_scans, LocalizedRangeScan *range_scan)
-
Vertices FindScansWithinRadius(LocalizedRangeScan *scan, const double &radius)
-
void updateScoresSlamGraph(const double &score, Vertex<LocalizedRangeScan> *vertex)
-
void checkIsNotNormalized(const double &value)
-
explicit LifelongSlamToolbox(rclcpp::NodeOptions options)