map_grid.h
Go to the documentation of this file.
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_H
36 #define DWB_CRITICS_MAP_GRID_H
37 
40 #include <memory>
41 #include <vector>
42 
43 namespace dwb_critics
44 {
59 {
60 public:
62 
63  // Standard TrajectoryCritic Interface
64  void onInit() override;
65  double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override;
66  void addCriticVisualization(sensor_msgs::PointCloud& pc) override;
67  double getScale() const override { return costmap_->getResolution() * 0.5 * scale_; }
68 
69  // Helper Functions
75  virtual double scorePose(const geometry_msgs::Pose2D& pose);
76 
83  inline double getScore(unsigned int x, unsigned int y) { return cell_values_(x, y); }
84 
90  void setAsObstacle(unsigned int x, unsigned int y);
91 
92 protected:
101 
107  {
108  public:
110  : costmap_queue::CostmapQueue(costmap, true), parent_(parent) {}
111  bool validCellToQueue(const costmap_queue::CellData& cell) override;
112  protected:
114  };
115 
119  void reset() override;
120 
125 
126  std::shared_ptr<MapGridQueue> queue_;
131 };
132 } // namespace dwb_critics
133 
134 #endif // DWB_CRITICS_MAP_GRID_H
dwb_critics::MapGridCritic::ScoreAggregationType::Product
@ Product
dwb_critics::MapGridCritic::MapGridCritic
MapGridCritic()
Definition: map_grid.h:61
dwb_critics::MapGridCritic::ScoreAggregationType::Last
@ Last
costmap
nav_core2::BasicCostmap costmap
dwb_critics::MapGridCritic::ScoreAggregationType
ScoreAggregationType
Separate modes for aggregating scores across the multiple poses in a trajectory.
Definition: map_grid.h:100
dwb_critics::MapGridCritic::MapGridQueue
Subclass of CostmapQueue that avoids Obstacles and Unknown Values.
Definition: map_grid.h:106
dwb_critics::MapGridCritic::obstacle_score_
double obstacle_score_
Definition: map_grid.h:128
dwb_critics::MapGridCritic::propogateManhattanDistances
void propogateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents.
Definition: map_grid.cpp:110
costmap_queue::CostmapQueue::CostmapQueue
CostmapQueue(nav_core2::Costmap &costmap, bool manhattan=false)
costmap_queue
dwb_critics::MapGridCritic::setAsObstacle
void setAsObstacle(unsigned int x, unsigned int y)
Sets the score of a particular cell to the obstacle cost.
Definition: map_grid.cpp:89
dwb_critics::MapGridCritic
breadth-first scoring of all the cells in the costmap
Definition: map_grid.h:58
costmap_queue.h
dwb_critics::MapGridCritic::scorePose
virtual double scorePose(const geometry_msgs::Pose2D &pose)
Retrieve the score for a single pose.
Definition: map_grid.cpp:170
trajectory_critic.h
costmap_queue::CostmapQueue
dwb_critics::MapGridCritic::aggregationType_
ScoreAggregationType aggregationType_
Definition: map_grid.h:130
dwb_critics::MapGridCritic::addCriticVisualization
void addCriticVisualization(sensor_msgs::PointCloud &pc) override
Definition: map_grid.cpp:181
costmap_queue::CellData
dwb_critics::MapGridCritic::getScale
double getScale() const override
Definition: map_grid.h:67
dwb_critics::MapGridCritic::MapGridQueue::MapGridQueue
MapGridQueue(nav_core2::Costmap &costmap, MapGridCritic &parent)
Definition: map_grid.h:109
dwb_critics::MapGridCritic::stop_on_failure_
bool stop_on_failure_
Definition: map_grid.h:129
dwb_critics::MapGridCritic::MapGridQueue::validCellToQueue
bool validCellToQueue(const costmap_queue::CellData &cell) override
Definition: map_grid.cpp:46
dwb_critics::MapGridCritic::getScore
double getScore(unsigned int x, unsigned int y)
Retrieve the score for a particular cell of the costmap.
Definition: map_grid.h:83
dwb_critics::MapGridCritic::queue_
std::shared_ptr< MapGridQueue > queue_
Definition: map_grid.h:126
dwb_local_planner::TrajectoryCritic::scale_
double scale_
dwb_critics::MapGridCritic::cell_values_
nav_grid::VectorNavGrid< double > cell_values_
Definition: map_grid.h:127
dwb_critics::MapGridCritic::ScoreAggregationType::Sum
@ Sum
dwb_critics::MapGridCritic::onInit
void onInit() override
Definition: map_grid.cpp:60
nav_core2::Costmap
dwb_critics
Definition: alignment_util.h:40
dwb_critics::MapGridCritic::scoreTrajectory
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
Definition: map_grid.cpp:121
dwb_critics::MapGridCritic::unreachable_score_
double unreachable_score_
Special cell_values.
Definition: map_grid.h:128
dwb_local_planner::TrajectoryCritic
dwb_local_planner::TrajectoryCritic::costmap_
nav_core2::Costmap::Ptr costmap_
dwb_critics::MapGridCritic::reset
void reset() override
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore.
Definition: map_grid.cpp:94
nav_grid::VectorNavGrid< double >
dwb_critics::MapGridCritic::MapGridQueue::parent_
MapGridCritic & parent_
Definition: map_grid.h:113


dwb_critics
Author(s): David V. Lu!!
autogenerated on Sun May 18 2025 02:47:34