rotate_to_goal.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
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 #include <dwb_critics/rotate_to_goal.h>
00035 #include <dwb_local_planner/trajectory_utils.h>
00036 #include <nav_2d_utils/parameters.h>
00037 #include <nav_core2/exceptions.h>
00038 #include <pluginlib/class_list_macros.h>
00039 #include <angles/angles.h>
00040 #include <string>
00041 #include <vector>
00042 
00043 const double EPSILON = 1E-5;
00044 
00045 PLUGINLIB_EXPORT_CLASS(dwb_critics::RotateToGoalCritic, dwb_local_planner::TrajectoryCritic)
00046 
00047 namespace dwb_critics
00048 {
00049 
00050 inline double hypot_sq(double dx, double dy)
00051 {
00052   return dx * dx + dy * dy;
00053 }
00054 
00055 void RotateToGoalCritic::onInit()
00056 {
00057   xy_goal_tolerance_ = nav_2d_utils::searchAndGetParam(critic_nh_, "xy_goal_tolerance", 0.25);
00058   xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
00059   double stopped_xy_velocity = nav_2d_utils::searchAndGetParam(critic_nh_, "trans_stopped_velocity", 0.25);
00060   stopped_xy_velocity_sq_ = stopped_xy_velocity * stopped_xy_velocity;
00061   critic_nh_.param("slowing_factor", slowing_factor_, 5.0);
00062   critic_nh_.param("lookahead_time", lookahead_time_, -1.0);
00063   reset();
00064 }
00065 
00066 void RotateToGoalCritic::reset()
00067 {
00068   in_window_ = false;
00069   rotating_ = false;
00070 }
00071 
00072 bool RotateToGoalCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
00073                                  const geometry_msgs::Pose2D& goal,
00074                                  const nav_2d_msgs::Path2D& global_plan)
00075 {
00076   double dxy_sq = hypot_sq(pose.x - goal.x, pose.y - goal.y);
00077   in_window_ = in_window_ || dxy_sq <= xy_goal_tolerance_sq_;
00078   current_xy_speed_sq_ = hypot_sq(vel.x, vel.y);
00079   rotating_ = rotating_ || (in_window_ && current_xy_speed_sq_ <= stopped_xy_velocity_sq_);
00080   goal_yaw_ = goal.theta;
00081   return true;
00082 }
00083 
00084 double RotateToGoalCritic::scoreTrajectory(const dwb_msgs::Trajectory2D& traj)
00085 {
00086   // If we're not sufficiently close to the goal, we don't care what the twist is
00087   if (!in_window_)
00088   {
00089     return 0.0;
00090   }
00091   else if (!rotating_)
00092   {
00093     double speed_sq = hypot_sq(traj.velocity.x, traj.velocity.y);
00094     if (speed_sq >= current_xy_speed_sq_)
00095     {
00096       throw nav_core2::IllegalTrajectoryException(name_, "Not slowing down near goal.");
00097     }
00098     return speed_sq * slowing_factor_ + scoreRotation(traj);
00099   }
00100 
00101   // If we're sufficiently close to the goal, any transforming velocity is invalid
00102   if (fabs(traj.velocity.x) > EPSILON || fabs(traj.velocity.y) > EPSILON)
00103   {
00104     throw nav_core2::IllegalTrajectoryException(name_, "Nonrotation command near goal.");
00105   }
00106 
00107   return scoreRotation(traj);
00108 }
00109 
00110 double RotateToGoalCritic::scoreRotation(const dwb_msgs::Trajectory2D& traj)
00111 {
00112   if (traj.poses.empty())
00113   {
00114     throw nav_core2::IllegalTrajectoryException(name_, "Empty trajectory.");
00115   }
00116 
00117   double end_yaw;
00118   if (lookahead_time_ >= 0.0)
00119   {
00120     geometry_msgs::Pose2D eval_pose = dwb_local_planner::projectPose(traj, lookahead_time_);
00121     end_yaw = eval_pose.theta;
00122   }
00123   else
00124   {
00125     end_yaw = traj.poses.back().theta;
00126   }
00127   return fabs(angles::shortest_angular_distance(end_yaw, goal_yaw_));
00128 }
00129 
00130 } /* namespace dwb_critics */


dwb_critics
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:09:47