#include <loop_closure.h>
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) | |
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::mutex & | control_mutex_ |
costmap_2d::Costmap2DROS & | costmap_ |
GraphNode * | curr_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_ |
double | slam_entropy_time_ |
Definition at line 84 of file loop_closure.h.
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 | |||
) |
Definition at line 52 of file loop_closure.cpp.
LoopClosure::~LoopClosure | ( | ) |
Definition at line 80 of file loop_closure.cpp.
void LoopClosure::addNode | ( | const tf::Pose & | pose | ) | [private] |
Definition at line 197 of file loop_closure.cpp.
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 170 of file loop_closure.h.
bool LoopClosure::checkLoopClosure | ( | const tf::Pose & | pose, | |
std::vector< GraphNode * > & | candidates | |||
) | [private] |
Definition at line 340 of file loop_closure.cpp.
void LoopClosure::dijkstra | ( | int | source | ) | [private] |
Definition at line 450 of file loop_closure.cpp.
double explore::LoopClosure::distance | ( | const geometry_msgs::PoseStamped & | p1, | |
const geometry_msgs::PoseStamped & | p2 | |||
) | [inline, private] |
Definition at line 115 of file loop_closure.h.
void LoopClosure::entropyCallback | ( | const std_msgs::Float64::ConstPtr & | entropy | ) | [private] |
Definition at line 86 of file loop_closure.cpp.
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.
at | The action to take... a functor | |
x0 | The starting x coordinate | |
y0 | The starting y coordinate | |
x1 | The ending x coordinate | |
y1 | The ending y coordinate | |
max_length | The maximum desired length of the segment... allows you to not go all the way to the endpoint |
Definition at line 137 of file loop_closure.h.
int explore::LoopClosure::sign | ( | int | x | ) | [inline, private] |
Definition at line 123 of file loop_closure.h.
void LoopClosure::updateGraph | ( | const tf::Pose & | pose | ) |
Definition at line 94 of file loop_closure.cpp.
void LoopClosure::visualizeEdge | ( | const tf::Pose & | pose1, | |
const tf::Pose & | pose2, | |||
visualization_msgs::MarkerArray & | markers | |||
) | [private] |
Definition at line 518 of file loop_closure.cpp.
void LoopClosure::visualizeGraph | ( | ) | [private] |
Definition at line 546 of file loop_closure.cpp.
void LoopClosure::visualizeNode | ( | const tf::Pose & | pose, | |
visualization_msgs::MarkerArray & | markers | |||
) | [private] |
Definition at line 495 of file loop_closure.cpp.
double explore::LoopClosure::addition_dist_min_ [private] |
Definition at line 203 of file loop_closure.h.
boost::mutex& explore::LoopClosure::control_mutex_ [private] |
Definition at line 227 of file loop_closure.h.
costmap_2d::Costmap2DROS& explore::LoopClosure::costmap_ [private] |
Definition at line 225 of file loop_closure.h.
GraphNode* explore::LoopClosure::curr_node_ [private] |
Definition at line 201 of file loop_closure.h.
ros::Subscriber explore::LoopClosure::entropy_subscriber_ [private] |
Definition at line 222 of file loop_closure.h.
std::vector<std::vector<int> > explore::LoopClosure::graph_ [private] |
Definition at line 220 of file loop_closure.h.
double explore::LoopClosure::graph_update_frequency_ [private] |
Definition at line 212 of file loop_closure.h.
double explore::LoopClosure::loop_dist_max_ [private] |
Definition at line 207 of file loop_closure.h.
double explore::LoopClosure::loop_dist_min_ [private] |
Definition at line 205 of file loop_closure.h.
int explore::LoopClosure::marker_id_ [private] |
Definition at line 224 of file loop_closure.h.
ros::Publisher explore::LoopClosure::marker_publisher_ [private] |
Definition at line 223 of file loop_closure.h.
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>& explore::LoopClosure::move_base_client_ [private] |
Definition at line 215 of file loop_closure.h.
ros::NodeHandle explore::LoopClosure::nh_ [private] |
Definition at line 216 of file loop_closure.h.
std::vector<GraphNode*> explore::LoopClosure::nodes_ [private] |
Definition at line 218 of file loop_closure.h.
navfn::NavfnROS* explore::LoopClosure::planner_ [private] |
Definition at line 228 of file loop_closure.h.
double explore::LoopClosure::slam_entropy_ [private] |
Definition at line 229 of file loop_closure.h.
double explore::LoopClosure::slam_entropy_max_ [private] |
Definition at line 209 of file loop_closure.h.
double explore::LoopClosure::slam_entropy_time_ [private] |
Definition at line 230 of file loop_closure.h.