Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
frontier_exploration::BoundedExploreLayer Class Reference

costmap_2d layer plugin that holds the state for a bounded frontier exploration task. Manages the boundary polygon, superimposes the polygon on the overall exploration costmap, and processes costmap to find next frontier to explore. More...

#include <bounded_explore_layer.h>

Inheritance diagram for frontier_exploration::BoundedExploreLayer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 BoundedExploreLayer ()
bool isDiscretized ()
virtual void matchSize ()
 Match dimensions and origin of parent costmap.
virtual void onInitialize ()
 Loads default values and initialize exploration costmap.
virtual void reset ()
 Reset exploration progress.
virtual void updateBounds (double origin_x, double origin_y, double origin_yaw, double *polygon_min_x, double *polygon_min_y, double *polygon_max_x, double *polygon_max_y)
 Calculate bounds of costmap window to update.
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 Update requested costmap window.
 ~BoundedExploreLayer ()

Protected Member Functions

bool getNextFrontier (geometry_msgs::PoseStamped start_pose, geometry_msgs::PoseStamped &next_frontier)
 Search the costmap for next reachable frontier to explore.
bool getNextFrontierService (frontier_exploration::GetNextFrontier::Request &req, frontier_exploration::GetNextFrontier::Response &res)
 ROS Service wrapper for getNextFrontier.
bool updateBoundaryPolygon (geometry_msgs::PolygonStamped polygon_stamped)
 Load polygon boundary to draw on map with each update.
bool updateBoundaryPolygonService (frontier_exploration::UpdateBoundaryPolygon::Request &req, frontier_exploration::UpdateBoundaryPolygon::Response &res)
 ROS Service wrapper for updateBoundaryPolygon.

Private Member Functions

void mapUpdateKeepObstacles (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 Update the map with exploration boundary data.
void reconfigureCB (costmap_2d::GenericPluginConfig &config, uint32_t level)

Private Attributes

bool configured_
dynamic_reconfigure::Server
< costmap_2d::GenericPluginConfig > * 
dsrv_
ros::Publisher frontier_cloud_pub
std::string frontier_travel_point_
ros::ServiceServer frontierService_
bool marked_
geometry_msgs::Polygon polygon_
ros::ServiceServer polygonService_
bool resize_to_boundary_
tf::TransformListener tf_listener_

Detailed Description

costmap_2d layer plugin that holds the state for a bounded frontier exploration task. Manages the boundary polygon, superimposes the polygon on the overall exploration costmap, and processes costmap to find next frontier to explore.

Definition at line 22 of file bounded_explore_layer.h.


Constructor & Destructor Documentation

Definition at line 28 of file bounded_explore_layer.cpp.

Definition at line 30 of file bounded_explore_layer.cpp.


Member Function Documentation

bool frontier_exploration::BoundedExploreLayer::getNextFrontier ( geometry_msgs::PoseStamped  start_pose,
geometry_msgs::PoseStamped &  next_frontier 
) [protected]

Search the costmap for next reachable frontier to explore.

Parameters:
start_posePose from which to start search
next_frontierPose of found frontier
Returns:
True if a reachable frontier was found, false otherwise

Definition at line 83 of file bounded_explore_layer.cpp.

bool frontier_exploration::BoundedExploreLayer::getNextFrontierService ( frontier_exploration::GetNextFrontier::Request &  req,
frontier_exploration::GetNextFrontier::Response &  res 
) [protected]

ROS Service wrapper for getNextFrontier.

Parameters:
reqService request
resService response
Returns:
True on service success, false otherwise

Definition at line 79 of file bounded_explore_layer.cpp.

Definition at line 43 of file bounded_explore_layer.h.

void frontier_exploration::BoundedExploreLayer::mapUpdateKeepObstacles ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
) [private]

Update the map with exploration boundary data.

Parameters:
master_gridReference to master costmap

Definition at line 279 of file bounded_explore_layer.cpp.

Match dimensions and origin of parent costmap.

Reimplemented from costmap_2d::Layer.

Definition at line 68 of file bounded_explore_layer.cpp.

Loads default values and initialize exploration costmap.

Reimplemented from costmap_2d::Layer.

Definition at line 37 of file bounded_explore_layer.cpp.

void frontier_exploration::BoundedExploreLayer::reconfigureCB ( costmap_2d::GenericPluginConfig &  config,
uint32_t  level 
) [private]

Definition at line 75 of file bounded_explore_layer.cpp.

Reset exploration progress.

Reimplemented from costmap_2d::Layer.

Definition at line 171 of file bounded_explore_layer.cpp.

bool frontier_exploration::BoundedExploreLayer::updateBoundaryPolygon ( geometry_msgs::PolygonStamped  polygon_stamped) [protected]

Load polygon boundary to draw on map with each update.

Parameters:
polygon_stampedpolygon boundary
Returns:
True if polygon successfully loaded, false otherwise

Definition at line 180 of file bounded_explore_layer.cpp.

bool frontier_exploration::BoundedExploreLayer::updateBoundaryPolygonService ( frontier_exploration::UpdateBoundaryPolygon::Request &  req,
frontier_exploration::UpdateBoundaryPolygon::Response &  res 
) [protected]

ROS Service wrapper for updateBoundaryPolygon.

Parameters:
reqService request
resService response
Returns:
True on service success, false otherwise

Definition at line 165 of file bounded_explore_layer.cpp.

void frontier_exploration::BoundedExploreLayer::updateBounds ( double  origin_x,
double  origin_y,
double  origin_yaw,
double *  polygon_min_x,
double *  polygon_min_y,
double *  polygon_max_x,
double *  polygon_max_y 
) [virtual]

Calculate bounds of costmap window to update.

Reimplemented from costmap_2d::Layer.

Definition at line 243 of file bounded_explore_layer.cpp.

void frontier_exploration::BoundedExploreLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
) [virtual]

Update requested costmap window.

Reimplemented from costmap_2d::Layer.

Definition at line 257 of file bounded_explore_layer.cpp.


Member Data Documentation

Definition at line 109 of file bounded_explore_layer.h.

dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>* frontier_exploration::BoundedExploreLayer::dsrv_ [private]

Definition at line 101 of file bounded_explore_layer.h.

Definition at line 107 of file bounded_explore_layer.h.

Definition at line 111 of file bounded_explore_layer.h.

Definition at line 103 of file bounded_explore_layer.h.

Definition at line 109 of file bounded_explore_layer.h.

geometry_msgs::Polygon frontier_exploration::BoundedExploreLayer::polygon_ [private]

Definition at line 104 of file bounded_explore_layer.h.

Definition at line 102 of file bounded_explore_layer.h.

Definition at line 112 of file bounded_explore_layer.h.

Definition at line 105 of file bounded_explore_layer.h.


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


frontier_exploration
Author(s): Paul Bovbel
autogenerated on Thu Aug 10 2017 03:02:58