motion_cache.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018-2019, 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_MOTION_CACHE_H
31 #define PLANNER_CSPACE_PLANNER_3D_MOTION_CACHE_H
32 
33 #include <memory>
34 #include <list>
35 #include <unordered_map>
36 #include <vector>
37 
39 
40 namespace planner_cspace
41 {
42 namespace planner_3d
43 {
45 {
46 public:
47  class Page
48  {
49  protected:
50  friend class MotionCache;
51 
52  std::vector<CyclicVecInt<3, 2>> motion_;
53  std::vector<CyclicVecFloat<3, 2>> interpolated_motion_;
54  float distance_;
55 
56  public:
57  inline float getDistance() const
58  {
59  return distance_;
60  }
61  const std::vector<CyclicVecInt<3, 2>>& getMotion() const
62  {
63  return motion_;
64  }
65  const std::vector<CyclicVecFloat<3, 2>>& getInterpolatedMotion() const
66  {
67  return interpolated_motion_;
68  }
69  };
70 
71  using Cache =
72  std::unordered_map<CyclicVecInt<3, 2>, Page, CyclicVecInt<3, 2>>;
73 
74  using Ptr = std::shared_ptr<MotionCache>;
75 
76  inline const typename Cache::const_iterator find(
77  const int start_yaw,
78  const CyclicVecInt<3, 2>& goal) const
79  {
80  int i = start_yaw % page_size_;
81  if (i < 0)
82  i += page_size_;
83  return cache_[i].find(goal);
84  }
85  inline const typename Cache::const_iterator find(
86  const CyclicVecInt<3, 2>& from,
87  const CyclicVecInt<3, 2>& to) const
88  {
89  const int start_yaw = from[2];
90  const CyclicVecInt<3, 2> goal(to[0] - from[0], to[1] - from[1], to[2]);
91  return find(start_yaw, goal);
92  }
93  inline const typename Cache::const_iterator end(
94  const int start_yaw) const
95  {
96  int i = start_yaw % page_size_;
97  if (i < 0)
98  i += page_size_;
99  return cache_[i].cend();
100  }
101 
102  inline const CyclicVecInt<3, 2>& getMaxRange() const
103  {
104  return max_range_;
105  }
106 
107  void reset(
108  const float linear_resolution,
109  const float angular_resolution,
110  const int range,
111  const std::function<void(CyclicVecInt<3, 2>, size_t&, size_t&)> gm_addr,
112  const float interpolation_resolution,
113  const float grid_enumeration_resolution);
114 
115  std::list<CyclicVecFloat<3, 2>> interpolatePath(const std::list<CyclicVecInt<3, 2>>& path_grid) const;
116 
117 protected:
118  std::vector<Cache> cache_;
121 };
122 } // namespace planner_3d
123 } // namespace planner_cspace
124 
125 #endif // PLANNER_CSPACE_PLANNER_3D_MOTION_CACHE_H
planner_cspace::planner_3d::MotionCache::Page::getMotion
const std::vector< CyclicVecInt< 3, 2 > > & getMotion() const
Definition: motion_cache.h:61
planner_cspace::planner_3d::MotionCache::Cache
std::unordered_map< CyclicVecInt< 3, 2 >, Page, CyclicVecInt< 3, 2 > > Cache
Definition: motion_cache.h:72
planner_cspace
Definition: bbf.h:33
planner_cspace::planner_3d::MotionCache::find
const Cache::const_iterator find(const int start_yaw, const CyclicVecInt< 3, 2 > &goal) const
Definition: motion_cache.h:76
planner_cspace::planner_3d::MotionCache::reset
void reset(const float linear_resolution, const float angular_resolution, const int range, const std::function< void(CyclicVecInt< 3, 2 >, size_t &, size_t &)> gm_addr, const float interpolation_resolution, const float grid_enumeration_resolution)
Definition: motion_cache.cpp:45
planner_cspace::planner_3d::MotionCache::Page::motion_
std::vector< CyclicVecInt< 3, 2 > > motion_
Definition: motion_cache.h:52
planner_cspace::planner_3d::MotionCache::getMaxRange
const CyclicVecInt< 3, 2 > & getMaxRange() const
Definition: motion_cache.h:102
planner_cspace::planner_3d::MotionCache::Page::getDistance
float getDistance() const
Definition: motion_cache.h:57
planner_cspace::planner_3d::MotionCache::Page::getInterpolatedMotion
const std::vector< CyclicVecFloat< 3, 2 > > & getInterpolatedMotion() const
Definition: motion_cache.h:65
planner_cspace::planner_3d::MotionCache::Page::distance_
float distance_
Definition: motion_cache.h:54
planner_cspace::planner_3d::MotionCache::find
const Cache::const_iterator find(const CyclicVecInt< 3, 2 > &from, const CyclicVecInt< 3, 2 > &to) const
Definition: motion_cache.h:85
planner_cspace::planner_3d::MotionCache::Page::interpolated_motion_
std::vector< CyclicVecFloat< 3, 2 > > interpolated_motion_
Definition: motion_cache.h:53
planner_cspace::planner_3d::MotionCache::page_size_
int page_size_
Definition: motion_cache.h:119
planner_cspace::planner_3d::MotionCache::end
const Cache::const_iterator end(const int start_yaw) const
Definition: motion_cache.h:93
planner_cspace::planner_3d::MotionCache::Ptr
std::shared_ptr< MotionCache > Ptr
Definition: motion_cache.h:74
cyclic_vec.h
planner_cspace::planner_3d::MotionCache::max_range_
CyclicVecInt< 3, 2 > max_range_
Definition: motion_cache.h:120
planner_cspace::planner_3d::MotionCache
Definition: motion_cache.h:44
planner_cspace::planner_3d::MotionCache::interpolatePath
std::list< CyclicVecFloat< 3, 2 > > interpolatePath(const std::list< CyclicVecInt< 3, 2 >> &path_grid) const
Definition: motion_cache.cpp:192
planner_cspace::planner_3d::MotionCache::cache_
std::vector< Cache > cache_
Definition: motion_cache.h:118
planner_cspace::planner_3d::MotionCache::Page
Definition: motion_cache.h:47
planner_cspace::CyclicVecBase
Definition: cyclic_vec.h:78


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