37 #include <costmap_cspace_msgs/MapMetaData3D.h> 51 const costmap_cspace_msgs::MapMetaData3D& map_info,
52 const Vecf& euclid_cost_coef,
53 const int local_range,
62 , euclid_cost_coef_(euclid_cost_coef)
64 1.0
f / map_info.linear_resolution,
65 1.0
f / map_info.linear_resolution,
66 1.0
f / map_info.angular_resolution)
67 , local_range_(local_range)
68 , cost_estim_cache_(cost_estim_cache)
77 costmap_cspace_msgs::MapMetaData3D map_info_linear(
map_info_);
78 map_info_linear.angle = 1;
81 map_info_linear.linear_resolution,
82 map_info_linear.angular_resolution,
124 for (
int rootsum = 0;
135 while (angle > static_cast<int>(
map_info_.angle) / 2)
136 angle -=
static_cast<int>(
map_info_.angle);
137 while (angle < -static_cast<int>(
map_info_.angle) / 2)
138 angle += static_cast<int>(
map_info_.angle);
145 for (
int i = 0; i < 2; ++i)
146 rootsum += v[i] * v[i];
156 const Vec& cur,
const Vec& next,
const std::vector<VecWithCost>& start,
const Vec& goal)
const 158 Vec d_raw = next - cur;
163 if (d[0] == 0 && d[1] == 0)
167 const int dir = d[2] < 0 ? -1 : 1;
169 for (
int i = 0; i < std::abs(d[2]); i++)
174 else if (pos[2] >= static_cast<int>(
map_info_.angle))
176 const auto c =
cm_[pos];
191 const float dist = motion.
len();
201 const float aspect = motion[0] / motion[1];
205 int sum = 0, sum_hyst = 0;
206 Vec d_index(d[0], d[1], next[2]);
212 const int num = cache_page->second.getMotion().size();
213 for (
const auto& pos_diff : cache_page->second.getMotion())
216 cur[0] + pos_diff[0], cur[1] + pos_diff[1], pos_diff[2]);
217 const auto c =
cm_[pos];
225 const float distf = cache_page->second.getDistance();
232 const float r1 = radiuses.first;
233 const float r2 = radiuses.second;
234 const float curv_radius = (r1 + r2) / 2;
249 int sum = 0, sum_hyst = 0;
250 Vec d_index(d[0], d[1], next[2]);
256 const int num = cache_page->second.getMotion().size();
257 for (
const auto& pos_diff : cache_page->second.getMotion())
260 cur[0] + pos_diff[0], cur[1] + pos_diff[1], pos_diff[2]);
261 const auto c =
cm_[pos];
269 const float distf = cache_page->second.getDistance();
279 const Vec& cur,
const Vec& goal)
const 281 Vec s2(cur[0], cur[1], 0);
283 if (cost == std::numeric_limits<float>::max())
284 return std::numeric_limits<float>::max();
286 int diff = cur[2] - goal[2];
287 while (diff > static_cast<int>(
map_info_.angle) / 2)
288 diff -=
static_cast<int>(
map_info_.angle);
289 while (diff < -static_cast<int>(
map_info_.angle) / 2)
290 diff += static_cast<int>(
map_info_.angle);
298 const std::vector<VecWithCost>& ss,
302 for (
const VecWithCost&
s : ss)
304 const Vec ds =
s.v_ - p;
306 if (ds.
sqlen() < local_range_sq)
315 const Vec& cur,
const Vec& next,
const std::vector<VecWithCost>& start,
const Vec& goal)
const 319 float cost = base_->euclidCostRough(d);
322 const auto cache_page = base_->motion_cache_linear_.find(0, d);
323 if (cache_page == base_->motion_cache_linear_.end(0))
325 const int num = cache_page->second.getMotion().size();
326 for (
const auto& pos_diff : cache_page->second.getMotion())
328 const Vec pos(cur[0] + pos_diff[0], cur[1] + pos_diff[1], 0);
329 const auto c = base_->cm_rough_[pos];
334 const float distf = cache_page->second.getDistance();
335 cost += sum * base_->map_info_.linear_resolution *
336 distf * base_->cc_.weight_costmap_ / (100.0 * num);
341 const Vec& cur,
const Vec& goal)
const 343 const Vec d = goal - cur;
344 const float cost = base_->euclidCostRough(d);
349 const Vec& cur,
const std::vector<VecWithCost>& start,
const Vec& goal)
const 351 return base_->search_list_rough_;
std::array< float, 1024 > euclid_cost_lin_cache_
float cost(const Vec &cur, const Vec &next, const std::vector< VecWithCost > &start, const Vec &goal) const final
float costEstim(const Vec &cur, const Vec &goal) const final
const BlockMemGridmapBase< char, 3, 2 > & cm_
const std::vector< Vec > & searchGrids(const Vec &p, const std::vector< VecWithCost > &ss, const Vec &es) const override
const CyclicVecFloat< 3, 2 > & getMotion(const int start_angle, const CyclicVecInt< 3, 2 > &end) const
float weight_costmap_turn_
virtual std::function< void(CyclicVecInt< DIM, NONCYCLIC >, size_t &, size_t &)> getAddressor() const =0
const BlockMemGridmapBase< float, 3, 2 > & cost_estim_cache_
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
std::vector< std::vector< Vec > > motion_primitives_
const CyclicVecInt< 3, 2 > & getMaxRange() const
const std::pair< float, float > & getRadiuses(const int start_angle, const CyclicVecInt< 3, 2 > &end) const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
float euclidCost(const Vec &v) const
std::vector< Vec > search_list_rough_
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)
void reset(const float linear_resolution, const float angular_resolution, const int range)
float cost(const Vec &cur, const Vec &next, const std::vector< VecWithCost > &start, const Vec &goal) const override
void cycleUnsigned(const int res, const ArgList &... rest)
void enableHysteresis(const bool enable)
const BlockMemGridmapBase< char, 3, 2 > & cm_hyst_
const BlockMemGridmapBase< char, 3, 2 > & cm_rough_
const Cache::const_iterator find(const int start_yaw, const CyclicVecInt< 3, 2 > &goal) const
float costEstim(const Vec &cur, const Vec &goal) const override
MotionCache motion_cache_
const std::vector< Vec > & searchGrids(const Vec &cur, const std::vector< VecWithCost > &start, const Vec &goal) const final
PathInterpolator path_interpolator_
float euclidCostRough(const Vec &v) const
void reset(const float angular_resolution, const int range)
void cycle(const int res, const ArgList &... rest)
const Cache::const_iterator end(const int start_yaw) const
MotionCache motion_cache_linear_
static std::vector< std::vector< Vec > > build(const costmap_cspace_msgs::MapMetaData3D &map_info, const CostCoeff &cc, const int range)
void createEuclidCostCache()
costmap_cspace_msgs::MapMetaData3D map_info_
GridAstarModel3D(const costmap_cspace_msgs::MapMetaData3D &map_info, const Vecf &euclid_cost_coef, const int local_range, const BlockMemGridmapBase< float, 3, 2 > &cost_estim_cache, const BlockMemGridmapBase< char, 3, 2 > &cm, const BlockMemGridmapBase< char, 3, 2 > &cm_hyst, const BlockMemGridmapBase< char, 3, 2 > &cm_rough, const CostCoeff &cc, const int range)