Public Member Functions | Private Member Functions | Private Attributes
graph_slam::KartoLaserConstraints Class Reference

#include <karto_laser_constraints.h>

Inheritance diagram for graph_slam::KartoLaserConstraints:
Inheritance graph
[legend]

List of all members.

Public Member Functions

NodeConstraintVector getConstraints (const pg::PoseGraph &graph, const pg::NodeId new_node, const NodePoseMap &optimized_poses)
 Return a set of constraints given the current state of the graph the identity of the new node, and current optimized poses.
void initializeFromGraph (const pg::PoseGraph &g, const std::vector< pg::NodeId > &node_sequence)
 Initialize from existing graph.
 KartoLaserConstraints (double max_seq_link_length, unsigned min_seq_chain_length, double min_seq_link_response, double max_loop_link_length, unsigned min_loop_chain_length, double min_loop_closure_response, bool use_covariances)
void updateLocalization (const graph_slam::GraphLocalization &loc)

Private Member Functions

NodeConstraintVector loopConstraints (const pg::PoseGraph &graph, const pg::NodeId new_node, const geometry_msgs::Pose &pose_estimate, const NodePoseMap &optimized_poses)
void possiblyInitializeMatchers (const sensor_msgs::LaserScan &scan)
NodeConstraintVector scanOdomConstraints (const pg::PoseGraph &graph, const pg::NodeId new_node, const geometry_msgs::Pose &pose_estimate, const NodePoseMap &optimized_poses)

Private Attributes

boost::optional< pg::NodeIdlast_ref_node_
LoopMatcherPtr loop_matcher_
const double max_loop_link_length_
const double max_sequential_link_length_
const unsigned min_loop_chain_length_
const double min_loop_closure_response_
const unsigned min_sequential_chain_length_
const double min_sequential_link_response_
ros::NodeHandle nh_
geometry_msgs::Pose ref_node_odom_pose_
SeqMatcherPtr seq_matcher_
tf::TransformListener tf_
const bool use_covariances_

Detailed Description

Definition at line 63 of file karto_laser_constraints.h.


Constructor & Destructor Documentation

graph_slam::KartoLaserConstraints::KartoLaserConstraints ( double  max_seq_link_length,
unsigned  min_seq_chain_length,
double  min_seq_link_response,
double  max_loop_link_length,
unsigned  min_loop_chain_length,
double  min_loop_closure_response,
bool  use_covariances 
)

Definition at line 67 of file karto_laser_constraint_generator.cpp.


Member Function Documentation

NodeConstraintVector graph_slam::KartoLaserConstraints::getConstraints ( const pg::PoseGraph graph,
const pg::NodeId  new_node,
const NodePoseMap optimized_poses 
) [virtual]

Return a set of constraints given the current state of the graph the identity of the new node, and current optimized poses.

Implements graph_slam::ConstraintGenerator.

Definition at line 123 of file karto_laser_constraint_generator.cpp.

void graph_slam::KartoLaserConstraints::initializeFromGraph ( const pg::PoseGraph g,
const std::vector< pg::NodeId > &  node_sequence 
) [virtual]

Initialize from existing graph.

Parameters:
node_sequenceis a suffix of the order in which nodes were seen; can have repeats

Implements graph_slam::ConstraintGenerator.

Definition at line 165 of file karto_laser_constraint_generator.cpp.

NodeConstraintVector graph_slam::KartoLaserConstraints::loopConstraints ( const pg::PoseGraph graph,
const pg::NodeId  new_node,
const geometry_msgs::Pose pose_estimate,
const NodePoseMap optimized_poses 
) [private]

Definition at line 181 of file karto_laser_constraint_generator.cpp.

void graph_slam::KartoLaserConstraints::possiblyInitializeMatchers ( const sensor_msgs::LaserScan &  scan) [private]

Definition at line 108 of file karto_laser_constraint_generator.cpp.

NodeConstraintVector graph_slam::KartoLaserConstraints::scanOdomConstraints ( const pg::PoseGraph graph,
const pg::NodeId  new_node,
const geometry_msgs::Pose pose_estimate,
const NodePoseMap optimized_poses 
) [private]

Definition at line 194 of file karto_laser_constraint_generator.cpp.

void graph_slam::KartoLaserConstraints::updateLocalization ( const graph_slam::GraphLocalization &  loc) [virtual]

Member Data Documentation

Definition at line 101 of file karto_laser_constraints.h.

Definition at line 99 of file karto_laser_constraints.h.

Definition at line 90 of file karto_laser_constraints.h.

Definition at line 87 of file karto_laser_constraints.h.

Definition at line 91 of file karto_laser_constraints.h.

Definition at line 92 of file karto_laser_constraints.h.

Definition at line 88 of file karto_laser_constraints.h.

Definition at line 89 of file karto_laser_constraints.h.

Definition at line 95 of file karto_laser_constraints.h.

Definition at line 106 of file karto_laser_constraints.h.

Definition at line 98 of file karto_laser_constraints.h.

Definition at line 96 of file karto_laser_constraints.h.

Definition at line 93 of file karto_laser_constraints.h.


The documentation for this class was generated from the following files:


graph_slam
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:21