path_angle.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2019, DFKI GmbH
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include <mir_dwb_critics/path_angle.h>
00036 #include <pluginlib/class_list_macros.h>
00037 #include <nav_2d_utils/path_ops.h>
00038 #include <nav_grid/coordinate_conversion.h>
00039 #include <vector>
00040 
00041 namespace mir_dwb_critics {
00042 
00043 bool PathAngleCritic::prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel,
00044                               const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) {
00045   const nav_core2::Costmap &costmap = *costmap_;
00046   const nav_grid::NavGridInfo &info = costmap.getInfo();
00047   nav_2d_msgs::Path2D adjusted_global_plan = nav_2d_utils::adjustPlanResolution(global_plan, info.resolution);
00048 
00049   if (global_plan.poses.empty()) {
00050     ROS_ERROR_NAMED("PathAngleCritic", "The global plan was empty.");
00051     return false;
00052   }
00053 
00054   // find the angle of the plan at the pose on the plan closest to the robot
00055   double distance_min = std::numeric_limits<double>::infinity();
00056   bool started_path = false;
00057   for (unsigned int i = 0; i < adjusted_global_plan.poses.size(); i++) {
00058     double g_x = adjusted_global_plan.poses[i].x;
00059     double g_y = adjusted_global_plan.poses[i].y;
00060     unsigned int map_x, map_y;
00061     if (worldToGridBounded(info, g_x, g_y, map_x, map_y) && costmap(map_x, map_y) != costmap.NO_INFORMATION) {
00062       double distance = nav_2d_utils::poseDistance(adjusted_global_plan.poses[i], pose);
00063       if (distance_min > distance) {
00064         // still getting closer
00065         desired_angle_ = adjusted_global_plan.poses[i].theta;
00066         distance_min = distance;
00067         started_path = true;
00068       } else {
00069         // plan is going away from the robot again
00070         break;
00071       }
00072     } else if (started_path) {
00073       // Off the costmap after being on the costmap.
00074       break;
00075     }
00076     // else, we have not yet found a point on the costmap, so we just continue
00077   }
00078 
00079   if (!started_path) {
00080     ROS_ERROR_NAMED("PathAngleCritic", "None of the points of the global plan were in the local costmap.");
00081     return false;
00082   }
00083   return true;
00084 }
00085 
00086 double PathAngleCritic::scoreTrajectory(const dwb_msgs::Trajectory2D &traj) {
00087   double diff = fabs(remainder(traj.poses.back().theta - desired_angle_, 2 * M_PI));
00088   return diff * diff;
00089 }
00090 
00091 }  // namespace mir_dwb_critics
00092 
00093 PLUGINLIB_EXPORT_CLASS(mir_dwb_critics::PathAngleCritic, dwb_local_planner::TrajectoryCritic)


mir_dwb_critics
Author(s): Martin Günther
autogenerated on Wed May 8 2019 02:53:29