Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
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]

Public Member Functions

 BoundedExploreLayer ()
 
bool isDiscretized ()
 
virtual void matchSize ()
 Match dimensions and origin of parent costmap. More...
 
virtual void onInitialize ()
 Loads default values and initialize exploration costmap. More...
 
virtual void reset ()
 Reset exploration progress. More...
 
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. More...
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 Update requested costmap window. More...
 
 ~BoundedExploreLayer ()
 
- Public Member Functions inherited from costmap_2d::Layer
virtual void activate ()
 
virtual void deactivate ()
 
const std::vector< geometry_msgs::Point > & getFootprint () const
 
std::string getName () const
 
void initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf)
 
bool isCurrent () const
 
 Layer ()
 
virtual void onFootprintChanged ()
 
virtual ~Layer ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
unsigned int cellDistance (double world_dist)
 
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 
bool copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
 
 Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
 
 Costmap2D (const Costmap2D &map)
 
 Costmap2D ()
 
unsigned char * getCharMap () const
 
unsigned char getCost (unsigned int mx, unsigned int my) const
 
unsigned char getDefaultValue ()
 
unsigned int getIndex (unsigned int mx, unsigned int my) const
 
mutex_tgetMutex ()
 
double getOriginX () const
 
double getOriginY () const
 
double getResolution () const
 
unsigned int getSizeInCellsX () const
 
unsigned int getSizeInCellsY () const
 
double getSizeInMetersX () const
 
double getSizeInMetersY () const
 
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 
Costmap2Doperator= (const Costmap2D &map)
 
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 
void resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
 
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
 
bool saveMap (std::string file_name)
 
bool setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
 
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 
void setDefaultValue (unsigned char c)
 
virtual void updateOrigin (double new_origin_x, double new_origin_y)
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 
virtual ~Costmap2D ()
 

Protected Member Functions

bool getNextFrontier (geometry_msgs::PoseStamped start_pose, geometry_msgs::PoseStamped &next_frontier)
 Search the costmap for next reachable frontier to explore. More...
 
bool getNextFrontierService (frontier_exploration::GetNextFrontier::Request &req, frontier_exploration::GetNextFrontier::Response &res)
 ROS Service wrapper for getNextFrontier. More...
 
bool updateBoundaryPolygon (geometry_msgs::PolygonStamped polygon_stamped)
 Load polygon boundary to draw on map with each update. More...
 
bool updateBoundaryPolygonService (frontier_exploration::UpdateBoundaryPolygon::Request &req, frontier_exploration::UpdateBoundaryPolygon::Response &res)
 ROS Service wrapper for updateBoundaryPolygon. More...
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
void copyMapRegion (data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
 
virtual void deleteMaps ()
 
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 
void raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
 
virtual void resetMaps ()
 

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. More...
 
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_
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf::TransformListenertf_
 
- Protected Attributes inherited from costmap_2d::Costmap2D
unsigned char * costmap_
 
unsigned char default_value_
 
double origin_x_
 
double origin_y_
 
double resolution_
 
unsigned int size_x_
 
unsigned int size_y_
 

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

frontier_exploration::BoundedExploreLayer::BoundedExploreLayer ( )

Definition at line 28 of file bounded_explore_layer.cpp.

frontier_exploration::BoundedExploreLayer::~BoundedExploreLayer ( )

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.

bool frontier_exploration::BoundedExploreLayer::isDiscretized ( )
inline

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.

void frontier_exploration::BoundedExploreLayer::matchSize ( )
virtual

Match dimensions and origin of parent costmap.

Reimplemented from costmap_2d::Layer.

Definition at line 68 of file bounded_explore_layer.cpp.

void frontier_exploration::BoundedExploreLayer::onInitialize ( )
virtual

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.

void frontier_exploration::BoundedExploreLayer::reset ( )
virtual

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

bool frontier_exploration::BoundedExploreLayer::configured_
private

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.

ros::Publisher frontier_exploration::BoundedExploreLayer::frontier_cloud_pub
private

Definition at line 107 of file bounded_explore_layer.h.

std::string frontier_exploration::BoundedExploreLayer::frontier_travel_point_
private

Definition at line 111 of file bounded_explore_layer.h.

ros::ServiceServer frontier_exploration::BoundedExploreLayer::frontierService_
private

Definition at line 103 of file bounded_explore_layer.h.

bool frontier_exploration::BoundedExploreLayer::marked_
private

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.

ros::ServiceServer frontier_exploration::BoundedExploreLayer::polygonService_
private

Definition at line 102 of file bounded_explore_layer.h.

bool frontier_exploration::BoundedExploreLayer::resize_to_boundary_
private

Definition at line 112 of file bounded_explore_layer.h.

tf::TransformListener frontier_exploration::BoundedExploreLayer::tf_listener_
private

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 Mon Jun 10 2019 13:25:00