Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
costmap_downsampler.hpp
1 // Copyright (c) 2020, Carlos Luis
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #ifndef NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_
16 #define NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_
17 
18 #include <algorithm>
19 #include <string>
20 #include <memory>
21 
22 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
23 #include "nav2_smac_planner/constants.hpp"
24 
25 namespace nav2_smac_planner
26 {
27 
33 {
34 public:
39 
44 
54  void on_configure(
55  const nav2_util::LifecycleNode::WeakPtr & node,
56  const std::string & global_frame,
57  const std::string & topic_name,
58  nav2_costmap_2d::Costmap2D * const costmap,
59  const unsigned int & downsampling_factor,
60  const bool & use_min_cost_neighbor = false);
61 
65  void on_activate();
66 
70  void on_deactivate();
71 
75  void on_cleanup();
76 
82  nav2_costmap_2d::Costmap2D * downsample(const unsigned int & downsampling_factor);
83 
87  void resizeCostmap();
88 
89 protected:
93  void updateCostmapSize();
94 
100  void setCostOfCell(
101  const unsigned int & new_mx,
102  const unsigned int & new_my);
103 
104  unsigned int _size_x;
105  unsigned int _size_y;
106  unsigned int _downsampled_size_x;
107  unsigned int _downsampled_size_y;
108  unsigned int _downsampling_factor;
109  bool _use_min_cost_neighbor;
110  float _downsampled_resolution;
111  nav2_costmap_2d::Costmap2D * _costmap;
112  std::unique_ptr<nav2_costmap_2d::Costmap2D> _downsampled_costmap;
113  std::unique_ptr<nav2_costmap_2d::Costmap2DPublisher> _downsampled_costmap_pub;
114 };
115 
116 } // namespace nav2_smac_planner
117 
118 #endif // NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
A costmap downsampler for more efficient path planning.
~CostmapDownsampler()
A destructor for CostmapDownsampler.
CostmapDownsampler()
A constructor for CostmapDownsampler.
void resizeCostmap()
Resize the downsampled costmap. Used in case the costmap changes and we need to update the downsample...
void on_activate()
Activate the publisher of the downsampled costmap.
void on_deactivate()
Deactivate the publisher of the downsampled costmap.
void on_cleanup()
Cleanup the publisher of the downsampled costmap.
void updateCostmapSize()
Update the sizes X-Y of the costmap and its downsampled version.
void on_configure(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &global_frame, const std::string &topic_name, nav2_costmap_2d::Costmap2D *const costmap, const unsigned int &downsampling_factor, const bool &use_min_cost_neighbor=false)
Configure the downsampled costmap object and the ROS publisher.
void setCostOfCell(const unsigned int &new_mx, const unsigned int &new_my)
Explore all subcells of the original costmap and assign the max cost to the new (downsampled) cell.
nav2_costmap_2d::Costmap2D * downsample(const unsigned int &downsampling_factor)
Downsample the given costmap by the downsampling factor, and publish the downsampled costmap.