Classes | Public Member Functions | Private Member Functions | Private Attributes
explore::LoopClosure Class Reference

#include <loop_closure.h>

List of all members.

Classes

class  VisibilityChecker

Public Member Functions

 LoopClosure (double addition_dist_min, double loop_dist_min, double loop_dist_max, double slam_entropy_max_, double graph_update_frequency, actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > &move_base_client, costmap_2d::Costmap2DROS &costmap, boost::mutex &control_mutex, boost::function< void(void) > continuation_callback)
void updateGraph (const tf::Pose &pose)
 ~LoopClosure ()

Private Member Functions

void addNode (const tf::Pose &pose)
template<class ActionType >
void bresenham2D (ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset, unsigned int max_length)
 A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step.
bool checkLoopClosure (const tf::Pose &pose, std::vector< GraphNode * > &candidates)
void dijkstra (int source)
double distance (const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
void entropyCallback (const std_msgs::Float64::ConstPtr &entropy)
template<class ActionType >
void raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int size_x, unsigned int max_length=UINT_MAX)
 Raytrace a line and apply some action at each step.
int sign (int x)
void visualizeEdge (const tf::Pose &pose1, const tf::Pose &pose2, visualization_msgs::MarkerArray &markers)
void visualizeGraph ()
void visualizeNode (const tf::Pose &pose, visualization_msgs::MarkerArray &markers)

Private Attributes

double addition_dist_min_
boost::function< void(void)> continuation_callback_
boost::mutex & control_mutex_
costmap_2d::Costmap2DROS & costmap_
GraphNodecurr_node_
ros::Subscriber entropy_subscriber_
std::vector< std::vector< int > > graph_
double graph_update_frequency_
double loop_dist_max_
double loop_dist_min_
int marker_id_
ros::Publisher marker_publisher_
actionlib::SimpleActionClient
< move_base_msgs::MoveBaseAction > & 
move_base_client_
ros::NodeHandle nh_
std::vector< GraphNode * > nodes_
navfn::NavfnROS * planner_
double slam_entropy_
double slam_entropy_max_

Detailed Description

Definition at line 84 of file loop_closure.h.


Constructor & Destructor Documentation

LoopClosure::LoopClosure ( double  addition_dist_min,
double  loop_dist_min,
double  loop_dist_max,
double  slam_entropy_max_,
double  graph_update_frequency,
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > &  move_base_client,
costmap_2d::Costmap2DROS &  costmap,
boost::mutex &  control_mutex,
boost::function< void(void) >  continuation_callback 
)

Definition at line 52 of file loop_closure.cpp.

Definition at line 81 of file loop_closure.cpp.


Member Function Documentation

void LoopClosure::addNode ( const tf::Pose pose) [private]

Definition at line 212 of file loop_closure.cpp.

template<class ActionType >
void explore::LoopClosure::bresenham2D ( ActionType  at,
unsigned int  abs_da,
unsigned int  abs_db,
int  error_b,
int  offset_a,
int  offset_b,
unsigned int  offset,
unsigned int  max_length 
) [inline, private]

A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step.

Definition at line 171 of file loop_closure.h.

bool LoopClosure::checkLoopClosure ( const tf::Pose pose,
std::vector< GraphNode * > &  candidates 
) [private]

Definition at line 355 of file loop_closure.cpp.

void LoopClosure::dijkstra ( int  source) [private]

Definition at line 465 of file loop_closure.cpp.

double explore::LoopClosure::distance ( const geometry_msgs::PoseStamped &  p1,
const geometry_msgs::PoseStamped &  p2 
) [inline, private]

Definition at line 116 of file loop_closure.h.

void LoopClosure::entropyCallback ( const std_msgs::Float64::ConstPtr &  entropy) [private]

Definition at line 108 of file loop_closure.cpp.

template<class ActionType >
void explore::LoopClosure::raytraceLine ( ActionType  at,
unsigned int  x0,
unsigned int  y0,
unsigned int  x1,
unsigned int  y1,
unsigned int  size_x,
unsigned int  max_length = UINT_MAX 
) [inline, private]

Raytrace a line and apply some action at each step.

Parameters:
atThe action to take... a functor
x0The starting x coordinate
y0The starting y coordinate
x1The ending x coordinate
y1The ending y coordinate
max_lengthThe maximum desired length of the segment... allows you to not go all the way to the endpoint

Definition at line 138 of file loop_closure.h.

int explore::LoopClosure::sign ( int  x) [inline, private]

Definition at line 124 of file loop_closure.h.

void LoopClosure::updateGraph ( const tf::Pose pose)

Definition at line 114 of file loop_closure.cpp.

void LoopClosure::visualizeEdge ( const tf::Pose pose1,
const tf::Pose pose2,
visualization_msgs::MarkerArray &  markers 
) [private]

Definition at line 533 of file loop_closure.cpp.

void LoopClosure::visualizeGraph ( ) [private]

Definition at line 561 of file loop_closure.cpp.

void LoopClosure::visualizeNode ( const tf::Pose pose,
visualization_msgs::MarkerArray &  markers 
) [private]

Definition at line 510 of file loop_closure.cpp.


Member Data Documentation

Definition at line 204 of file loop_closure.h.

boost::function<void(void)> explore::LoopClosure::continuation_callback_ [private]

Definition at line 229 of file loop_closure.h.

boost::mutex& explore::LoopClosure::control_mutex_ [private]

Definition at line 228 of file loop_closure.h.

costmap_2d::Costmap2DROS& explore::LoopClosure::costmap_ [private]

Definition at line 226 of file loop_closure.h.

Definition at line 202 of file loop_closure.h.

Definition at line 223 of file loop_closure.h.

Definition at line 221 of file loop_closure.h.

Definition at line 213 of file loop_closure.h.

Definition at line 208 of file loop_closure.h.

Definition at line 206 of file loop_closure.h.

Definition at line 225 of file loop_closure.h.

Definition at line 224 of file loop_closure.h.

actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>& explore::LoopClosure::move_base_client_ [private]

Definition at line 216 of file loop_closure.h.

Definition at line 217 of file loop_closure.h.

Definition at line 219 of file loop_closure.h.

navfn::NavfnROS* explore::LoopClosure::planner_ [private]

Definition at line 230 of file loop_closure.h.

Definition at line 231 of file loop_closure.h.

Definition at line 210 of file loop_closure.h.


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


explore_hrl
Author(s): Travis Deyle
autogenerated on Wed Nov 27 2013 11:48:01