slam_toolbox_common.hpp
Go to the documentation of this file.
1 /*
2  * slam_toolbox
3  * Copyright (c) 2008, Willow Garage, Inc.
4  * Copyright Work Modifications (c) 2018, Simbe Robotics, Inc.
5  * Copyright Work Modifications (c) 2019, Steve Macenski
6  *
7  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
8  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
9  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
10  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
11  *
12  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
13  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
14  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
15  * CONDITIONS.
16  *
17  */
18 
19 #ifndef SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
20 #define SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
21 
22 #include "ros/ros.h"
26 #include "tf2_ros/message_filter.h"
29 
30 #include "pluginlib/class_loader.h"
31 
39 
40 #include <string>
41 #include <map>
42 #include <vector>
43 #include <queue>
44 #include <cstdlib>
45 #include <fstream>
46 #include <boost/thread.hpp>
47 #include <sys/resource.h>
48 
49 namespace slam_toolbox
50 {
51 
52 // dirty, dirty cheat I love
53 using namespace ::toolbox_types;
54 
56 {
57 public:
59  ~SlamToolbox();
60 
61 protected:
62  // threads
63  void publishVisualizations();
64  void publishTransformLoop(const double& transform_publish_period);
65 
66  // setup
67  void setParams(ros::NodeHandle& nh);
68  void setSolver(ros::NodeHandle& private_nh_);
70 
71  // callbacks
72  virtual void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan) = 0;
73  bool mapCallback(nav_msgs::GetMap::Request& req,
74  nav_msgs::GetMap::Response& res);
75  virtual bool serializePoseGraphCallback(slam_toolbox_msgs::SerializePoseGraph::Request& req,
76  slam_toolbox_msgs::SerializePoseGraph::Response& resp);
77  virtual bool deserializePoseGraphCallback(slam_toolbox_msgs::DeserializePoseGraph::Request& req,
78  slam_toolbox_msgs::DeserializePoseGraph::Response& resp);
79  void loadSerializedPoseGraph(std::unique_ptr<karto::Mapper>&, std::unique_ptr<karto::Dataset>&);
81 
82  // functional bits
83  karto::LaserRangeFinder* getLaser(const sensor_msgs::LaserScan::ConstPtr& scan);
84  virtual karto::LocalizedRangeScan* addScan(karto::LaserRangeFinder* laser, const sensor_msgs::LaserScan::ConstPtr& scan,
85  karto::Pose2& karto_pose);
86  karto::LocalizedRangeScan* addScan(karto::LaserRangeFinder* laser, PosedScan& scanWPose);
87  bool updateMap();
89  const karto::Pose2& karto_pose, const ros::Time& t, const bool& update_reprocessing_transform);
91  const sensor_msgs::LaserScan::ConstPtr& scan,
92  karto::Pose2& karto_pose);
93  bool shouldStartWithPoseGraph(std::string& filename, geometry_msgs::Pose2D& pose, bool& start_at_dock);
94  bool shouldProcessScan(const sensor_msgs::LaserScan::ConstPtr& scan, const karto::Pose2& pose);
95  void publishPose(const karto::Pose2 & pose, const karto::Matrix3 & cov, const ros::Time & t);
96 
97  // pausing bits
98  bool isPaused(const PausedApplication& app);
99  bool pauseNewMeasurementsCallback(slam_toolbox_msgs::Pause::Request& req,
100  slam_toolbox_msgs::Pause::Response& resp);
101 
102  // ROS-y-ness
104  std::unique_ptr<tf2_ros::Buffer> tf_;
105  std::unique_ptr<tf2_ros::TransformListener> tfL_;
106  std::unique_ptr<tf2_ros::TransformBroadcaster> tfB_;
107  std::unique_ptr<message_filters::Subscriber<sensor_msgs::LaserScan> > scan_filter_sub_;
108  std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::LaserScan> > scan_filter_;
111 
112  // Storage for ROS parameters
116 
117  double resolution_;
121 
122  // Book keeping
123  std::unique_ptr<mapper_utils::SMapper> smapper_;
124  std::unique_ptr<karto::Dataset> dataset_;
125  std::map<std::string, laser_utils::LaserMetadata> lasers_;
126 
127  // helpers
128  std::unique_ptr<laser_utils::LaserAssistant> laser_assistant_;
129  std::unique_ptr<pose_utils::GetPoseHelper> pose_helper_;
130  std::unique_ptr<map_saver::MapSaver> map_saver_;
131  std::unique_ptr<loop_closure_assistant::LoopClosureAssistant> closure_assistant_;
132  std::unique_ptr<laser_utils::ScanHolder> scan_holder_;
133 
134  // Internal state
135  std::vector<std::unique_ptr<boost::thread> > threads_;
138  PausedState state_;
139  nav_msgs::GetMap::Response map_;
141  std::unique_ptr<karto::Pose2> process_near_pose_;
143 
144  // pluginlib
147 };
148 
149 } // end namespace
150 
151 #endif //SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
slam_toolbox::SlamToolbox::process_near_pose_
std::unique_ptr< karto::Pose2 > process_near_pose_
Definition: slam_toolbox_common.hpp:141
slam_toolbox::SlamToolbox
Definition: slam_toolbox_common.hpp:55
slam_toolbox::SlamToolbox::scan_holder_
std::unique_ptr< laser_utils::ScanHolder > scan_holder_
Definition: slam_toolbox_common.hpp:132
slam_toolbox::SlamToolbox::map_
nav_msgs::GetMap::Response map_
Definition: slam_toolbox_common.hpp:139
toolbox_types
Definition: toolbox_types.hpp:36
slam_toolbox::SlamToolbox::ssSerialize_
ros::ServiceServer ssSerialize_
Definition: slam_toolbox_common.hpp:110
toolbox_types::PausedApplication
PausedApplication
Definition: toolbox_types.hpp:76
slam_toolbox::SlamToolbox::ssMap_
ros::ServiceServer ssMap_
Definition: slam_toolbox_common.hpp:110
slam_toolbox::SlamToolbox::threads_
std::vector< std::unique_ptr< boost::thread > > threads_
Definition: slam_toolbox_common.hpp:135
slam_toolbox::SlamToolbox::scan_filter_
std::unique_ptr< tf2_ros::MessageFilter< sensor_msgs::LaserScan > > scan_filter_
Definition: slam_toolbox_common.hpp:108
slam_toolbox::SlamToolbox::solver_loader_
pluginlib::ClassLoader< karto::ScanSolver > solver_loader_
Definition: slam_toolbox_common.hpp:145
slam_toolbox::SlamToolbox::nh_
ros::NodeHandle nh_
Definition: slam_toolbox_common.hpp:103
ros::Publisher
slam_toolbox::SlamToolbox::getLaser
karto::LaserRangeFinder * getLaser(const sensor_msgs::LaserScan::ConstPtr &scan)
Definition: slam_toolbox_common.cpp:289
slam_toolbox::SlamToolbox::publishPose
void publishPose(const karto::Pose2 &pose, const karto::Matrix3 &cov, const ros::Time &t)
Definition: slam_toolbox_common.cpp:549
karto::LaserRangeFinder
Definition: Karto.h:3922
class_loader.h
boost::shared_ptr< karto::ScanSolver >
slam_toolbox::SlamToolbox::yaw_covariance_scale_
double yaw_covariance_scale_
Definition: slam_toolbox_common.hpp:119
slam_toolbox::SlamToolbox::getLocalizedRangeScan
karto::LocalizedRangeScan * getLocalizedRangeScan(karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
Definition: slam_toolbox_common.cpp:391
slam_toolbox::SlamToolbox::setSolver
void setSolver(ros::NodeHandle &private_nh_)
Definition: slam_toolbox_common.cpp:83
ros.h
slam_toolbox::SlamToolbox::updateMap
bool updateMap()
Definition: slam_toolbox_common.cpp:313
slam_toolbox::SlamToolbox::state_
PausedState state_
Definition: slam_toolbox_common.hpp:138
slam_toolbox::SlamToolbox::laser_assistant_
std::unique_ptr< laser_utils::LaserAssistant > laser_assistant_
Definition: slam_toolbox_common.hpp:128
slam_toolbox::SlamToolbox::transform_timeout_
ros::Duration transform_timeout_
Definition: slam_toolbox_common.hpp:114
slam_toolbox::SlamToolbox::shouldProcessScan
bool shouldProcessScan(const sensor_msgs::LaserScan::ConstPtr &scan, const karto::Pose2 &pose)
Definition: slam_toolbox_common.cpp:415
slam_toolbox::SlamToolbox::smapper_
std::unique_ptr< mapper_utils::SMapper > smapper_
Definition: slam_toolbox_common.hpp:123
slam_toolbox::SlamToolbox::deserializePoseGraphCallback
virtual bool deserializePoseGraphCallback(slam_toolbox_msgs::DeserializePoseGraph::Request &req, slam_toolbox_msgs::DeserializePoseGraph::Response &resp)
Definition: slam_toolbox_common.cpp:736
snap_utils.hpp
tf2::Stamped
karto::LocalizedRangeScan
Definition: Karto.h:5505
slam_toolbox::SlamToolbox::closure_assistant_
std::unique_ptr< loop_closure_assistant::LoopClosureAssistant > closure_assistant_
Definition: slam_toolbox_common.hpp:131
get_pose_helper.hpp
slam_toolbox::SlamToolbox::map_saver_
std::unique_ptr< map_saver::MapSaver > map_saver_
Definition: slam_toolbox_common.hpp:130
slam_toolbox::SlamToolbox::setTransformFromPoses
tf2::Stamped< tf2::Transform > setTransformFromPoses(const karto::Pose2 &pose, const karto::Pose2 &karto_pose, const ros::Time &t, const bool &update_reprocessing_transform)
Definition: slam_toolbox_common.cpp:340
slam_toolbox::SlamToolbox::isPaused
bool isPaused(const PausedApplication &app)
Definition: slam_toolbox_common.cpp:609
slam_toolbox::SlamToolbox::SlamToolbox
SlamToolbox(ros::NodeHandle &nh)
Definition: slam_toolbox_common.cpp:28
slam_toolbox::SlamToolbox::tfB_
std::unique_ptr< tf2_ros::TransformBroadcaster > tfB_
Definition: slam_toolbox_common.hpp:106
slam_toolbox::SlamToolbox::reprocessing_transform_
tf2::Transform reprocessing_transform_
Definition: slam_toolbox_common.hpp:142
transform_broadcaster.h
ros::ServiceServer
karto::Matrix3
Definition: Karto.h:2444
slam_toolbox::SlamToolbox::throttle_scans_
int throttle_scans_
Definition: slam_toolbox_common.hpp:115
slam_toolbox::SlamToolbox::publishVisualizations
void publishVisualizations()
Definition: slam_toolbox_common.cpp:191
slam_toolbox::SlamToolbox::enable_interactive_mode_
bool enable_interactive_mode_
Definition: slam_toolbox_common.hpp:120
slam_toolbox::SlamToolbox::sst_
ros::Publisher sst_
Definition: slam_toolbox_common.hpp:109
slam_toolbox::SlamToolbox::~SlamToolbox
~SlamToolbox()
Definition: slam_toolbox_common.cpp:65
message_filter.h
subscriber.h
slam_toolbox::SlamToolbox::serializePoseGraphCallback
virtual bool serializePoseGraphCallback(slam_toolbox_msgs::SerializePoseGraph::Request &req, slam_toolbox_msgs::SerializePoseGraph::Response &resp)
Definition: slam_toolbox_common.cpp:616
slam_toolbox::SlamToolbox::tf_buffer_dur_
ros::Duration tf_buffer_dur_
Definition: slam_toolbox_common.hpp:114
slam_toolbox::SlamToolbox::resolution_
double resolution_
Definition: slam_toolbox_common.hpp:117
slam_toolbox::SlamToolbox::tf_
std::unique_ptr< tf2_ros::Buffer > tf_
Definition: slam_toolbox_common.hpp:104
slam_toolbox::SlamToolbox::smapper_mutex_
boost::mutex smapper_mutex_
Definition: slam_toolbox_common.hpp:137
slam_toolbox::SlamToolbox::setROSInterfaces
void setROSInterfaces(ros::NodeHandle &node)
Definition: slam_toolbox_common.cpp:147
slam_toolbox::SlamToolbox::solver_
boost::shared_ptr< karto::ScanSolver > solver_
Definition: slam_toolbox_common.hpp:146
tf2::Transform
slam_toolbox::SlamToolbox::map_to_odom_
tf2::Transform map_to_odom_
Definition: slam_toolbox_common.hpp:136
slam_toolbox::SlamToolbox::mapCallback
bool mapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
Definition: slam_toolbox_common.cpp:574
slam_toolbox::SlamToolbox::lasers_
std::map< std::string, laser_utils::LaserMetadata > lasers_
Definition: slam_toolbox_common.hpp:125
slam_toolbox::SlamToolbox::map_frame_
std::string map_frame_
Definition: slam_toolbox_common.hpp:113
slam_toolbox::SlamToolbox::position_covariance_scale_
double position_covariance_scale_
Definition: slam_toolbox_common.hpp:118
pluginlib::ClassLoader< karto::ScanSolver >
slam_toolbox::SlamToolbox::setParams
void setParams(ros::NodeHandle &nh)
Definition: slam_toolbox_common.cpp:108
slam_toolbox::SlamToolbox::ssDesserialize_
ros::ServiceServer ssDesserialize_
Definition: slam_toolbox_common.hpp:110
slam_toolbox::SlamToolbox::loadSerializedPoseGraph
void loadSerializedPoseGraph(std::unique_ptr< karto::Mapper > &, std::unique_ptr< karto::Dataset > &)
Definition: slam_toolbox_common.cpp:635
app
app
toolbox_types.hpp
slam_toolbox::SlamToolbox::scan_topic_
std::string scan_topic_
Definition: slam_toolbox_common.hpp:113
transform_listener.h
slam_toolbox::SlamToolbox::loadPoseGraphByParams
void loadPoseGraphByParams(ros::NodeHandle &nh)
Definition: slam_toolbox_common.cpp:223
slam_toolbox::SlamToolbox::shouldStartWithPoseGraph
bool shouldStartWithPoseGraph(std::string &filename, geometry_msgs::Pose2D &pose, bool &start_at_dock)
Definition: slam_toolbox_common.cpp:250
slam_toolbox::SlamToolbox::first_measurement_
bool first_measurement_
Definition: slam_toolbox_common.hpp:120
slam_toolbox::SlamToolbox::processor_type_
ProcessType processor_type_
Definition: slam_toolbox_common.hpp:140
slam_toolbox::SlamToolbox::base_frame_
std::string base_frame_
Definition: slam_toolbox_common.hpp:113
ros::Time
slam_toolbox::SlamToolbox::addScan
virtual karto::LocalizedRangeScan * addScan(karto::LaserRangeFinder *laser, const sensor_msgs::LaserScan::ConstPtr &scan, karto::Pose2 &karto_pose)
Definition: slam_toolbox_common.cpp:476
slam_toolbox::SlamToolbox::dataset_
std::unique_ptr< karto::Dataset > dataset_
Definition: slam_toolbox_common.hpp:124
slam_toolbox::SlamToolbox::scan_filter_sub_
std::unique_ptr< message_filters::Subscriber< sensor_msgs::LaserScan > > scan_filter_sub_
Definition: slam_toolbox_common.hpp:107
slam_toolbox::SlamToolbox::minimum_time_interval_
ros::Duration minimum_time_interval_
Definition: slam_toolbox_common.hpp:114
slam_toolbox::SlamToolbox::tfL_
std::unique_ptr< tf2_ros::TransformListener > tfL_
Definition: slam_toolbox_common.hpp:105
slam_toolbox::SlamToolbox::pose_helper_
std::unique_ptr< pose_utils::GetPoseHelper > pose_helper_
Definition: slam_toolbox_common.hpp:129
slam_toolbox::SlamToolbox::map_name_
std::string map_name_
Definition: slam_toolbox_common.hpp:113
tf2_geometry_msgs.h
loop_closure_assistant.hpp
slam_toolbox::SlamToolbox::sstm_
ros::Publisher sstm_
Definition: slam_toolbox_common.hpp:109
slam_toolbox
Definition: slam_toolbox_lifelong.hpp:24
process_constraints.filename
filename
Definition: process_constraints.py:114
karto::Pose2
Definition: Karto.h:2046
slam_toolbox::SlamToolbox::pauseNewMeasurementsCallback
bool pauseNewMeasurementsCallback(slam_toolbox_msgs::Pause::Request &req, slam_toolbox_msgs::Pause::Response &resp)
Definition: slam_toolbox_common.cpp:592
toolbox_types::ProcessType
ProcessType
Definition: toolbox_types.hpp:84
slam_toolbox::SlamToolbox::map_to_odom_mutex_
boost::mutex map_to_odom_mutex_
Definition: slam_toolbox_common.hpp:137
slam_toolbox::SlamToolbox::publishTransformLoop
void publishTransformLoop(const double &transform_publish_period)
Definition: slam_toolbox_common.cpp:166
ros::Duration
Matrix3x3.h
slam_toolbox::SlamToolbox::odom_frame_
std::string odom_frame_
Definition: slam_toolbox_common.hpp:113
laser_utils.hpp
t
geometry_msgs::TransformStamped t
slam_toolbox::SlamToolbox::pose_mutex_
boost::mutex pose_mutex_
Definition: slam_toolbox_common.hpp:137
ros::NodeHandle
map_saver.hpp
slam_toolbox::SlamToolbox::pose_pub_
ros::Publisher pose_pub_
Definition: slam_toolbox_common.hpp:109
slam_mapper.hpp
slam_toolbox::SlamToolbox::ssPauseMeasurements_
ros::ServiceServer ssPauseMeasurements_
Definition: slam_toolbox_common.hpp:110
slam_toolbox::SlamToolbox::laserCallback
virtual void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan)=0


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56