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

#include <static_layer.h>

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

Public Member Functions

virtual void activate ()
 
virtual void deactivate ()
 
virtual void matchSize ()
 
virtual void onInitialize ()
 
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)
 
virtual void updateCosts (costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
 
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
 
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 ()
 

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

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
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 ()
 
- Protected Attributes inherited from costmap_2d::CostmapLayer
bool has_extra_bounds_
 
- 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

Definition at line 53 of file static_layer.h.

Constructor & Destructor Documentation

rtabmap_ros::StaticLayer::StaticLayer ( )

Definition at line 56 of file static_layer.cpp.

rtabmap_ros::StaticLayer::~StaticLayer ( )
virtual

Definition at line 58 of file static_layer.cpp.

Member Function Documentation

void rtabmap_ros::StaticLayer::activate ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 217 of file static_layer.cpp.

void rtabmap_ros::StaticLayer::deactivate ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 222 of file static_layer.cpp.

void rtabmap_ros::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 150 of file static_layer.cpp.

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

Definition at line 196 of file static_layer.cpp.

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

Definition at line 136 of file static_layer.cpp.

void rtabmap_ros::StaticLayer::matchSize ( )
virtual

Reimplemented from costmap_2d::CostmapLayer.

Definition at line 129 of file static_layer.cpp.

void rtabmap_ros::StaticLayer::onInitialize ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 64 of file static_layer.cpp.

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

Definition at line 117 of file static_layer.cpp.

void rtabmap_ros::StaticLayer::reset ( )
virtual

Reimplemented from costmap_2d::Layer.

Definition at line 229 of file static_layer.cpp.

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

Reimplemented from costmap_2d::Layer.

Definition at line 235 of file static_layer.cpp.

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

Reimplemented from costmap_2d::Layer.

Definition at line 256 of file static_layer.cpp.

Member Data Documentation

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

Definition at line 95 of file static_layer.h.

std::string rtabmap_ros::StaticLayer::global_frame_
private

The global frame for the costmap.

Definition at line 82 of file static_layer.h.

bool rtabmap_ros::StaticLayer::has_updated_data_
private

Definition at line 85 of file static_layer.h.

unsigned int rtabmap_ros::StaticLayer::height_
private

Definition at line 86 of file static_layer.h.

unsigned char rtabmap_ros::StaticLayer::lethal_threshold_
private

Definition at line 92 of file static_layer.h.

boost::recursive_mutex rtabmap_ros::StaticLayer::lock_
mutableprivate

Definition at line 94 of file static_layer.h.

bool rtabmap_ros::StaticLayer::map_received_
private

Definition at line 84 of file static_layer.h.

ros::Subscriber rtabmap_ros::StaticLayer::map_sub_
private

Definition at line 90 of file static_layer.h.

ros::Subscriber rtabmap_ros::StaticLayer::map_update_sub_
private

Definition at line 90 of file static_layer.h.

bool rtabmap_ros::StaticLayer::subscribe_to_updates_
private

Definition at line 83 of file static_layer.h.

bool rtabmap_ros::StaticLayer::track_unknown_space_
private

Definition at line 87 of file static_layer.h.

bool rtabmap_ros::StaticLayer::trinary_costmap_
private

Definition at line 89 of file static_layer.h.

unsigned char rtabmap_ros::StaticLayer::unknown_cost_value_
private

Definition at line 92 of file static_layer.h.

bool rtabmap_ros::StaticLayer::use_maximum_
private

Definition at line 88 of file static_layer.h.

unsigned int rtabmap_ros::StaticLayer::width_
private

Definition at line 86 of file static_layer.h.

unsigned int rtabmap_ros::StaticLayer::x_
private

Definition at line 86 of file static_layer.h.

unsigned int rtabmap_ros::StaticLayer::y_
private

Definition at line 86 of file static_layer.h.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19