Public Member Functions | Private Member Functions | Private Attributes | List of all members
costmap_2d::StaticLayer Class Reference

#include <static_layer.h>

Inheritance diagram for costmap_2d::StaticLayer:
Inheritance graph
[legend]

Public Member Functions

virtual void activate ()
 Restart publishers if they've been stopped. More...
 
virtual void deactivate ()
 Stop publishers. More...
 
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap. More...
 
virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization. More...
 
virtual void reset ()
 
 StaticLayer ()
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds. More...
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 Actually update the underlying costmap, only within the bounds calculated during UpdateBounds(). More...
 
virtual ~StaticLayer ()
 
- Public Member Functions inherited from costmap_2d::CostmapLayer
void addExtraBounds (double mx0, double my0, double mx1, double my1)
 
 CostmapLayer ()
 
bool isDiscretized ()
 
- Public Member Functions inherited from costmap_2d::Layer
const std::vector< geometry_msgs::Point > & getFootprint () const
 Convenience function for layered_costmap_->getFootprint(). More...
 
std::string getName () const
 
void initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf)
 
bool isCurrent () const
 Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More...
 
 Layer ()
 
virtual void onFootprintChanged ()
 LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint. More...
 
virtual ~Layer ()
 
- Public Member Functions inherited from costmap_2d::Costmap2D
unsigned int cellDistance (double world_dist)
 Given distance in the world... convert it to cells. More...
 
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that fill a convex polygon. More...
 
bool copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
 Turn this costmap into a copy of a window of a costmap passed in. More...
 
 Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
 Constructor for a costmap. More...
 
 Costmap2D (const Costmap2D &map)
 Copy constructor for a costmap, creates a copy efficiently. More...
 
 Costmap2D ()
 Default constructor. More...
 
unsigned char * getCharMap () const
 Will return a pointer to the underlying unsigned char array used as the costmap. More...
 
unsigned char getCost (unsigned int mx, unsigned int my) const
 Get the cost of a cell in the costmap. More...
 
unsigned char getDefaultValue ()
 
unsigned int getIndex (unsigned int mx, unsigned int my) const
 Given two map coordinates... compute the associated index. More...
 
mutex_tgetMutex ()
 
double getOriginX () const
 Accessor for the x origin of the costmap. More...
 
double getOriginY () const
 Accessor for the y origin of the costmap. More...
 
double getResolution () const
 Accessor for the resolution of the costmap. More...
 
unsigned int getSizeInCellsX () const
 Accessor for the x size of the costmap in cells. More...
 
unsigned int getSizeInCellsY () const
 Accessor for the y size of the costmap in cells. More...
 
double getSizeInMetersX () const
 Accessor for the x size of the costmap in meters. More...
 
double getSizeInMetersY () const
 Accessor for the y size of the costmap in meters. More...
 
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 Given an index... compute the associated map coordinates. More...
 
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 Convert from map coordinates to world coordinates. More...
 
Costmap2Doperator= (const Costmap2D &map)
 Overloaded assignment operator. More...
 
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that make up the outline of a polygon. More...
 
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)
 Save the costmap out to a pgm file. More...
 
bool setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
 Sets the cost of a convex polygon to a desired value. More...
 
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 Set the cost of a cell in the costmap. More...
 
void setDefaultValue (unsigned char c)
 
virtual void updateOrigin (double new_origin_x, double new_origin_y)
 Move the origin of the costmap to a new location.... keeping data when it can. More...
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 Convert from world coordinates to map coordinates. More...
 
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates, constraining results to legal bounds. More...
 
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates without checking for legal bounds. More...
 
virtual ~Costmap2D ()
 Destructor. More...
 

Private Member Functions

void incomingMap (const nav_msgs::OccupancyGridConstPtr &new_map)
 Callback to update the costmap's map from the map_server. More...
 
void incomingUpdate (const map_msgs::OccupancyGridUpdateConstPtr &update)
 
unsigned char interpretValue (unsigned char value)
 
void reconfigureCB (costmap_2d::GenericPluginConfig &config, uint32_t level)
 

Private Attributes

dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
 
bool first_map_only_
 Store the first static map and reuse it on reinitializing. More...
 
std::string global_frame_
 The global frame for the costmap. More...
 
bool has_updated_data_
 
unsigned int height_
 
unsigned char lethal_threshold_
 
std::string map_frame_
 
bool map_received_
 
ros::Subscriber map_sub_
 
ros::Subscriber map_update_sub_
 
bool subscribe_to_updates_
 frame that map is located in More...
 
bool track_unknown_space_
 
bool trinary_costmap_
 
unsigned char unknown_cost_value_
 
bool use_maximum_
 
unsigned int width_
 
unsigned int x_
 
unsigned int y_
 

Additional Inherited Members

- Public Types inherited from costmap_2d::Costmap2D
typedef boost::recursive_mutex mutex_t
 
