gpp_prune_path.hpp
Go to the documentation of this file.
1 /*
2  * MIT License
3  *
4  * Copyright (c) 2021 Dima Dorezyuk
5  *
6  * Permission is hereby granted, free of charge, to any person obtaining a copy
7  * of this software and associated documentation files (the "Software"), to deal
8  * in the Software without restriction, including without limitation the rights
9  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10  * copies of the Software, and to permit persons to whom the Software is
11  * furnished to do so, subject to the following conditions:
12  *
13  * The above copyright notice and this permission notice shall be included in
14  * all copies or substantial portions of the Software.
15  *
16  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22  * SOFTWARE.
23  */
24 
25 #pragma once
26 
28 
29 #include <iterator>
30 
31 namespace gpp_prune_path {
32 
33 namespace internal {
34 
66 template <typename _Iter>
67 _Iter
68 prune(_Iter _begin, _Iter _end, size_t _step) {
69  if (_step < 2)
70  return _end;
71  // find the distance between _begin and end
72  const auto distance = std::distance(_begin, _end);
73 
74  // we prune such that we always include the first and last element of the
75  // sequence. if the distance is less than three, we cannot prune.
76  if (distance < 2)
77  return _end;
78 
79  // find the end of our source.
80  // note: we denote the source (s) as the iterator from where we are copying
81  // data; the destination is denoted with (d).
82  const _Iter d_end = _begin + (distance + _step - 2) / _step;
83 
84  // inplace pruning.
85  // note: don't use std::move, as it doesn't work for ros-msgs...
86  for (_Iter s_begin = _begin; _begin != d_end; ++_begin, s_begin += _step)
87  *_begin = *s_begin;
88 
89  // last element must be updated separatelly:
90  *_begin++ = *std::prev(_end);
91 
92  return _begin;
93 }
94 } // namespace internal
95 
96 // short-cut
98 
112  bool
113  postProcess(const Pose &_start, const Pose &_goal, Path &_path,
114  double &_cost) override;
115 
116  void
117  initialize(const std::string &_name, Map *_map) override;
118 
119 private:
120  int step_ = 0;
121 };
122 
123 } // namespace gpp_prune_path
gpp_prune_path
Definition: gpp_prune_path.hpp:31
gpp_prune_path::GppPrunePath::postProcess
bool postProcess(const Pose &_start, const Pose &_goal, Path &_path, double &_cost) override
Definition: gpp_prune_path.cpp:32
gpp_prune_path::GppPrunePath
post-processing class which will prune the given path.
Definition: gpp_prune_path.hpp:111
gpp_interface::PostPlanningInterface
post_planning_interface.hpp
distance
double distance(double x0, double y0, double x1, double y1)
gpp_prune_path::GppPrunePath::step_
int step_
Definition: gpp_prune_path.hpp:120
gpp_prune_path::internal::prune
_Iter prune(_Iter _begin, _Iter _end, size_t _step)
inplace pruning for a random-access iterator-sequence
Definition: gpp_prune_path.hpp:68
gpp_interface::PostPlanningInterface::Path
std::vector< Pose > Path
gpp_interface::PostPlanningInterface::Pose
geometry_msgs::PoseStamped Pose
costmap_2d::Costmap2DROS
gpp_prune_path::GppPrunePath::initialize
void initialize(const std::string &_name, Map *_map) override
Definition: gpp_prune_path.cpp:51


gpp_prune_path
Author(s):
autogenerated on Wed Mar 2 2022 00:21:26