karto_scan_matcher::KartoScanMatcher Class Reference

Wraps the Karto Scan matcher. More...

#include <karto_scan_matcher.h>

List of all members.

Public Member Functions

 KartoScanMatcher (const sensor_msgs::LaserScan &init_scan, const geometry_msgs::Pose2D &laser_pose, const DoubleVector &search_sizes, const DoubleVector &search_resolutions)
 Constructor when we have multiple matchers we want to use in sequence (increasingly fine).
 KartoScanMatcher (const sensor_msgs::LaserScan &init_scan, const geometry_msgs::Pose2D &laser_pose, double search_space_size, double search_grid_resolution)
 Constructor when laser relative pose is known.
 KartoScanMatcher (const sensor_msgs::LaserScan &init_scan, const tf::TransformListener &tf, double search_space_size, double search_grid_resolution)
 Constructor.
ScanMatchResult scanMatch (const sensor_msgs::LaserScan &scan, const geometry_msgs::Pose2D &pose, const vector< ScanWithPose > &reference_scans) const
 Match scans.
void setPenalizeDistance (bool penalize)
 Set flag indicating whether to penalize distance from initial estimate in scan matching.

Private Types

typedef boost::shared_ptr
< karto::Mapper > 
MapperPtr
typedef boost::shared_ptr
< karto::ScanMatcher > 
MatcherPtr

Private Member Functions

void initialize (const sensor_msgs::LaserScan &init_scan, const geometry_msgs::Pose2D &laser_pose, const DoubleVector &search_space_sizes, const DoubleVector &search_space_resolutions)

Private Attributes

boost::shared_ptr< karto::Dataset > dataset_
karto::LaserRangeFinder * laser_
std::vector< MapperPtrmappers_
std::vector< MatcherPtrmatchers_
bool penalize_distance_

Detailed Description

Wraps the Karto Scan matcher.

To use it, just construct an instance and call scanMatch as many times as you want. The main constraint is that laser offset and frame should be the same for all scans passed into the constructor and to scanMatch.

All scans are assumed to be in the base_laser_link frame, and poses are of the base_link frame.

Definition at line 105 of file karto_scan_matcher.h.


Member Typedef Documentation

typedef boost::shared_ptr<karto::Mapper> karto_scan_matcher::KartoScanMatcher::MapperPtr [private]

Definition at line 162 of file karto_scan_matcher.h.

typedef boost::shared_ptr<karto::ScanMatcher> karto_scan_matcher::KartoScanMatcher::MatcherPtr [private]

Definition at line 161 of file karto_scan_matcher.h.


Constructor & Destructor Documentation

karto_scan_matcher::KartoScanMatcher::KartoScanMatcher ( const sensor_msgs::LaserScan &  init_scan,
const tf::TransformListener &  tf,
double  search_space_size,
double  search_grid_resolution 
)

Constructor.

Parameters:
init_scan A scan that's used to set the parameters of the laser
tf Used to figure out the offset of the laser (we're assuming this will be fixed henceforth)
name Prefixed to the sensor name (since all karto instances in this process have a global namespace)
search_space_size Size in meters of space to search over centered at initial estimate
search_grid_resolution Resolution (m/cell) of discretization of search space

Other parameters: penalize_distance is true on construction

karto_scan_matcher::KartoScanMatcher::KartoScanMatcher ( const sensor_msgs::LaserScan &  init_scan,
const geometry_msgs::Pose2D &  laser_pose,
double  search_space_size,
double  search_grid_resolution 
)

Constructor when laser relative pose is known.

Parameters:
init_scan A scan that's used to set the parameters of the laser
name Prefixed to the sensor name (since all karto instances in this process have a global namespace)
laser_pose Relative pose of the laser w.r.t. the base
search_space_size Size in meters of space to search over centered at initial estimate
search_grid_resolution Resolution (m/cell) of discretization of search space

Other parameters: penalize_distance is true on construction

karto_scan_matcher::KartoScanMatcher::KartoScanMatcher ( const sensor_msgs::LaserScan &  init_scan,
const geometry_msgs::Pose2D &  laser_pose,
const DoubleVector search_sizes,
const DoubleVector search_resolutions 
)

Constructor when we have multiple matchers we want to use in sequence (increasingly fine).

Parameters:
init_scan A scan that's used to set the parameters of the laser
laser_pose Relative pose of the laser w.r.t. the base
name Prefixed to the sensor name (since all karto instances in this process have a global namespace)
search_space_sizes The sizes in meters of space to search over at each level (coarse to fine)
search_grid_resolutions Resolutions (m/cells) of discretizations of search space (match up with the ones in search_space_sizes)

Other parameters: penealize_distance is true on construction

Definition at line 92 of file karto_scan_matcher.cpp.


Member Function Documentation

void karto_scan_matcher::KartoScanMatcher::initialize ( const sensor_msgs::LaserScan &  init_scan,
const geometry_msgs::Pose2D &  laser_pose,
const DoubleVector search_space_sizes,
const DoubleVector search_space_resolutions 
) [private]
ScanMatchResult karto_scan_matcher::KartoScanMatcher::scanMatch ( const sensor_msgs::LaserScan &  scan,
const geometry_msgs::Pose2D &  pose,
const vector< ScanWithPose > &  reference_scans 
) const

Match scans.

Parameters:
scan The current laser scan.
pose The initial estimate of the pose at which this scan was taken.
reference_scans Each of these is a scan, together with the pose at which it was taken
Return values:
The optimal pose, covariance, and response strength
void karto_scan_matcher::KartoScanMatcher::setPenalizeDistance ( bool  penalize  ) 

Set flag indicating whether to penalize distance from initial estimate in scan matching.

Definition at line 150 of file karto_scan_matcher.cpp.


Member Data Documentation

boost::shared_ptr<karto::Dataset> karto_scan_matcher::KartoScanMatcher::dataset_ [private]

Definition at line 164 of file karto_scan_matcher.h.

karto::LaserRangeFinder* karto_scan_matcher::KartoScanMatcher::laser_ [private]

Definition at line 167 of file karto_scan_matcher.h.

Definition at line 166 of file karto_scan_matcher.h.

Definition at line 165 of file karto_scan_matcher.h.

Definition at line 169 of file karto_scan_matcher.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


karto_scan_matcher
Author(s): Bhaskara Marthi
autogenerated on Fri Jan 11 09:10:48 2013