laser_slam::ScanMatchLocalizer Class Reference

Localization based on scan matching. More...

#include <scan_match_localization.h>

List of all members.

Public Member Functions

 ScanMatchLocalizer (ros::NodeHandle param_nh, boost::shared_ptr< tf::TransformListener > tf)

Private Member Functions

void adjustInitialPose (const tf::Pose &p, const pose_graph::ConstraintGraph &g, const pose_graph::NodeSet &comp, double global_loc_radius)
bool closerTo (const pg::ConstraintGraph &g, const btVector3 &barycenter, const unsigned n1, const unsigned n2) const
unsigned closestNode (const pg::ConstraintGraph &g, const pg::NodeSet &nodes, const btVector3 &barycenter) const
void diffCB (boost::optional< const msg::ConstraintGraphDiff & > diff, const pg::ConstraintGraph &graph)
boost::optional
< tf::StampedTransform > 
fixedFramePoseAt (const ros::Time &t)
void matchCB (const kidnapped_robot::MatchResult &match)
void recomputeOptimizedPoses (pg::ConstraintGraph *g, const pg::NodeSet &comp)
void setInitialPose (const geometry_msgs::PoseWithCovarianceStamped &m)
void storeScan (sensor_msgs::LaserScan::ConstPtr scan)
void update (const ros::TimerEvent &e)
void updateUsingFixedFrame ()

Private Attributes

const double angular_resolution_
const std::string base_frame_
warehouse::WarehouseClient db_
pg::DiffSubscriber diff_sub_
const bool do_global_localization_
const
pose_graph::CachedNodeMap
< geometry_msgs::Pose > 
ff_poses_
const std::string fixed_frame_
ros::ServiceClient get_poses_client_
ros::Publisher image_save_pub_
ros::Subscriber init_pose_sub_
sensor_msgs::LaserScan::ConstPtr initialization_scan_
bool initialized_
tf::Pose laser_offset_
msg::LocalizationDistribution::Ptr last_loc_
boost::optional< ros::Time > last_match_request_time_
sensor_msgs::LaserScan::ConstPtr last_scan_
ros::Publisher loc_pub_
unsigned match_count_
const double match_radius_
ros::Publisher match_req_pub_
const double match_resolution_
boost::optional
< kidnapped_robot::MatchResult > 
match_result_
ros::Subscriber match_sub_
MatcherPtr matcher_
const double max_nbd_size_
boost::mutex mutex_
ros::NodeHandle nh_
const double odom_noise_
const std::string opt_frame_
pg::NodePoseMap opt_poses_
bool optimize_flag_
ros::NodeHandle param_nh_
const double scan_match_proportion_
ros::Subscriber scan_sub_
const ScanMap scans_
boost::shared_ptr
< tf::TransformListener > 
tf_
const double update_rate_
ros::Timer update_timer_
const double window_size_

Detailed Description

Localization based on scan matching.

Definition at line 57 of file scan_match_localization.h.


Constructor & Destructor Documentation

laser_slam::ScanMatchLocalizer::ScanMatchLocalizer ( ros::NodeHandle  param_nh,
boost::shared_ptr< tf::TransformListener >  tf 
)

Definition at line 74 of file scan_match_localization.cpp.


Member Function Documentation

void laser_slam::ScanMatchLocalizer::adjustInitialPose ( const tf::Pose &  p,
const pose_graph::ConstraintGraph &  g,
const pose_graph::NodeSet &  comp,
double  global_loc_radius 
) [private]
bool laser_slam::ScanMatchLocalizer::closerTo ( const pg::ConstraintGraph &  g,
const btVector3 &  barycenter,
const unsigned  n1,
const unsigned  n2 
) const [private]

Definition at line 127 of file scan_match_localization.cpp.

unsigned laser_slam::ScanMatchLocalizer::closestNode ( const pg::ConstraintGraph &  g,
const pg::NodeSet &  nodes,
const btVector3 &  barycenter 
) const [private]

Definition at line 144 of file scan_match_localization.cpp.

void laser_slam::ScanMatchLocalizer::diffCB ( boost::optional< const msg::ConstraintGraphDiff & >  diff,
const pg::ConstraintGraph &  graph 
) [private]

Definition at line 188 of file scan_match_localization.cpp.

boost::optional< tf::StampedTransform > laser_slam::ScanMatchLocalizer::fixedFramePoseAt ( const ros::Time &  t  )  [private]

Definition at line 490 of file scan_match_localization.cpp.

void laser_slam::ScanMatchLocalizer::matchCB ( const kidnapped_robot::MatchResult &  match  )  [private]
void laser_slam::ScanMatchLocalizer::recomputeOptimizedPoses ( pg::ConstraintGraph *  g,
const pg::NodeSet &  comp 
) [private]

