gpp_prune_path.cpp
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 
26 
28 
29 namespace gpp_prune_path {
30 
31 bool
32 GppPrunePath::postProcess(const Pose &_start, const Pose &_goal, Path &_path,
33  double &_cost) {
34  // start and goal arguments are not really required here.
35  // this class is a noop, if the defined step is less than 2
36  if (step_ < 2)
37  return true;
38 
39  // in order to prune the path, we need at least three poses - since we dont
40  // want to change the start and goal pose.
41  if (_path.size() < 2)
42  return false;
43 
44  auto end = internal::prune(_path.begin(), _path.end(), step_);
45  _path.erase(end, _path.end());
46 
47  return true;
48 }
49 
50 void
51 GppPrunePath::initialize(const std::string &_name, Map *_map) {
52  // load the config
53  ros::NodeHandle nh("~/" + _name);
54 
55  step_ = nh.param("step", 2);
56 }
57 } // namespace gpp_prune_path
58 
59 // register the plugin
gpp_prune_path
Definition: gpp_prune_path.hpp:31
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(gpp_prune_path::GppPrunePath, gpp_interface::PostPlanningInterface)
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
gpp_prune_path.hpp
gpp_prune_path::GppPrunePath::step_
int step_
Definition: gpp_prune_path.hpp:120
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
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
ros::NodeHandle


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