30 #ifndef PLANNER_CSPACE_PLANNER_3D_MOTION_CACHE_H 31 #define PLANNER_CSPACE_PLANNER_3D_MOTION_CACHE_H 34 #include <unordered_map> 59 const std::vector<CyclicVecInt<3, 2>>&
getMotion()
const 68 using Ptr = std::shared_ptr<MotionCache>;
70 inline const typename Cache::const_iterator
find(
72 const CyclicVecInt<3, 2>& goal)
const 77 return cache_[i].find(goal);
79 inline const typename Cache::const_iterator
end(
80 const int start_yaw)
const 94 const float linear_resolution,
95 const float angular_resolution,
97 const std::function<
void(CyclicVecInt<3, 2>,
size_t&,
size_t&)> gm_addr);
107 #endif // PLANNER_CSPACE_PLANNER_3D_MOTION_CACHE_H float getDistance() const
const Cache::const_iterator end(const int start_yaw) const
const CyclicVecInt< 3, 2 > & getMaxRange() const
std::vector< CyclicVecInt< 3, 2 > > motion_
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 std::vector< CyclicVecInt< 3, 2 > > & getMotion() const
std::unordered_map< CyclicVecInt< 3, 2 >, Page, CyclicVecInt< 3, 2 >> Cache
std::shared_ptr< MotionCache > Ptr
CyclicVecInt< 3, 2 > max_range_
std::vector< Cache > cache_
const Cache::const_iterator find(const int start_yaw, const CyclicVecInt< 3, 2 > &goal) const