#include <laser_slam/scan_matching.h>
#include <laser_slam/LocalizedScan.h>
#include <pose_graph/graph_db.h>
#include <pose_graph/diff_subscriber.h>
#include <graph_mapping_msgs/LocalizationDistribution.h>
#include <graph_mapping_msgs/NodePoses.h>
#include <geometry_msgs/Pose2D.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <string>
#include <vector>
#include <ostream>
#include "ros/serialization.h"
#include "ros/builtin_message_traits.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include "ros/time.h"
#include "std_msgs/Header.h"
#include "geometry_msgs/Pose.h"
#include "geometry_msgs/Transform.h"
#include <tf/transform_listener.h>
#include <boost/thread.hpp>
#include <boost/optional.hpp>
Go to the source code of this file.
Classes | |
class | laser_slam::ScanMatchLocalizer |
Localization based on scan matching. More... | |
Namespaces | |
namespace | laser_slam |
Variables | |
const double | laser_slam::GLOBAL_MATCH_MIN_RESPONSE = 0.6 |
Definition of ScanMatchLocalizer class
Definition in file scan_match_localization.h.