Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
static_layer.hpp
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 NAV2_COSTMAP_2D__STATIC_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__STATIC_LAYER_HPP_
40 
41 #include <mutex>
42 #include <string>
43 #include <vector>
44 
45 #include "map_msgs/msg/occupancy_grid_update.hpp"
46 #include "message_filters/subscriber.h"
47 #include "nav2_costmap_2d/costmap_layer.hpp"
48 #include "nav2_costmap_2d/layered_costmap.hpp"
49 #include "nav_msgs/msg/occupancy_grid.hpp"
50 #include "rclcpp/rclcpp.hpp"
51 #include "nav2_costmap_2d/footprint.hpp"
52 
53 namespace nav2_costmap_2d
54 {
55 
60 class StaticLayer : public CostmapLayer
61 {
62 public:
66  StaticLayer();
70  virtual ~StaticLayer();
71 
75  virtual void onInitialize();
76 
80  virtual void activate();
84  virtual void deactivate();
85 
89  virtual void reset();
90 
94  virtual bool isClearable() {return false;}
95 
106  virtual void updateBounds(
107  double robot_x, double robot_y, double robot_yaw, double * min_x,
108  double * min_y, double * max_x, double * max_y);
109 
118  virtual void updateCosts(
119  nav2_costmap_2d::Costmap2D & master_grid,
120  int min_i, int min_j, int max_i, int max_j);
121 
125  virtual void matchSize();
126 
127 protected:
131  void getParameters();
132 
136  void processMap(const nav_msgs::msg::OccupancyGrid & new_map);
137 
144  void incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map);
149  void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update);
150 
155  unsigned char interpretValue(unsigned char value);
156 
161  rcl_interfaces::msg::SetParametersResult
162  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
163 
164  std::vector<geometry_msgs::msg::Point> transformed_footprint_;
165  bool footprint_clearing_enabled_;
169  void updateFootprint(
170  double robot_x, double robot_y, double robot_yaw, double * min_x,
171  double * min_y,
172  double * max_x,
173  double * max_y);
174 
175  std::string global_frame_;
176  std::string map_frame_;
177 
178  bool has_updated_data_{false};
179 
180  unsigned int x_{0};
181  unsigned int y_{0};
182  unsigned int width_{0};
183  unsigned int height_{0};
184 
185  rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr map_sub_;
186  rclcpp::Subscription<map_msgs::msg::OccupancyGridUpdate>::SharedPtr map_update_sub_;
187 
188  // Parameters
189  std::string map_topic_;
190  bool map_subscribe_transient_local_;
191  bool subscribe_to_updates_;
192  bool track_unknown_space_;
193  bool use_maximum_;
194  unsigned char lethal_threshold_;
195  unsigned char unknown_cost_value_;
196  bool trinary_costmap_;
197  bool map_received_{false};
198  bool map_received_in_update_bounds_{false};
199  tf2::Duration transform_tolerance_;
200  nav_msgs::msg::OccupancyGrid::SharedPtr map_buffer_;
201  // Dynamic parameters handler
202  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
203 };
204 
205 } // namespace nav2_costmap_2d
206 
207 #endif // NAV2_COSTMAP_2D__STATIC_LAYER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
Takes in a map generated from SLAM to add costs to costmap.
void getParameters()
Get parameters of layer.
virtual ~StaticLayer()
Static Layer destructor.
virtual void deactivate()
Deactivate this layer.
bool has_updated_data_
frame that map is located in
unsigned char interpretValue(unsigned char value)
Interpret the value in the static map given on the topic to convert into costs for the costmap to uti...
StaticLayer()
Static Layer constructor.
virtual void matchSize()
Match the size of the master costmap.
virtual void onInitialize()
Initialization process of layer on startup.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Clear costmap layer info below the robot's footprint.
virtual void activate()
Activate this layer.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
void incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr update)
Callback to update the costmap's map from the map_server (or SLAM) with an update in a particular are...
void incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
Callback to update the costmap's map from the map_server.
std::string global_frame_
The global frame for the costmap.
void processMap(const nav_msgs::msg::OccupancyGrid &new_map)
Process a new map coming from a topic.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual void reset()
Reset this costmap.