Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
slam_toolbox::LifelongSlamToolbox Class Reference

#include <slam_toolbox_lifelong.hpp>

Inheritance diagram for slam_toolbox::LifelongSlamToolbox:
Inheritance graph
[legend]

Public Member Functions

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
 
 LifelongSlamToolbox (ros::NodeHandle &nh)
 
 ~LifelongSlamToolbox ()
 
- Public Member Functions inherited from slam_toolbox::SlamToolbox
 SlamToolbox (ros::NodeHandle &nh)
 
 ~SlamToolbox ()
 

Static Public Member Functions

static double computeAreaOverlapRatio (LocalizedRangeScan *ref_scan, LocalizedRangeScan *candidate_scan)
 
static double computeIntersect (LocalizedRangeScan *s1, LocalizedRangeScan *s2)
 
static void computeIntersectBounds (LocalizedRangeScan *s1, LocalizedRangeScan *s2, double &x_l, double &x_u, double &y_l, double &y_u)
 
static double computeIntersectOverUnion (LocalizedRangeScan *s1, LocalizedRangeScan *s2)
 
static double computeReadingOverlapRatio (LocalizedRangeScan *ref_scan, LocalizedRangeScan *candidate_scan)
 

Protected Member Functions

void checkIsNotNormalized (const double &value)
 
double computeScore (LocalizedRangeScan *reference_scan, Vertex< LocalizedRangeScan > *candidate, const double &initial_score, const int &num_candidates)
 
ScoredVertices computeScores (Vertices &near_scans, LocalizedRangeScan *range_scan)
 
virtual bool deserializePoseGraphCallback (slam_toolbox_msgs::DeserializePoseGraph::Request &req, slam_toolbox_msgs::DeserializePoseGraph::Response &resp) override final
 
void evaluateNodeDepreciation (LocalizedRangeScan *range_scan)
 
Vertices FindScansWithinRadius (LocalizedRangeScan *scan, const double &radius)
 
virtual void laserCallback (const sensor_msgs::LaserScan::ConstPtr &scan) override final
 
void removeFromSlamGraph (Vertex< LocalizedRangeScan > *vertex)
 
void updateScoresSlamGraph (const double &score, Vertex< LocalizedRangeScan > *vertex)
 
