Class SlamToolbox
Defined in File slam_toolbox_common.hpp
Inheritance Relationships
Base Type
public rclcpp_lifecycle::LifecycleNode
Derived Types
public slam_toolbox::AsynchronousSlamToolbox
(Class AsynchronousSlamToolbox)public slam_toolbox::LifelongSlamToolbox
(Class LifelongSlamToolbox)public slam_toolbox::LocalizationSlamToolbox
(Class LocalizationSlamToolbox)public slam_toolbox::SynchronousSlamToolbox
(Class SynchronousSlamToolbox)
Class Documentation
-
class SlamToolbox : public rclcpp_lifecycle::LifecycleNode
Subclassed by slam_toolbox::AsynchronousSlamToolbox, slam_toolbox::LifelongSlamToolbox, slam_toolbox::LocalizationSlamToolbox, slam_toolbox::SynchronousSlamToolbox
Public Functions
-
explicit SlamToolbox(rclcpp::NodeOptions)
-
SlamToolbox()
-
virtual ~SlamToolbox()
-
virtual void loadPoseGraphByParams()
-
void createBond()
-
void destroyBond()
-
CallbackReturn on_configure(const rclcpp_lifecycle::State&) override
-
CallbackReturn on_activate(const rclcpp_lifecycle::State&) override
-
CallbackReturn on_deactivate(const rclcpp_lifecycle::State&) override
-
CallbackReturn on_cleanup(const rclcpp_lifecycle::State&) override
-
CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Protected Functions
-
void publishVisualizations()
-
void publishTransformLoop(const double &transform_publish_period)
-
void setParams()
-
void setSolver()
-
void setROSInterfaces()
-
void loadSerializedPoseGraph(std::unique_ptr<karto::Mapper>&, std::unique_ptr<karto::Dataset>&)
-
karto::LocalizedRangeScan *addScan(karto::LaserRangeFinder *laser, PosedScan &scanWPose)
-
bool updateMap()
-
tf2::Stamped<tf2::Transform> setTransformFromPoses(const karto::Pose2 &pose, const karto::Pose2 &karto_pose, const rclcpp::Time &t, const bool &update_reprocessing_transform)
-
bool shouldStartWithPoseGraph(std::string &filename, geometry_msgs::msg::Pose2D &pose, bool &start_at_dock)
-
void publishPose(const Pose2 &pose, const Matrix3 &cov, const rclcpp::Time &t)
-
bool isPaused(const PausedApplication &app)
Protected Attributes
-
std::unique_ptr<tf2_ros::Buffer> tf_
-
std::unique_ptr<tf2_ros::TransformListener> tfL_
-
std::unique_ptr<tf2_ros::TransformBroadcaster> tfB_
-
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan, rclcpp_lifecycle::LifecycleNode>> scan_filter_sub_
-
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> scan_filter_
-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid>> sst_
-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::MapMetaData>> sstm_
-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PoseWithCovarianceStamped>> pose_pub_
-
std::shared_ptr<rclcpp::Service<nav_msgs::srv::GetMap>> ssMap_
-
std::shared_ptr<rclcpp::Service<slam_toolbox::srv::Pause>> ssPauseMeasurements_
-
std::shared_ptr<rclcpp::Service<slam_toolbox::srv::SerializePoseGraph>> ssSerialize_
-
std::shared_ptr<rclcpp::Service<slam_toolbox::srv::DeserializePoseGraph>> ssDesserialize_
-
std::shared_ptr<rclcpp::Service<slam_toolbox::srv::Reset>> ssReset_
-
std::string odom_frame_
-
std::string map_frame_
-
std::string base_frame_
-
std::string map_name_
-
std::string scan_topic_
-
bool use_map_saver_
-
bool use_lifecycle_manager_
-
rclcpp::Duration transform_timeout_
-
rclcpp::Duration minimum_time_interval_
-
std_msgs::msg::Header scan_header
-
int throttle_scans_
-
int scan_queue_size_
-
double resolution_
-
double position_covariance_scale_
-
double yaw_covariance_scale_
-
bool first_measurement_
-
bool enable_interactive_mode_
-
std::unique_ptr<karto::Dataset> dataset_
-
std::map<std::string, laser_utils::LaserMetadata> lasers_
-
std::unique_ptr<laser_utils::LaserAssistant> laser_assistant_
-
std::unique_ptr<pose_utils::GetPoseHelper> pose_helper_
-
std::unique_ptr<loop_closure_assistant::LoopClosureAssistant> closure_assistant_
-
std::unique_ptr<laser_utils::ScanHolder> scan_holder_
-
std::vector<std::unique_ptr<boost::thread>> threads_
-
tf2::Transform map_to_odom_
-
boost::mutex map_to_odom_mutex_
-
boost::mutex smapper_mutex_
-
boost::mutex pose_mutex_
-
PausedState state_
-
nav_msgs::srv::GetMap::Response map_
-
ProcessType processor_type_
-
std::unique_ptr<karto::Pose2> process_near_pose_
-
tf2::Transform reprocessing_transform_
-
pluginlib::ClassLoader<karto::ScanSolver> solver_loader_
-
std::shared_ptr<karto::ScanSolver> solver_
-
std::unique_ptr<bond::Bond> bond_ = {nullptr}
-
explicit SlamToolbox(rclcpp::NodeOptions)