goal_align.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/goal_align.h>
00035 #include <dwb_critics/alignment_util.h>
00036 #include <pluginlib/class_list_macros.h>
00037 #include <nav_2d_utils/parameters.h>
00038 #include <vector>
00039 #include <string>
00040 
00041 namespace dwb_critics
00042 {
00043 
00044 void GoalAlignCritic::onInit()
00045 {
00046   GoalDistCritic::onInit();
00047   stop_on_failure_ = false;
00048   forward_point_distance_ = nav_2d_utils::searchAndGetParam(critic_nh_, "forward_point_distance", 0.325);
00049 }
00050 
00051 bool GoalAlignCritic::prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
00052                               const geometry_msgs::Pose2D& goal,
00053                               const nav_2d_msgs::Path2D& global_plan)
00054 {
00055   // we want the robot nose to be drawn to its final position
00056   // (before robot turns towards goal orientation), not the end of the
00057   // path for the robot center. Choosing the final position after
00058   // turning towards goal orientation causes instability when the
00059   // robot needs to make a 180 degree turn at the end
00060   double angle_to_goal = atan2(goal.y - pose.y, goal.x - pose.x);
00061 
00062   nav_2d_msgs::Path2D target_poses = global_plan;
00063   target_poses.poses.back().x += forward_point_distance_ * cos(angle_to_goal);
00064   target_poses.poses.back().y += forward_point_distance_ * sin(angle_to_goal);
00065 
00066   return GoalDistCritic::prepare(pose, vel, goal, target_poses);
00067 }
00068 
00069 double GoalAlignCritic::scorePose(const geometry_msgs::Pose2D& pose)
00070 {
00071   return GoalDistCritic::scorePose(getForwardPose(pose, forward_point_distance_));
00072 }
00073 
00074 }  // namespace dwb_critics
00075 
00076 PLUGINLIB_EXPORT_CLASS(dwb_critics::GoalAlignCritic, dwb_local_planner::TrajectoryCritic)


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