slam_toolbox_sync.hpp
Go to the documentation of this file.
1 /*
2  * slam_toolbox
3  * Copyright Work Modifications (c) 2018, Simbe Robotics, Inc.
4  * Copyright Work Modifications (c) 2019, Steve Macenski
5  *
6  * THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
7  * COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
8  * COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
9  * AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
10  *
11  * BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE TO
12  * BE BOUND BY THE TERMS OF THIS LICENSE. THE LICENSOR GRANTS YOU THE RIGHTS
13  * CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
14  * CONDITIONS.
15  *
16  */
17 
18 /* Author: Steven Macenski */
19 
20 #ifndef SLAM_TOOLBOX_SLAM_TOOLBOX_SYNC_H_
21 #define SLAM_TOOLBOX_SLAM_TOOLBOX_SYNC_H_
22 
24 
25 namespace slam_toolbox
26 {
27 
29 {
30 public:
33  void run();
34 
35 protected:
36  virtual void laserCallback(const sensor_msgs::LaserScan::ConstPtr& scan) override final;
37  bool clearQueueCallback(slam_toolbox_msgs::ClearQueue::Request& req, slam_toolbox_msgs::ClearQueue::Response& resp);
38  virtual bool deserializePoseGraphCallback(slam_toolbox_msgs::DeserializePoseGraph::Request& req,
39  slam_toolbox_msgs::DeserializePoseGraph::Response& resp) override final;
40 
41  std::queue<PosedScan> q_;
43  boost::mutex q_mutex_;
44 };
45 
46 }
47 
48 #endif //SLAM_TOOLBOX_SLAM_TOOLBOX_SYNC_NODE_H_
slam_toolbox::SynchronousSlamToolbox::q_mutex_
boost::mutex q_mutex_
Definition: slam_toolbox_sync.hpp:43
slam_toolbox::SlamToolbox
Definition: slam_toolbox_common.hpp:55
slam_toolbox::SynchronousSlamToolbox::~SynchronousSlamToolbox
~SynchronousSlamToolbox()
Definition: slam_toolbox_sync.hpp:32
slam_toolbox_common.hpp
ros::ServiceServer
slam_toolbox::SynchronousSlamToolbox
Definition: slam_toolbox_sync.hpp:28
slam_toolbox::SynchronousSlamToolbox::run
void run()
Definition: slam_toolbox_sync.cpp:40
slam_toolbox::SynchronousSlamToolbox::clearQueueCallback
bool clearQueueCallback(slam_toolbox_msgs::ClearQueue::Request &req, slam_toolbox_msgs::ClearQueue::Response &resp)
Definition: slam_toolbox_sync.cpp:109
slam_toolbox::SynchronousSlamToolbox::q_
std::queue< PosedScan > q_
Definition: slam_toolbox_sync.hpp:41
slam_toolbox
Definition: slam_toolbox_lifelong.hpp:24
slam_toolbox::SynchronousSlamToolbox::ssClear_
ros::ServiceServer ssClear_
Definition: slam_toolbox_sync.hpp:42
slam_toolbox::SynchronousSlamToolbox::SynchronousSlamToolbox
SynchronousSlamToolbox(ros::NodeHandle &nh)
Definition: slam_toolbox_sync.cpp:26
slam_toolbox::SynchronousSlamToolbox::laserCallback
virtual void laserCallback(const sensor_msgs::LaserScan::ConstPtr &scan) override final
Definition: slam_toolbox_sync.cpp:77
slam_toolbox::SynchronousSlamToolbox::deserializePoseGraphCallback
virtual bool deserializePoseGraphCallback(slam_toolbox_msgs::DeserializePoseGraph::Request &req, slam_toolbox_msgs::DeserializePoseGraph::Response &resp) override final
Definition: slam_toolbox_sync.cpp:124
ros::NodeHandle


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