Public Member Functions | Protected Member Functions | List of all members
slam_toolbox::AsynchronousSlamToolbox Class Reference

#include <slam_toolbox_async.hpp>

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

Public Member Functions

 AsynchronousSlamToolbox (ros::NodeHandle &nh)
 
 ~AsynchronousSlamToolbox ()
 
- Public Member Functions inherited from slam_toolbox::SlamToolbox
 SlamToolbox (ros::NodeHandle &nh)
 
 ~SlamToolbox ()
 

Protected Member Functions

virtual bool deserializePoseGraphCallback (slam_toolbox_msgs::DeserializePoseGraph::Request &req, slam_toolbox_msgs::DeserializePoseGraph::Response &resp) override final
 
virtual void laserCallback (const sensor_msgs::LaserScan::ConstPtr &scan) override final
 
- 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 ()
 

Additional Inherited Members

- 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 28 of file slam_toolbox_async.hpp.

Constructor & Destructor Documentation

◆ AsynchronousSlamToolbox()

slam_toolbox::AsynchronousSlamToolbox::AsynchronousSlamToolbox ( ros::NodeHandle nh)

Definition at line 26 of file slam_toolbox_async.cpp.

◆ ~AsynchronousSlamToolbox()

slam_toolbox::AsynchronousSlamToolbox::~AsynchronousSlamToolbox ( )
inline

Definition at line 32 of file slam_toolbox_async.hpp.

Member Function Documentation

◆ deserializePoseGraphCallback()

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

Reimplemented from slam_toolbox::SlamToolbox.

Definition at line 60 of file slam_toolbox_async.cpp.

◆ laserCallback()

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

Implements slam_toolbox::SlamToolbox.

Definition at line 34 of file slam_toolbox_async.cpp.


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