Nav2 Navigation Stack - rolling  main
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 <memory>
19 #include <string>
20 
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
22 #include "nav2_smac_planner/constants.hpp"
23 
24 namespace nav2_smac_planner
25 {
26 
32 {
33 public:
38 
43 
53  void on_configure(
54  const nav2::LifecycleNode::WeakPtr & node,
55  const std::string & global_frame,
56  const std::string & topic_name,
57  nav2_costmap_2d::Costmap2D * const costmap,
58  const unsigned int & downsampling_factor,
59  const bool & use_min_cost_neighbor = false);
60 
64  void on_activate();
65 
69  void on_deactivate();
70 
74  void on_cleanup();
75 
81  nav2_costmap_2d::Costmap2D * downsample(const unsigned int & downsampling_factor);
82 
86  void resizeCostmap();
87 
88 protected:
92  void updateCostmapSize();
93 
99  void setCostOfCell(
100  const unsigned int & new_mx,
101  const unsigned int & new_my);
102 
103  unsigned int _size_x;
104  unsigned int _size_y;
105  unsigned int _downsampled_size_x;
106  unsigned int _downsampled_size_y;
107  unsigned int _downsampling_factor;
108  bool _use_min_cost_neighbor;
109  float _downsampled_resolution;
110  nav2_costmap_2d::Costmap2D * _costmap;
111  std::unique_ptr<nav2_costmap_2d::Costmap2D> _downsampled_costmap;
112  std::unique_ptr<nav2_costmap_2d::Costmap2DPublisher> _downsampled_costmap_pub;
113 };
114 
115 } // namespace nav2_smac_planner
116 
117 #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:69
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 on_configure(const nav2::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 updateCostmapSize()
Update the sizes X-Y of the costmap and its downsampled version.
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.