#include <static_layer.h>

| 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 () | 
| 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_ | 
Definition at line 53 of file static_layer.h.
Definition at line 56 of file static_layer.cpp.
| rtabmap_ros::StaticLayer::~StaticLayer | ( | ) |  [virtual] | 
Definition at line 58 of file static_layer.cpp.
| 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.
| new_map | The 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.
| 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_  [mutable, private] | 
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.
Definition at line 90 of file static_layer.h.
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.