Definition at line 158 of file scan_match_localization.cpp.

void laser_slam::ScanMatchLocalizer::setInitialPose ( const geometry_msgs::PoseWithCovarianceStamped &  m  )  [private]
void laser_slam::ScanMatchLocalizer::storeScan ( sensor_msgs::LaserScan::ConstPtr  scan  )  [private]
void laser_slam::ScanMatchLocalizer::update ( const ros::TimerEvent &  e  )  [private]

Definition at line 337 of file scan_match_localization.cpp.

void laser_slam::ScanMatchLocalizer::updateUsingFixedFrame (  )  [private]

Definition at line 297 of file scan_match_localization.cpp.


Member Data Documentation

Definition at line 94 of file scan_match_localization.h.

const std::string laser_slam::ScanMatchLocalizer::base_frame_ [private]

Definition at line 88 of file scan_match_localization.h.

warehouse::WarehouseClient laser_slam::ScanMatchLocalizer::db_ [private]

Definition at line 119 of file scan_match_localization.h.

pg::DiffSubscriber laser_slam::ScanMatchLocalizer::diff_sub_ [private]

Definition at line 126 of file scan_match_localization.h.

Definition at line 95 of file scan_match_localization.h.

const pose_graph::CachedNodeMap<geometry_msgs::Pose> laser_slam::ScanMatchLocalizer::ff_poses_ [private]

Definition at line 121 of file scan_match_localization.h.

const std::string laser_slam::ScanMatchLocalizer::fixed_frame_ [private]

Definition at line 87 of file scan_match_localization.h.

Definition at line 127 of file scan_match_localization.h.

Definition at line 124 of file scan_match_localization.h.

Definition at line 125 of file scan_match_localization.h.

sensor_msgs::LaserScan::ConstPtr laser_slam::ScanMatchLocalizer::initialization_scan_ [private]

Definition at line 103 of file scan_match_localization.h.

Definition at line 102 of file scan_match_localization.h.

Definition at line 83 of file scan_match_localization.h.

msg::LocalizationDistribution::Ptr laser_slam::ScanMatchLocalizer::last_loc_ [private]

Definition at line 101 of file scan_match_localization.h.

boost::optional<ros::Time> laser_slam::ScanMatchLocalizer::last_match_request_time_ [private]

Definition at line 110 of file scan_match_localization.h.

sensor_msgs::LaserScan::ConstPtr laser_slam::ScanMatchLocalizer::last_scan_ [private]

Definition at line 103 of file scan_match_localization.h.

ros::Publisher laser_slam::ScanMatchLocalizer::loc_pub_ [private]

Definition at line 124 of file scan_match_localization.h.

Definition at line 109 of file scan_match_localization.h.

Definition at line 92 of file scan_match_localization.h.

Definition at line 124 of file scan_match_localization.h.

Definition at line 93 of file scan_match_localization.h.

boost::optional<kidnapped_robot::MatchResult> laser_slam::ScanMatchLocalizer::match_result_ [private]

Definition at line 111 of file scan_match_localization.h.

ros::Subscriber laser_slam::ScanMatchLocalizer::match_sub_ [private]

Definition at line 125 of file scan_match_localization.h.

Definition at line 122 of file scan_match_localization.h.

Definition at line 86 of file scan_match_localization.h.

boost::mutex laser_slam::ScanMatchLocalizer::mutex_ [mutable, private]

Definition at line 81 of file scan_match_localization.h.

ros::NodeHandle laser_slam::ScanMatchLocalizer::nh_ [private]

Definition at line 123 of file scan_match_localization.h.

Definition at line 91 of file scan_match_localization.h.

const std::string laser_slam::ScanMatchLocalizer::opt_frame_ [private]

Definition at line 89 of file scan_match_localization.h.

pg::NodePoseMap laser_slam::ScanMatchLocalizer::opt_poses_ [private]

Definition at line 107 of file scan_match_localization.h.

Definition at line 108 of file scan_match_localization.h.

ros::NodeHandle laser_slam::ScanMatchLocalizer::param_nh_ [private]

Definition at line 82 of file scan_match_localization.h.

Definition at line 85 of file scan_match_localization.h.

ros::Subscriber laser_slam::ScanMatchLocalizer::scan_sub_ [private]

Definition at line 125 of file scan_match_localization.h.

Definition at line 120 of file scan_match_localization.h.

boost::shared_ptr<tf::TransformListener> laser_slam::ScanMatchLocalizer::tf_ [private]

Definition at line 118 of file scan_match_localization.h.

Definition at line 84 of file scan_match_localization.h.

Definition at line 128 of file scan_match_localization.h.

Definition at line 90 of file scan_match_localization.h.


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


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