19 #ifndef SLAM_TOOLBOX_LASER_UTILS_H_
20 #define SLAM_TOOLBOX_LASER_UTILS_H_
33 inline std::vector<double>
scanToReadings(
const sensor_msgs::LaserScan& scan,
const bool& inverted)
35 std::vector<double> readings;
39 for(std::vector<float>::const_reverse_iterator it = scan.ranges.rbegin(); it != scan.ranges.rend(); ++it)
41 readings.push_back(*it);
46 for(std::vector<float>::const_iterator it = scan.ranges.begin(); it != scan.ranges.end(); ++it)
48 readings.push_back(*it);
64 void invertScan(sensor_msgs::LaserScan& scan)
const;
94 ScanHolder(std::map<std::string, laser_utils::LaserMetadata>& lasers);
97 void addScan(
const sensor_msgs::LaserScan scan);
101 std::map<std::string, laser_utils::LaserMetadata>&
lasers_;
106 #endif //SLAM_TOOLBOX_LASER_UTILS_H_