- Protected Member Functions inherited from costmap_2d::CostmapLayer
void touch (double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
 
void updateWithAddition (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithMax (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void updateWithTrueOverwrite (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
void useExtraBounds (double *min_x, double *min_y, double *max_x, double *max_y)
 
- Protected Member Functions inherited from costmap_2d::Costmap2D
template<typename data_type >
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)
 Copy a region of a source map into a destination map. More...
 
virtual void deleteMaps ()
 Deletes the costmap, static_map, and markers data structures. More...
 
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 Initializes the costmap, static_map, and markers data structures. More...
 
template<class ActionType >
void raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
 Raytrace a line and apply some action at each step. More...
 
virtual void resetMaps ()
 Resets the costmap and static_map to be unknown space. More...
 
- Protected Attributes inherited from costmap_2d::CostmapLayer
bool has_extra_bounds_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class. More...
 
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

Definition at line 53 of file static_layer.h.

Constructor & Destructor Documentation

costmap_2d::StaticLayer::StaticLayer ( )

Definition at line 52 of file static_layer.cpp.

costmap_2d::StaticLayer::~StaticLayer ( )
virtual

Definition at line 54 of file static_layer.cpp.

Member Function Documentation

void costmap_2d::StaticLayer::activate ( )
virtual

Restart publishers if they've been stopped.

Reimplemented from costmap_2d::Layer.

Definition at line 244 of file static_layer.cpp.

void costmap_2d::StaticLayer::deactivate ( )
virtual

Stop publishers.

Reimplemented from costmap_2d::Layer.

Definition at line 249 of file static_layer.cpp.

void costmap_2d::StaticLayer::incomingMap ( const nav_msgs::OccupancyGridConstPtr &  new_map)
private

Callback to update the costmap's map from the map_server.

Parameters
new_mapThe map to put into the costmap. The origin of the new map along with its size will determine what parts of the costmap's static map are overwritten.

Definition at line 164 of file static_layer.cpp.

void costmap_2d::StaticLayer::incomingUpdate ( const map_msgs::OccupancyGridUpdateConstPtr &  update)
private

Definition at line 225 of file static_layer.cpp.

unsigned char costmap_2d::StaticLayer::interpretValue ( unsigned char  value)
private

Definition at line 148 of file static_layer.cpp.

void costmap_2d::StaticLayer::matchSize ( )
virtual

Implement this to make this layer match the size of the parent costmap.

Reimplemented from costmap_2d::CostmapLayer.

Definition at line 136 of file static_layer.cpp.

void costmap_2d::StaticLayer::onInitialize ( )
virtual

This is called at the end of initialize(). Override to implement subclass-specific initialization.

tf_, name_, and layered_costmap_ will all be set already when this is called.

Reimplemented from costmap_2d::Layer.

Definition at line 60 of file static_layer.cpp.

void costmap_2d::StaticLayer::reconfigureCB ( costmap_2d::GenericPluginConfig &  config,
uint32_t  level 
)
private

Definition at line 124 of file static_layer.cpp.

void costmap_2d::StaticLayer::reset ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 256 of file static_layer.cpp.

void costmap_2d::StaticLayer::updateBounds ( double  robot_x,
double  robot_y,
double  robot_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
)
virtual

This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds.

For more details, see "Layered Costmaps for Context-Sensitive Navigation", by Lu et. Al, IROS 2014.

Reimplemented from costmap_2d::Layer.

Definition at line 268 of file static_layer.cpp.

void costmap_2d::StaticLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
)
virtual

Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().

Reimplemented from costmap_2d::Layer.

Definition at line 292 of file static_layer.cpp.

Member Data Documentation

dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>* costmap_2d::StaticLayer::dsrv_
private

Definition at line 96 of file static_layer.h.

bool costmap_2d::StaticLayer::first_map_only_
private

Store the first static map and reuse it on reinitializing.

Definition at line 90 of file static_layer.h.

std::string costmap_2d::StaticLayer::global_frame_
private

The global frame for the costmap.

Definition at line 82 of file static_layer.h.

bool costmap_2d::StaticLayer::has_updated_data_
private

Definition at line 86 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::height_
private

Definition at line 87 of file static_layer.h.

unsigned char costmap_2d::StaticLayer::lethal_threshold_
private

Definition at line 94 of file static_layer.h.

std::string costmap_2d::StaticLayer::map_frame_
private

Definition at line 83 of file static_layer.h.

bool costmap_2d::StaticLayer::map_received_
private

Definition at line 85 of file static_layer.h.

ros::Subscriber costmap_2d::StaticLayer::map_sub_
private

Definition at line 92 of file static_layer.h.

ros::Subscriber costmap_2d::StaticLayer::map_update_sub_
private

Definition at line 92 of file static_layer.h.

bool costmap_2d::StaticLayer::subscribe_to_updates_
private

frame that map is located in

Definition at line 84 of file static_layer.h.

bool costmap_2d::StaticLayer::track_unknown_space_
private

Definition at line 88 of file static_layer.h.

bool costmap_2d::StaticLayer::trinary_costmap_
private

Definition at line 91 of file static_layer.h.

unsigned char costmap_2d::StaticLayer::unknown_cost_value_
private

Definition at line 94 of file static_layer.h.

bool costmap_2d::StaticLayer::use_maximum_
private

Definition at line 89 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::width_
private

Definition at line 87 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::x_
private

Definition at line 87 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::y_
private

Definition at line 87 of file static_layer.h.


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


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:42