Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 #include <dwb_critics/path_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 PathAlignCritic::onInit()
00045 {
00046   PathDistCritic::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 PathAlignCritic::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   double dx = pose.x - goal.x;
00056   double dy = pose.y - goal.y;
00057   double sq_dist = dx * dx + dy * dy;
00058   if (sq_dist > forward_point_distance_ * forward_point_distance_)
00059   {
00060     zero_scale_ = false;
00061   }
00062   else
00063   {
00064     
00065     zero_scale_ = true;
00066     return true;
00067   }
00068 
00069   return PathDistCritic::prepare(pose, vel, goal, global_plan);
00070 }
00071 
00072 double PathAlignCritic::getScale() const
00073 {
00074   if (zero_scale_)
00075     return 0.0;
00076   else
00077     return costmap_->getResolution() * 0.5 * scale_;
00078 }
00079 
00080 double PathAlignCritic::scorePose(const geometry_msgs::Pose2D& pose)
00081 {
00082   return PathDistCritic::scorePose(getForwardPose(pose, forward_point_distance_));
00083 }
00084 
00085 }  
00086 
00087 PLUGINLIB_EXPORT_CLASS(dwb_critics::PathAlignCritic, dwb_local_planner::TrajectoryCritic)