path_dist_pruned.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, DFKI GmbH
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 #include <nav_2d_utils/path_ops.h>
36 
38 
39 namespace mir_dwb_critics {
40 
42  const geometry_msgs::Pose2D &pose,
43  const nav_2d_msgs::Twist2D &vel,
44  const geometry_msgs::Pose2D &goal,
45  const nav_2d_msgs::Path2D &global_plan) {
46 
48  const nav_grid::NavGridInfo &info = costmap.getInfo();
49 
50  auto plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution).poses;
51 
52 
53  // --- stolen from PathProgressCritic::getGoalPose ---
54  // find the "start pose", i.e. the pose on the plan closest to the robot that is also on the local map
55  unsigned int start_index = 0;
56  double distance_to_start = std::numeric_limits<double>::infinity();
57  bool started_path = false;
58  for (unsigned int i = 0; i < plan.size(); i++) {
59  double g_x = plan[i].x;
60  double g_y = plan[i].y;
61  unsigned int map_x, map_y;
62  if (worldToGridBounded(info, g_x, g_y, map_x, map_y)
63  && costmap(map_x, map_y) != nav_core2::Costmap::NO_INFORMATION) {
64  // Still on the costmap. Continue.
65  double distance = nav_2d_utils::poseDistance(plan[i], pose);
66  if (distance_to_start > distance) {
67  start_index = i;
68  distance_to_start = distance;
69  started_path = true;
70  } else {
71  // Plan is going away from the robot again. It's possible that it comes back and we would find a pose that's
72  // even closer to the robot, but then we would skip over parts of the plan.
73  break;
74  }
75  } else if (started_path) {
76  // Off the costmap after being on the costmap.
77  break;
78  }
79  // else, we have not yet found a point on the costmap, so we just continue
80  }
81 
82  if (!started_path) {
83  ROS_ERROR_NAMED("PathDistPrunedCritic", "None of the points of the global plan were in the local costmap.");
84  return false;
85  }
86  // ---------------------------------------------------
87 
88  // remove the first part of the path, everything before start_index, to
89  // disregard that part in the PathDistCritic implementation.
90  nav_2d_msgs::Path2D global_plan_pruned;
91  global_plan_pruned.header = global_plan.header;
92  global_plan_pruned.poses = std::vector<geometry_msgs::Pose2D>(
93  plan.begin() + start_index,
94  plan.end());
95 
96  return dwb_critics::PathDistCritic::prepare(pose, vel, goal, global_plan_pruned);
97 }
98 
99 } // namespace mir_dwb_critics
100 
bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override
nav_core2::BasicCostmap costmap
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static const unsigned char NO_INFORMATION
Scores trajectories based on how far from the global path they end up, where the global path is prune...
double poseDistance(const geometry_msgs::Pose2D &pose0, const geometry_msgs::Pose2D &pose1)
nav_core2::Costmap::Ptr costmap_
nav_2d_msgs::Path2D adjustPlanResolution(const nav_2d_msgs::Path2D &global_plan_in, double resolution)
#define ROS_ERROR_NAMED(name,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)
virtual bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override


mir_dwb_critics
Author(s): Martin Günther
autogenerated on Sun Feb 14 2021 03:40:12