planner_3d/grid_astar_model.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019-2020, 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_GRID_ASTAR_MODEL_H
31 #define PLANNER_CSPACE_PLANNER_3D_GRID_ASTAR_MODEL_H
32 
33 #include <array>
34 #include <memory>
35 #include <utility>
36 #include <vector>
37 
38 #include <costmap_cspace_msgs/MapMetaData3D.h>
39 
46 
47 namespace planner_cspace
48 {
49 namespace planner_3d
50 {
51 class CostCoeff
52 {
53 public:
65  float max_vel_;
66  float max_ang_vel_;
68 };
69 
71 {
72 public:
73  friend class GridAstarModel2D;
74  using Ptr = std::shared_ptr<GridAstarModel3D>;
75  using ConstPtr = std::shared_ptr<const GridAstarModel3D>;
78 
80 
81 protected:
83  costmap_cspace_msgs::MapMetaData3D map_info_;
86  std::vector<std::vector<Vec>> motion_primitives_;
87  std::vector<Vec> search_list_rough_;
93  const CostCoeff& cc_;
94  int range_;
100  std::array<float, 1024> euclid_cost_lin_cache_;
101 
102 public:
103  explicit GridAstarModel3D(
104  const costmap_cspace_msgs::MapMetaData3D& map_info,
105  const Vecf& euclid_cost_coef,
106  const int local_range,
107  const BlockMemGridmapBase<float, 3, 2>& cost_estim_cache,
109  const BlockMemGridmapBase<char, 3, 2>& cm_hyst,
110  const BlockMemGridmapBase<char, 3, 2>& cm_rough,
111  const CostCoeff& cc,
112  const int range);
113  void enableHysteresis(const bool enable);
114  void createEuclidCostCache();
115  float euclidCost(const Vec& v) const;
116  float euclidCostRough(const Vec& v) const;
117  float cost(
118  const Vec& cur, const Vec& next, const std::vector<VecWithCost>& start, const Vec& goal) const override;
119 
120  float costEstim(
121  const Vec& cur, const Vec& goal) const override;
122  const std::vector<Vec>& searchGrids(
123  const Vec& p,
124  const std::vector<VecWithCost>& ss,
125  const Vec& es) const override;
126 };
127 
129 {
130 public:
131  using Ptr = std::shared_ptr<GridAstarModel2D>;
133 
134  inline explicit GridAstarModel2D(const GridAstarModel3D::ConstPtr base)
135  : base_(base)
136  {
137  }
138 
139  float cost(
140  const Vec& cur, const Vec& next, const std::vector<VecWithCost>& start, const Vec& goal) const final;
141  float costEstim(
142  const Vec& cur, const Vec& goal) const final;
143  const std::vector<Vec>& searchGrids(
144  const Vec& cur, const std::vector<VecWithCost>& start, const Vec& goal) const final;
145 };
146 } // namespace planner_3d
147 } // namespace planner_cspace
148 
149 #endif // PLANNER_CSPACE_PLANNER_3D_GRID_ASTAR_MODEL_H
ROSCPP_DECL void start()
const BlockMemGridmapBase< char, 3, 2 > & cm_
const BlockMemGridmapBase< float, 3, 2 > & cost_estim_cache_
std::vector< std::vector< Vec > > motion_primitives_
const BlockMemGridmapBase< char, 3, 2 > & cm_hyst_
std::shared_ptr< const GridAstarModel3D > ConstPtr
const BlockMemGridmapBase< char, 3, 2 > & cm_rough_
GridAstarModel2D(const GridAstarModel3D::ConstPtr base)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06