static_layer.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef RTABMAP_ROS_STATIC_LAYER_H_
39 #define RTABMAP_ROS_STATIC_LAYER_H_
40 
41 #include <ros/ros.h>
44 #include <costmap_2d/GenericPluginConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <nav_msgs/OccupancyGrid.h>
47 #include <map_msgs/OccupancyGridUpdate.h>
49 
51 {
52 
54 {
55 public:
56  StaticLayer();
57  virtual ~StaticLayer();
58  virtual void onInitialize();
59  virtual void activate();
60  virtual void deactivate();
61  virtual void reset();
62 
63  virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y, double* max_x,
64  double* max_y);
65  virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
66 
67  virtual void matchSize();
68 
69 private:
76  void incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map);
77  void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update);
78  void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level);
79 
80  unsigned char interpretValue(unsigned char value);
81 
82  std::string global_frame_;
84  bool map_received_;
85  bool has_updated_data_;
86  unsigned int x_,y_,width_,height_;
88  bool use_maximum_;
91 
93 
94  mutable boost::recursive_mutex lock_;
95  dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig> *dsrv_;
96 };
97 
98 } // namespace rtabmap_ros
99 
100 #endif // RTABMAP_ROS_DYNAMIC_LAYER_H_
rtabmap_costmap_plugins::StaticLayer::height_
unsigned int height_
Definition: static_layer.h:158
rtabmap_costmap_plugins::StaticLayer::StaticLayer
StaticLayer()
Definition: static_layer.cpp:56
rtabmap_costmap_plugins::StaticLayer::incomingMap
void incomingMap(const nav_msgs::OccupancyGridConstPtr &new_map)
Callback to update the costmap's map from the map_server.
Definition: static_layer.cpp:150
ros.h
rtabmap_costmap_plugins
Definition: static_layer.h:50
rtabmap_costmap_plugins::StaticLayer::onInitialize
virtual void onInitialize()
Definition: static_layer.cpp:64
costmap_2d::Costmap2D
layered_costmap.h
rtabmap_costmap_plugins::StaticLayer::subscribe_to_updates_
bool subscribe_to_updates_
Definition: static_layer.h:155
rtabmap_costmap_plugins::StaticLayer::x_
unsigned int x_
Definition: static_layer.h:158
rtabmap_costmap_plugins::StaticLayer::use_maximum_
bool use_maximum_
Definition: static_layer.h:160
rtabmap_costmap_plugins::StaticLayer::trinary_costmap_
bool trinary_costmap_
Definition: static_layer.h:161
rtabmap_costmap_plugins::StaticLayer::incomingUpdate
void incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr &update)
Definition: static_layer.cpp:196
rtabmap_costmap_plugins::StaticLayer::updateBounds
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Definition: static_layer.cpp:235
rtabmap_costmap_plugins::StaticLayer::activate
virtual void activate()
Definition: static_layer.cpp:217
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
rtabmap_costmap_plugins::StaticLayer::reset
virtual void reset()
Definition: static_layer.cpp:229
rtabmap_costmap_plugins::StaticLayer
Definition: static_layer.h:89
subscriber.h
costmap_layer.h
rtabmap_costmap_plugins::StaticLayer::has_updated_data_
bool has_updated_data_
Definition: static_layer.h:157
costmap_2d::CostmapLayer
rtabmap_costmap_plugins::StaticLayer::matchSize
virtual void matchSize()
Definition: static_layer.cpp:129
rtabmap_costmap_plugins::StaticLayer::y_
unsigned int y_
Definition: static_layer.h:158
rtabmap_costmap_plugins::StaticLayer::map_update_sub_
ros::Subscriber map_update_sub_
Definition: static_layer.h:162
rtabmap_costmap_plugins::StaticLayer::lock_
boost::recursive_mutex lock_
Definition: static_layer.h:166
rtabmap_costmap_plugins::StaticLayer::width_
unsigned int width_
Definition: static_layer.h:158
rtabmap_costmap_plugins::StaticLayer::global_frame_
std::string global_frame_
The global frame for the costmap.
Definition: static_layer.h:154
rtabmap_costmap_plugins::StaticLayer::reconfigureCB
void reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
Definition: static_layer.cpp:117
rtabmap_costmap_plugins::StaticLayer::unknown_cost_value_
unsigned char unknown_cost_value_
Definition: static_layer.h:164
rtabmap_costmap_plugins::StaticLayer::lethal_threshold_
unsigned char lethal_threshold_
Definition: static_layer.h:164
rtabmap_costmap_plugins::StaticLayer::updateCosts
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Definition: static_layer.cpp:256
rtabmap_costmap_plugins::StaticLayer::track_unknown_space_
bool track_unknown_space_
Definition: static_layer.h:159
rtabmap_costmap_plugins::StaticLayer::map_sub_
ros::Subscriber map_sub_
Definition: static_layer.h:162
rtabmap_costmap_plugins::StaticLayer::dsrv_
dynamic_reconfigure::Server< costmap_2d::GenericPluginConfig > * dsrv_
Definition: static_layer.h:167
rtabmap_costmap_plugins::StaticLayer::~StaticLayer
virtual ~StaticLayer()
Definition: static_layer.cpp:58
rtabmap_costmap_plugins::StaticLayer::deactivate
virtual void deactivate()
Definition: static_layer.cpp:222
rtabmap_costmap_plugins::StaticLayer::map_received_
bool map_received_
Definition: static_layer.h:156
ros::Subscriber
rtabmap_costmap_plugins::StaticLayer::interpretValue
unsigned char interpretValue(unsigned char value)
Definition: static_layer.cpp:136


rtabmap_costmap_plugins
Author(s): Mathieu Labbe
autogenerated on Wed Dec 4 2024 03:31:30