distance_map.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2021, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef PLANNER_CSPACE_PLANNER_3D_DISTANCE_MAP_H
31 #define PLANNER_CSPACE_PLANNER_3D_DISTANCE_MAP_H
32 
33 #include <cmath>
34 #include <limits>
35 #include <unordered_map>
36 #include <utility>
37 #include <vector>
38 
42 
43 namespace planner_cspace
44 {
45 namespace planner_3d
46 {
48 {
49 public:
51 
52  struct Rect
53  {
56  Rect(const Astar::Vec& min, const Astar::Vec& max)
57  : min(min)
58  , max(max) // NOLINT(build/include_what_you_use)
59  {
60  }
61  };
62 
63  struct DebugData
64  {
68  };
69 
70  struct Params
71  {
73  int range;
77  float resolution;
78  };
79 
80  struct SearchDiffs
81  {
83  std::vector<Astar::Vec> pos;
84  float grid_to_len;
85  float euclid_cost;
86  };
87 
89  const BlockMemGridmapBase<char, 3, 2>& cm_rough,
90  const CostmapBBF::ConstPtr bbf_costmap);
91 
92  void setParams(const CostCoeff& cc, const int num_cost_estim_task);
93 
94  void init(const GridAstarModel3D::Ptr model, const Params& p);
95 
96  void update(
97  const Astar::Vec& s, const Astar::Vec& e,
98  const Rect& rect);
99 
100  void create(const Astar::Vec& s, const Astar::Vec& e);
101 
102  inline const Astar::Vec& size() const
103  {
104  return g_.size();
105  }
106  inline float& operator[](const Astar::Vec& pos)
107  {
108  return g_.operator[](pos);
109  }
110  inline const float operator[](const Astar::Vec& pos) const
111  {
112  return g_.operator[](pos);
113  }
114  inline const Astar::Gridmap<float>& gridmap() const
115  {
116  return g_;
117  }
118  inline const DebugData& getDebugData() const
119  {
120  return debug_data_;
121  }
122 
123 protected:
124  Astar::Gridmap<float> g_;
130 
131  std::vector<SearchDiffs> search_diffs_;
133 
136  std::vector<bool> edges_buf_;
137 
139 
140  void fillCostmap(
142  const Astar::Vec& s_rough);
143 };
144 } // namespace planner_3d
145 } // namespace planner_cspace
146 
147 #endif // PLANNER_CSPACE_PLANNER_3D_DISTANCE_MAP_H
planner_cspace::planner_3d::DistanceMap::operator[]
float & operator[](const Astar::Vec &pos)
Definition: distance_map.h:106
planner_cspace::planner_3d::CostCoeff
Definition: planner_3d/grid_astar_model.h:51
planner_cspace::planner_3d::DistanceMap::num_cost_estim_task_
int num_cost_estim_task_
Definition: distance_map.h:127
planner_cspace::planner_3d::DistanceMap::SearchDiffs
Definition: distance_map.h:80
planner_cspace::planner_3d::DistanceMap::DebugData::search_queue_cap
size_t search_queue_cap
Definition: distance_map.h:66
planner_cspace::planner_3d::DistanceMap::DebugData::has_negative_cost
bool has_negative_cost
Definition: distance_map.h:67
planner_cspace::planner_3d::DistanceMap::bbf_costmap_
const CostmapBBF::ConstPtr bbf_costmap_
Definition: distance_map.h:129
planner_cspace
Definition: bbf.h:33
planner_cspace::planner_3d::DistanceMap::g_
Astar::Gridmap< float > g_
Definition: distance_map.h:124
planner_cspace::planner_3d::DistanceMap::Rect::max
Astar::Vec max
Definition: distance_map.h:55
planner_cspace::planner_3d::DistanceMap::debug_data_
DebugData debug_data_
Definition: distance_map.h:132
planner_cspace::planner_3d::DistanceMap::update
void update(const Astar::Vec &s, const Astar::Vec &e, const Rect &rect)
Definition: distance_map.cpp:250
planner_cspace::planner_3d::DistanceMap::pq_open_
reservable_priority_queue< Astar::PriorityVec > pq_open_
Definition: distance_map.h:134
planner_cspace::planner_3d::CostmapBBF::ConstPtr
std::shared_ptr< const CostmapBBF > ConstPtr
Definition: costmap_bbf.h:48
planner_cspace::planner_3d::DistanceMap::SearchDiffs::d
Astar::Vec d
Definition: distance_map.h:82
planner_cspace::planner_3d::DistanceMap::Params::size
Astar::Vec size
Definition: distance_map.h:76
planner_cspace::planner_3d::DistanceMap::p_
Params p_
Definition: distance_map.h:125
grid_astar_model.h
planner_cspace::planner_3d::DistanceMap::Rect::min
Astar::Vec min
Definition: distance_map.h:54
costmap_bbf.h
planner_cspace::planner_3d::DistanceMap::SearchDiffs::pos
std::vector< Astar::Vec > pos
Definition: distance_map.h:83
planner_cspace::planner_3d::DistanceMap::size
const Astar::Vec & size() const
Definition: distance_map.h:102
planner_cspace::BlockMemGridmapBase< char, 3, 2 >
planner_cspace::planner_3d::DistanceMap::SearchDiffs::grid_to_len
float grid_to_len
Definition: distance_map.h:84
planner_cspace::planner_3d::DistanceMap::cc_
CostCoeff cc_
Definition: distance_map.h:126
planner_cspace::planner_3d::DistanceMap::getDebugData
const DebugData & getDebugData() const
Definition: distance_map.h:118
planner_cspace::GridAstar< 3, 2 >
planner_cspace::planner_3d::DistanceMap::Params::local_range
int local_range
Definition: distance_map.h:74
planner_cspace::planner_3d::DistanceMap::Params
Definition: distance_map.h:70
planner_cspace::planner_3d::DistanceMap::Params::resolution
float resolution
Definition: distance_map.h:77
planner_cspace::planner_3d::DistanceMap::create
void create(const Astar::Vec &s, const Astar::Vec &e)
Definition: distance_map.cpp:356
grid_astar.h
planner_cspace::planner_3d::DistanceMap::Rect::Rect
Rect(const Astar::Vec &min, const Astar::Vec &max)
Definition: distance_map.h:56
planner_cspace::planner_3d::DistanceMap::pq_erase_
reservable_priority_queue< Astar::PriorityVec > pq_erase_
Definition: distance_map.h:135
planner_cspace::planner_3d::DistanceMap::search_diffs_
std::vector< SearchDiffs > search_diffs_
Definition: distance_map.h:131
planner_cspace::planner_3d::DistanceMap::Params::longcut_range
int longcut_range
Definition: distance_map.h:75
planner_cspace::planner_3d::DistanceMap
Definition: distance_map.h:47
planner_cspace::planner_3d::DistanceMap::fillCostmap
void fillCostmap(reservable_priority_queue< Astar::PriorityVec > &open, const Astar::Vec &s_rough)
Definition: distance_map.cpp:46
planner_cspace::planner_3d::GridAstarModel3D::Ptr
std::shared_ptr< GridAstarModel3D > Ptr
Definition: planner_3d/grid_astar_model.h:76
planner_cspace::planner_3d::DistanceMap::DebugData
Definition: distance_map.h:63
planner_cspace::planner_3d::DistanceMap::operator[]
const float operator[](const Astar::Vec &pos) const
Definition: distance_map.h:110
planner_cspace::planner_3d::DistanceMap::gridmap
const Astar::Gridmap< float > & gridmap() const
Definition: distance_map.h:114
planner_cspace::GridAstar< 3, 2 >::Vec
CyclicVecInt< DIM, NONCYCLIC > Vec
Definition: grid_astar.h:67
planner_cspace::planner_3d::DistanceMap::DebugData::search_queue_size
size_t search_queue_size
Definition: distance_map.h:65
planner_cspace::planner_3d::DistanceMap::init
void init(const GridAstarModel3D::Ptr model, const Params &p)
Definition: distance_map.cpp:198
planner_cspace::planner_3d::DistanceMap::DistanceMap
DistanceMap(const BlockMemGridmapBase< char, 3, 2 > &cm_rough, const CostmapBBF::ConstPtr bbf_costmap)
Definition: distance_map.cpp:183
planner_cspace::planner_3d::DistanceMap::setParams
void setParams(const CostCoeff &cc, const int num_cost_estim_task)
Definition: distance_map.cpp:192
planner_cspace::planner_3d::DistanceMap::Rect
Definition: distance_map.h:52
planner_cspace::planner_3d::DistanceMap::Params::range
int range
Definition: distance_map.h:73
planner_cspace::planner_3d::DistanceMap::goal_
Astar::Vec goal_
Definition: distance_map.h:138
planner_cspace::planner_3d::DistanceMap::edges_buf_
std::vector< bool > edges_buf_
Definition: distance_map.h:136
planner_cspace::reservable_priority_queue
Definition: reservable_priority_queue.h:38
planner_cspace::planner_3d::DistanceMap::SearchDiffs::euclid_cost
float euclid_cost
Definition: distance_map.h:85
planner_cspace::planner_3d::DistanceMap::Params::euclid_cost
Astar::Vecf euclid_cost
Definition: distance_map.h:72
planner_cspace::planner_3d::DistanceMap::cm_rough_
const BlockMemGridmapBase< char, 3, 2 > & cm_rough_
Definition: distance_map.h:128
planner_cspace::CyclicVecBase
Definition: cyclic_vec.h:78


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:22