costmap_queue.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 COSTMAP_QUEUE_COSTMAP_QUEUE_H
36 #define COSTMAP_QUEUE_COSTMAP_QUEUE_H
37 
38 #include <nav_core2/costmap.h>
41 #include <algorithm>
42 #include <limits>
43 #include <memory>
44 #include <vector>
45 
46 namespace costmap_queue
47 {
52 class CellData
53 {
54 public:
63  CellData(const double d, const unsigned int x, const unsigned int y, const unsigned int sx, const unsigned int sy) :
64  distance_(d), x_(x), y_(y), src_x_(sx), src_y_(sy)
65  {
66  }
67 
72  distance_(std::numeric_limits<double>::max()), x_(0), y_(0), src_x_(0), src_y_(0)
73  {
74  }
75 
76  double distance_;
77  unsigned int x_, y_;
78  unsigned int src_x_, src_y_;
79 };
80 
100 class CostmapQueue : public MapBasedQueue<CellData>
101 {
102 public:
108  explicit CostmapQueue(nav_core2::Costmap& costmap, bool manhattan = false);
109 
113  void reset() override;
114 
120  void enqueueCell(unsigned int x, unsigned int y);
121 
129 
133  virtual int getMaxDistance() const { return std::max(costmap_.getWidth(), costmap_.getHeight()); }
134 
140  virtual bool validCellToQueue(const CellData& cell) { return true; }
141 
145  using Ptr = std::shared_ptr<CostmapQueue>;
146 protected:
150  void enqueueCell(unsigned int cur_x, unsigned int cur_y, unsigned int src_x, unsigned int src_y);
151 
155  void computeCache();
156 
158 
159  // This really should be VectorNavGrid<bool>, but since
160  // vector<bool> is wacky, it would result in compile errors.
163 protected:
178  inline double distanceLookup(const unsigned int cur_x, const unsigned int cur_y,
179  const unsigned int src_x, const unsigned int src_y)
180  {
181  unsigned int dx = std::abs(static_cast<int>(cur_x) - static_cast<int>(src_x));
182  unsigned int dy = std::abs(static_cast<int>(cur_y) - static_cast<int>(src_y));
183  return cached_distances_[dx][dy];
184  }
185  std::vector<std::vector<double> > cached_distances_;
187 };
188 } // namespace costmap_queue
189 
190 #endif // COSTMAP_QUEUE_COSTMAP_QUEUE_H
costmap_queue::CellData::src_y_
unsigned int src_y_
Definition: costmap_queue.h:78
costmap
nav_core2::BasicCostmap costmap
Definition: utest.cpp:43
costmap_queue::CostmapQueue::reset
void reset() override
Clear the queue.
Definition: costmap_queue.cpp:47
costmap_queue::CellData::y_
unsigned int y_
Definition: costmap_queue.h:77
costmap_queue::CostmapQueue::distanceLookup
double distanceLookup(const unsigned int cur_x, const unsigned int cur_y, const unsigned int src_x, const unsigned int src_y)
Lookup pre-computed distances.
Definition: costmap_queue.h:178
costmap_queue::CostmapQueue::manhattan_
bool manhattan_
Definition: costmap_queue.h:162
costmap_queue::CostmapQueue::CostmapQueue
CostmapQueue(nav_core2::Costmap &costmap, bool manhattan=false)
constructor
Definition: costmap_queue.cpp:41
costmap_queue
Definition: costmap_queue.h:46
costmap_queue::CostmapQueue::computeCache
void computeCache()
Compute the cached distances.
Definition: costmap_queue.cpp:99
costmap_queue::CellData::x_
unsigned int x_
Definition: costmap_queue.h:77
costmap_queue::CostmapQueue::enqueueCell
void enqueueCell(unsigned int x, unsigned int y)
Add a cell the queue.
Definition: costmap_queue.cpp:55
costmap_queue::CostmapQueue
A tool for finding the cells closest to some set of originating cells.
Definition: costmap_queue.h:100
costmap_queue::CostmapQueue::getNextCell
CellData getNextCell()
Get the next cell to examine, and enqueue its neighbors as needed.
Definition: costmap_queue.cpp:75
costmap_queue::CostmapQueue::cached_max_distance_
int cached_max_distance_
Definition: costmap_queue.h:186
costmap_queue::CostmapQueue::Ptr
std::shared_ptr< CostmapQueue > Ptr
convenience definition for a pointer
Definition: costmap_queue.h:145
vector_nav_grid.h
costmap.h
costmap_queue::CellData
Storage for cell information used during queue expansion.
Definition: costmap_queue.h:52
costmap_queue::CellData::distance_
double distance_
Definition: costmap_queue.h:76
map_based_queue.h
costmap_queue::CellData::src_x_
unsigned int src_x_
Definition: costmap_queue.h:78
d
d
costmap_queue::CostmapQueue::getMaxDistance
virtual int getMaxDistance() const
Get the maximum x or y distance we'll need to calculate the distance between.
Definition: costmap_queue.h:133
costmap_queue::CostmapQueue::seen_
nav_grid::VectorNavGrid< unsigned char > seen_
Definition: costmap_queue.h:161
costmap_queue::CostmapQueue::costmap_
nav_core2::Costmap & costmap_
Definition: costmap_queue.h:157
costmap_queue::CellData::CellData
CellData(const double d, const unsigned int x, const unsigned int y, const unsigned int sx, const unsigned int sy)
Real Constructor.
Definition: costmap_queue.h:63
std
costmap_queue::CostmapQueue::validCellToQueue
virtual bool validCellToQueue(const CellData &cell)
Check to see if we should add this cell to the queue. Always true unless overridden.
Definition: costmap_queue.h:140
costmap_queue::MapBasedQueue
Templatized interface for a priority queue.
Definition: map_based_queue.h:61
nav_core2::Costmap
costmap_queue::CellData::CellData
CellData()
Default Constructor - Should be used sparingly.
Definition: costmap_queue.h:71
costmap_queue::CostmapQueue::cached_distances_
std::vector< std::vector< double > > cached_distances_
Definition: costmap_queue.h:185
nav_grid::VectorNavGrid< unsigned char >


costmap_queue
Author(s):
autogenerated on Sun May 18 2025 02:47:19