Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
map_grid.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef DWB_CRITICS__MAP_GRID_HPP_
36 #define DWB_CRITICS__MAP_GRID_HPP_
37 
38 #include <vector>
39 #include <memory>
40 #include <string>
41 #include <utility>
42 
43 #include "dwb_core/trajectory_critic.hpp"
44 #include "costmap_queue/costmap_queue.hpp"
45 
46 namespace dwb_critics
47 {
62 {
63 public:
64  // Standard TrajectoryCritic Interface
65  void onInit() override;
66  double scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj) override;
68  std::vector<std::pair<std::string, std::vector<float>>> & cost_channels) override;
69  double getScale() const override {return costmap_->getResolution() * 0.5 * scale_;}
70 
71  // Helper Functions
77  virtual double scorePose(const geometry_msgs::msg::Pose2D & pose);
78 
85  inline double getScore(unsigned int x, unsigned int y)
86  {
87  return cell_values_[costmap_->getIndex(x, y)];
88  }
89 
94  void setAsObstacle(unsigned int index);
95 
96 protected:
104  // cppcheck-suppress syntaxError
105  enum class ScoreAggregationType {Last, Sum, Product};
106 
112  {
113 public:
115  : costmap_queue::CostmapQueue(costmap, true), parent_(parent) {}
116  virtual ~MapGridQueue() = default;
117  bool validCellToQueue(const costmap_queue::CellData & cell) override;
118 
119 protected:
120  MapGridCritic & parent_;
121  };
122 
126  void reset() override;
127 
132 
133  std::shared_ptr<MapGridQueue> queue_;
134  nav2_costmap_2d::Costmap2D * costmap_;
135  std::vector<double> cell_values_;
136  double obstacle_score_, unreachable_score_;
137  bool stop_on_failure_;
138  ScoreAggregationType aggregationType_;
139 };
140 } // namespace dwb_critics
141 
142 #endif // DWB_CRITICS__MAP_GRID_HPP_
Storage for cell information used during queue expansion.
Evaluates a Trajectory2D to produce a score.
Subclass of CostmapQueue that avoids Obstacles and Unknown Values.
Definition: map_grid.hpp:112
bool validCellToQueue(const costmap_queue::CellData &cell) override
Check to see if we should add this cell to the queue. Always true unless overridden.
Definition: map_grid.cpp:53
breadth-first scoring of all the cells in the costmap
Definition: map_grid.hpp:62
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.
Definition: map_grid.cpp:117
void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &cost_channels) override
Add information to the given pointcloud for debugging costmap-grid based scores.
Definition: map_grid.cpp:169
ScoreAggregationType
Separate modes for aggregating scores across the multiple poses in a trajectory.
Definition: map_grid.hpp:105
void reset() override
Clear the queuDWB_CRITICS_MAP_GRID_He and set cell_values_ to the appropriate number of unreachableCe...
Definition: map_grid.cpp:99
virtual double scorePose(const geometry_msgs::msg::Pose2D &pose)
Retrieve the score for a single pose.
Definition: map_grid.cpp:158
void setAsObstacle(unsigned int index)
Sets the score of a particular cell to the obstacle cost.
Definition: map_grid.cpp:94
void propogateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents.
Definition: map_grid.cpp:108
double getScore(unsigned int x, unsigned int y)
Retrieve the score for a particular cell of the costmap.
Definition: map_grid.hpp:85
double unreachable_score_
Special cell_values.
Definition: map_grid.hpp:136
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:211
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:531