RAPP Platform  v0.6.0
RAPP Platform is a collection of ROS nodes and back-end processes that aim to deliver ready-to-use generic services to robots
 All Classes Namespaces Files Functions Variables Macros
costmap_2d::RappStaticLayer Class Reference

#include <rapp_static_layer.h>

Inheritance diagram for costmap_2d::RappStaticLayer:
Collaboration diagram for costmap_2d::RappStaticLayer:

Public Member Functions

 RappStaticLayer ()
 
virtual ~RappStaticLayer ()
 
virtual void activate ()
 
virtual void deactivate ()
 
virtual void matchSize ()
 
virtual void onInitialize ()
 
virtual void reset ()
 
virtual void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 

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)
 
bool incomingUpdateService (rapp_platform_ros_communications::Costmap2dRosSrvRequest &req, rapp_platform_ros_communications::Costmap2dRosSrvResponse &res)
 
unsigned char interpretValue (unsigned char value)
 
void reconfigureCB (costmap_2d::GenericPluginConfig &config, uint32_t level)
 

Private Attributes

ros::ServiceServer costmap_update_service
 
dynamic_reconfigure::Server
< costmap_2d::GenericPluginConfig > * 
dsrv_
 
std::string global_frame_
 The global frame for the costmap. More...
 
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 57 of file rapp_static_layer.h.

Constructor & Destructor Documentation

costmap_2d::RappStaticLayer::RappStaticLayer ( )

Definition at line 50 of file rapp_static_layer.cpp.

costmap_2d::RappStaticLayer::~RappStaticLayer ( )
virtual

Definition at line 52 of file rapp_static_layer.cpp.

Member Function Documentation

void costmap_2d::RappStaticLayer::activate ( )
virtual

Definition at line 257 of file rapp_static_layer.cpp.

void costmap_2d::RappStaticLayer::deactivate ( )
virtual

Definition at line 262 of file rapp_static_layer.cpp.

void costmap_2d::RappStaticLayer::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 194 of file rapp_static_layer.cpp.

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

Definition at line 238 of file rapp_static_layer.cpp.

bool costmap_2d::RappStaticLayer::incomingUpdateService ( rapp_platform_ros_communications::Costmap2dRosSrvRequest &  req,
rapp_platform_ros_communications::Costmap2dRosSrvResponse &  res 
)
private

Definition at line 148 of file rapp_static_layer.cpp.

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

Definition at line 180 of file rapp_static_layer.cpp.

void costmap_2d::RappStaticLayer::matchSize ( )
virtual

Definition at line 173 of file rapp_static_layer.cpp.

void costmap_2d::RappStaticLayer::onInitialize ( )
virtual

Definition at line 58 of file rapp_static_layer.cpp.

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

Definition at line 161 of file rapp_static_layer.cpp.

void costmap_2d::RappStaticLayer::reset ( )
virtual

Definition at line 269 of file rapp_static_layer.cpp.

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

Definition at line 275 of file rapp_static_layer.cpp.

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

Definition at line 296 of file rapp_static_layer.cpp.

Member Data Documentation

ros::ServiceServer costmap_2d::RappStaticLayer::costmap_update_service
private

Definition at line 96 of file rapp_static_layer.h.

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

Definition at line 100 of file rapp_static_layer.h.

std::string costmap_2d::RappStaticLayer::global_frame_
private

The global frame for the costmap.

Definition at line 87 of file rapp_static_layer.h.

bool costmap_2d::RappStaticLayer::has_updated_data_
private

Definition at line 90 of file rapp_static_layer.h.

unsigned int costmap_2d::RappStaticLayer::height_
private

Definition at line 91 of file rapp_static_layer.h.

unsigned char costmap_2d::RappStaticLayer::lethal_threshold_
private

Definition at line 97 of file rapp_static_layer.h.

boost::recursive_mutex costmap_2d::RappStaticLayer::lock_
mutableprivate

Definition at line 99 of file rapp_static_layer.h.

bool costmap_2d::RappStaticLayer::map_received_
private

Definition at line 89 of file rapp_static_layer.h.

ros::Subscriber costmap_2d::RappStaticLayer::map_sub_
private

Definition at line 95 of file rapp_static_layer.h.

ros::Subscriber costmap_2d::RappStaticLayer::map_update_sub_
private

Definition at line 95 of file rapp_static_layer.h.

bool costmap_2d::RappStaticLayer::subscribe_to_updates_
private

Definition at line 88 of file rapp_static_layer.h.

bool costmap_2d::RappStaticLayer::track_unknown_space_
private

Definition at line 92 of file rapp_static_layer.h.

bool costmap_2d::RappStaticLayer::trinary_costmap_
private

Definition at line 94 of file rapp_static_layer.h.

unsigned char costmap_2d::RappStaticLayer::unknown_cost_value_
private

Definition at line 97 of file rapp_static_layer.h.

bool costmap_2d::RappStaticLayer::use_maximum_
private

Definition at line 93 of file rapp_static_layer.h.

unsigned int costmap_2d::RappStaticLayer::width_
private

Definition at line 91 of file rapp_static_layer.h.

unsigned int costmap_2d::RappStaticLayer::x_
private

Definition at line 91 of file rapp_static_layer.h.

unsigned int costmap_2d::RappStaticLayer::y_
private

Definition at line 91 of file rapp_static_layer.h.


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