Go to the documentation of this file.
19 #ifndef SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
20 #define SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
46 #include <boost/thread.hpp>
47 #include <sys/resource.h>
72 virtual void laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan) = 0;
74 nav_msgs::GetMap::Response& res);
76 slam_toolbox_msgs::SerializePoseGraph::Response& resp);
78 slam_toolbox_msgs::DeserializePoseGraph::Response& resp);
79 virtual bool resetCallback(slam_toolbox_msgs::Reset::Request& req,
80 slam_toolbox_msgs::Reset::Response& resp);
93 const sensor_msgs::LaserScan::ConstPtr& scan,
102 slam_toolbox_msgs::Pause::Response& resp);
106 std::unique_ptr<tf2_ros::Buffer>
tf_;
107 std::unique_ptr<tf2_ros::TransformListener>
tfL_;
108 std::unique_ptr<tf2_ros::TransformBroadcaster>
tfB_;
110 std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::LaserScan> >
scan_filter_;
127 std::map<std::string, laser_utils::LaserMetadata>
lasers_;
137 std::vector<std::unique_ptr<boost::thread> >
threads_;
141 nav_msgs::GetMap::Response
map_;
153 #endif //SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
geometry_msgs::TransformStamped t
slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 23 2025 03:37:19