Public Member Functions | Private Member Functions | Private Attributes
costmap_2d::StaticLayer Class Reference

#include <static_layer.h>

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

List of all members.

Public Member Functions

virtual void activate ()
 Restart publishers if they've been stopped.
virtual void deactivate ()
 Stop publishers.
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap.
virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization.
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.
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().
virtual ~StaticLayer ()

Private Member Functions

void incomingMap (const nav_msgs::OccupancyGridConstPtr &new_map)
 Callback to update the costmap's map from the map_server.
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_
std::string global_frame_
 The global frame for the costmap.
bool has_updated_data_
unsigned int height_
unsigned char lethal_threshold_
boost::recursive_mutex lock_
bool map_received_
ros::Subscriber map_sub_
ros::Subscriber map_update_sub_
bool subscribe_to_updates_
bool track_unknown_space_
bool trinary_costmap_
unsigned char unknown_cost_value_
bool use_maximum_
unsigned int width_
unsigned int x_
unsigned int y_

Detailed Description

Definition at line 53 of file static_layer.h.


Constructor & Destructor Documentation

Definition at line 51 of file static_layer.cpp.

Definition at line 53 of file static_layer.cpp.


Member Function Documentation

Restart publishers if they've been stopped.

Reimplemented from costmap_2d::Layer.

Definition at line 208 of file static_layer.cpp.

Stop publishers.

Reimplemented from costmap_2d::Layer.

Definition at line 213 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 145 of file static_layer.cpp.

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

Definition at line 189 of file static_layer.cpp.

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

Definition at line 131 of file static_layer.cpp.

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

Reimplemented from costmap_2d::CostmapLayer.

Definition at line 124 of file static_layer.cpp.

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 59 of file static_layer.cpp.

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

Definition at line 112 of file static_layer.cpp.

void costmap_2d::StaticLayer::reset ( ) [virtual]

Reimplemented from costmap_2d::Layer.

Definition at line 220 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 226 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 247 of file static_layer.cpp.


Member Data Documentation

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

Definition at line 95 of file static_layer.h.

The global frame for the costmap.

Definition at line 82 of file static_layer.h.

Definition at line 85 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::height_ [private]

Definition at line 86 of file static_layer.h.

Definition at line 92 of file static_layer.h.

boost::recursive_mutex costmap_2d::StaticLayer::lock_ [mutable, private]

Definition at line 94 of file static_layer.h.

Definition at line 84 of file static_layer.h.

Definition at line 90 of file static_layer.h.

Definition at line 90 of file static_layer.h.

Definition at line 83 of file static_layer.h.

Definition at line 87 of file static_layer.h.

Definition at line 89 of file static_layer.h.

Definition at line 92 of file static_layer.h.

Definition at line 88 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::width_ [private]

Definition at line 86 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::x_ [private]

Definition at line 86 of file static_layer.h.

unsigned int costmap_2d::StaticLayer::y_ [private]

Definition at line 86 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 Aug 27 2015 14:06:55