- Protected Member Functions inherited from slam_toolbox::SlamToolbox
virtual karto::LocalizedRangeScanaddScan (karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
 
karto::LocalizedRangeScanaddScan (karto::LaserRangeFinder *laser, PosedScan &scanWPose)
 
karto::LaserRangeFindergetLaser (const sensor_msgs::LaserScan::ConstPtr &scan)
 
karto::LocalizedRangeScangetLocalizedRangeScan (karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
 
bool isPaused (const PausedApplication &app)
 
void loadPoseGraphByParams (ros::NodeHandle &nh)
 
void loadSerializedPoseGraph (std::unique_ptr< karto::Mapper > &, std::unique_ptr< karto::Dataset > &)
 
bool mapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
 
bool pauseNewMeasurementsCallback (slam_toolbox_msgs::Pause::Request &req, slam_toolbox_msgs::Pause::Response &resp)
 
void publishTransformLoop (const double &transform_publish_period)
 
void publishVisualizations ()
 
virtual bool serializePoseGraphCallback (slam_toolbox_msgs::SerializePoseGraph::Request &req, slam_toolbox_msgs::SerializePoseGraph::Response &resp)
 
void setParams (ros::NodeHandle &nh)
 
void setROSInterfaces (ros::NodeHandle &node)
 
void setSolver (ros::NodeHandle &private_nh_)
 
tf2::Stamped< tf2::TransformsetTransformFromPoses (const karto::Pose2 &pose, const karto::Pose2 &karto_pose, const ros::Time &t, const bool &update_reprocessing_transform)
 
bool shouldProcessScan (const sensor_msgs::LaserScan::ConstPtr &scan, const karto::Pose2 &pose)
 
bool shouldStartWithPoseGraph (std::string &filename, geometry_msgs::Pose2D &pose, bool &start_at_dock)
 
bool updateMap ()
 

Protected Attributes

double candidates_scale_
 
double constraint_scale_
 
double iou_match_
 
double iou_thresh_
 
double nearby_penalty_
 
double overlap_scale_
 
double removal_score_
 
bool use_tree_
 
- Protected Attributes inherited from slam_toolbox::SlamToolbox
std::string base_frame_
 
std::unique_ptr< loop_closure_assistant::LoopClosureAssistantclosure_assistant_
 
std::unique_ptr< karto::Datasetdataset_
 
bool enable_interactive_mode_
 
bool first_measurement_
 
std::unique_ptr< laser_utils::LaserAssistantlaser_assistant_
 
std::map< std::string, laser_utils::LaserMetadatalasers_
 
nav_msgs::GetMap::Response map_
 
std::string map_frame_
 
std::string map_name_
 
std::unique_ptr< map_saver::MapSavermap_saver_
 
tf2::Transform map_to_odom_
 
boost::mutex map_to_odom_mutex_
 
ros::Duration minimum_time_interval_
 
ros::NodeHandle nh_
 
std::string odom_frame_
 
std::unique_ptr< pose_utils::GetPoseHelperpose_helper_
 
boost::mutex pose_mutex_
 
std::unique_ptr< karto::Pose2process_near_pose_
 
ProcessType processor_type_
 
tf2::Transform reprocessing_transform_
 
double resolution_
 
std::unique_ptr< tf2_ros::MessageFilter< sensor_msgs::LaserScan > > scan_filter_
 
std::unique_ptr< message_filters::Subscriber< sensor_msgs::LaserScan > > scan_filter_sub_
 
std::unique_ptr< laser_utils::ScanHolderscan_holder_
 
std::string scan_topic_
 
std::unique_ptr< mapper_utils::SMappersmapper_
 
boost::mutex smapper_mutex_
 
boost::shared_ptr< karto::ScanSolversolver_
 
pluginlib::ClassLoader< karto::ScanSolversolver_loader_
 
ros::ServiceServer ssDesserialize_
 
ros::ServiceServer ssMap_
 
ros::ServiceServer ssPauseMeasurements_
 
ros::ServiceServer ssSerialize_
 
ros::Publisher sst_
 
ros::Publisher sstm_
 
PausedState state_
 
std::unique_ptr< tf2_ros::Buffertf_
 
ros::Duration tf_buffer_dur_
 
std::unique_ptr< tf2_ros::TransformBroadcastertfB_
 
std::unique_ptr< tf2_ros::TransformListenertfL_
 
std::vector< std::unique_ptr< boost::thread > > threads_
 
int throttle_scans_
 
ros::Duration transform_timeout_
 

Detailed Description

Definition at line 29 of file slam_toolbox_lifelong.hpp.

Constructor & Destructor Documentation

◆ LifelongSlamToolbox()

slam_toolbox::LifelongSlamToolbox::LifelongSlamToolbox ( ros::NodeHandle nh)

Definition at line 36 of file slam_toolbox_lifelong.cpp.

◆ ~LifelongSlamToolbox()

slam_toolbox::LifelongSlamToolbox::~LifelongSlamToolbox ( )
inline

Definition at line 33 of file slam_toolbox_lifelong.hpp.

Member Function Documentation

◆ checkIsNotNormalized()

void slam_toolbox::LifelongSlamToolbox::checkIsNotNormalized ( const double &  value)
protected

Definition at line 25 of file slam_toolbox_lifelong.cpp.

◆ computeAreaOverlapRatio()

double slam_toolbox::LifelongSlamToolbox::computeAreaOverlapRatio ( LocalizedRangeScan *  ref_scan,
LocalizedRangeScan *  candidate_scan 
)
static

Definition at line 400 of file slam_toolbox_lifelong.cpp.

◆ computeIntersect()

double slam_toolbox::LifelongSlamToolbox::computeIntersect ( LocalizedRangeScan *  s1,
LocalizedRangeScan *  s2 
)
static

Definition at line 364 of file slam_toolbox_lifelong.cpp.

◆ computeIntersectBounds()

void slam_toolbox::LifelongSlamToolbox::computeIntersectBounds ( LocalizedRangeScan *  s1,
LocalizedRangeScan *  s2,
double &  x_l,
double &  x_u,
double &  y_l,
double &  y_u 
)
static

Definition at line 336 of file slam_toolbox_lifelong.cpp.

◆ computeIntersectOverUnion()

double slam_toolbox::LifelongSlamToolbox::computeIntersectOverUnion ( LocalizedRangeScan *  s1,
LocalizedRangeScan *  s2 
)
static

Definition at line 381 of file slam_toolbox_lifelong.cpp.

◆ computeObjectiveScore()

double slam_toolbox::LifelongSlamToolbox::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

Definition at line 160 of file slam_toolbox_lifelong.cpp.

◆ computeReadingOverlapRatio()

double slam_toolbox::LifelongSlamToolbox::computeReadingOverlapRatio ( LocalizedRangeScan *  ref_scan,
LocalizedRangeScan *  candidate_scan 
)
static

Definition at line 418 of file slam_toolbox_lifelong.cpp.

◆ computeScore()

double slam_toolbox::LifelongSlamToolbox::computeScore ( LocalizedRangeScan *  reference_scan,
Vertex< LocalizedRangeScan > *  candidate,
const double &  initial_score,
const int &  num_candidates 
)
protected

Definition at line 216 of file slam_toolbox_lifelong.cpp.

◆ computeScores()

ScoredVertices slam_toolbox::LifelongSlamToolbox::computeScores ( Vertices &  near_scans,
LocalizedRangeScan *  range_scan 
)
protected

Definition at line 255 of file slam_toolbox_lifelong.cpp.

◆ deserializePoseGraphCallback()

bool slam_toolbox::LifelongSlamToolbox::deserializePoseGraphCallback ( slam_toolbox_msgs::DeserializePoseGraph::Request &  req,
slam_toolbox_msgs::DeserializePoseGraph::Response &  resp 
)
finaloverrideprotectedvirtual

Reimplemented from slam_toolbox::SlamToolbox.

Definition at line 320 of file slam_toolbox_lifelong.cpp.

◆ evaluateNodeDepreciation()

void slam_toolbox::LifelongSlamToolbox::evaluateNodeDepreciation ( LocalizedRangeScan *  range_scan)
protected

Definition at line 99 of file slam_toolbox_lifelong.cpp.

◆ FindScansWithinRadius()

Vertices slam_toolbox::LifelongSlamToolbox::FindScansWithinRadius ( LocalizedRangeScan *  scan,
const double &  radius 
)
protected

Definition at line 137 of file slam_toolbox_lifelong.cpp.

◆ laserCallback()

void slam_toolbox::LifelongSlamToolbox::laserCallback ( const sensor_msgs::LaserScan::ConstPtr &  scan)
finaloverrideprotectedvirtual

Implements slam_toolbox::SlamToolbox.

Definition at line 68 of file slam_toolbox_lifelong.cpp.

◆ removeFromSlamGraph()

void slam_toolbox::LifelongSlamToolbox::removeFromSlamGraph ( Vertex< LocalizedRangeScan > *  vertex)
protected

Definition at line 296 of file slam_toolbox_lifelong.cpp.

◆ updateScoresSlamGraph()

void slam_toolbox::LifelongSlamToolbox::updateScoresSlamGraph ( const double &  score,
Vertex< LocalizedRangeScan > *  vertex 
)
protected

Definition at line 311 of file slam_toolbox_lifelong.cpp.

Member Data Documentation

◆ candidates_scale_

double slam_toolbox::LifelongSlamToolbox::candidates_scale_
protected

Definition at line 63 of file slam_toolbox_lifelong.hpp.

◆ constraint_scale_

double slam_toolbox::LifelongSlamToolbox::constraint_scale_
protected

Definition at line 62 of file slam_toolbox_lifelong.hpp.

◆ iou_match_

double slam_toolbox::LifelongSlamToolbox::iou_match_
protected

Definition at line 64 of file slam_toolbox_lifelong.hpp.

◆ iou_thresh_

double slam_toolbox::LifelongSlamToolbox::iou_thresh_
protected

Definition at line 59 of file slam_toolbox_lifelong.hpp.

◆ nearby_penalty_

double slam_toolbox::LifelongSlamToolbox::nearby_penalty_
protected

Definition at line 65 of file slam_toolbox_lifelong.hpp.

◆ overlap_scale_

double slam_toolbox::LifelongSlamToolbox::overlap_scale_
protected

Definition at line 61 of file slam_toolbox_lifelong.hpp.

◆ removal_score_

double slam_toolbox::LifelongSlamToolbox::removal_score_
protected

Definition at line 60 of file slam_toolbox_lifelong.hpp.

◆ use_tree_

bool slam_toolbox::LifelongSlamToolbox::use_tree_
protected

Definition at line 58 of file slam_toolbox_lifelong.hpp.


The documentation for this class was generated from the following files:


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:50