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);
91 const sensor_msgs::LaserScan::ConstPtr& scan,
100 slam_toolbox_msgs::Pause::Response& resp);
104 std::unique_ptr<tf2_ros::Buffer>
tf_;
105 std::unique_ptr<tf2_ros::TransformListener>
tfL_;
106 std::unique_ptr<tf2_ros::TransformBroadcaster>
tfB_;
108 std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::LaserScan> >
scan_filter_;
125 std::map<std::string, laser_utils::LaserMetadata>
lasers_;
135 std::vector<std::unique_ptr<boost::thread> >
threads_;
139 nav_msgs::GetMap::Response
map_;
151 #endif //SLAM_TOOLBOX_SLAM_TOOLBOX_COMMON_H_
geometry_msgs::TransformStamped t
slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56