scan_matching.h File Reference

#include <laser_slam/LocalizedScan.h>
#include <laser_slam/util.h>
#include <karto_scan_matcher/karto_scan_matcher.h>
#include <map>
#include <vector>
#include "Karto.h"
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <sensor_msgs/LaserScan.h>
#include <geometry_msgs/Pose2D.h>
#include <boost/shared_ptr.hpp>
#include <boost/optional.hpp>
#include "Core"
#include "LU"
#include "Cholesky"
#include "QR"
#include "SVD"
#include "Geometry"
#include "Eigenvalues"
#include <pose_graph/constraint_graph.h>
#include <pose_graph/graph_db.h>
Include dependency graph for scan_matching.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  laser_slam

Typedefs

typedef boost::shared_ptr
< karto_scan_matcher::KartoScanMatcher > 
laser_slam::MatcherPtr

Functions

karto_scan_matcher::ScanMatchResult laser_slam::globalLocalization (const pose_graph::ConstraintGraph &g, MatcherPtr local_matcher, const pose_graph::NodeSet &nodes, const ScanMap &scans, const sensor_msgs::LaserScan &scan, const tf::Pose &laser_offset, double global_resolution, double angular_resolution, double min_x, double min_y, double max_x, double max_y)
 Basically, do repeated local matches by discretizing the world using global_resolution.
karto_scan_matcher::ScanMatchResult laser_slam::globalLocalization (const pose_graph::ConstraintGraph &g, MatcherPtr local_matcher, const pose_graph::NodeSet &nodes, const ScanMap &scans, const sensor_msgs::LaserScan &scan, const tf::Pose &laser_offset, double global_resolution, double angular_resolution)
 Basically, do repeated local matches by discretizing the world using global_resolution.
karto_scan_matcher::ScanMatchResult laser_slam::scanMatchNodes (const pose_graph::ConstraintGraph &g, MatcherPtr matcher, const pose_graph::NodeSet &nodes, const ScanMap &scans, const sensor_msgs::LaserScan &scan, const tf::Pose &init_estimate, const tf::Pose &laser_offset)

Detailed Description

Functions to do with laser scan matching

Author:
Bhaskara Marthi

Definition in file scan_matching.h.

 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


laser_slam
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 09:53:29 2013