trajectory_planner_ros.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 
00038 #include <iri_diff_local_planner/trajectory_planner_ros.h>
00039 #include <ros/console.h>
00040 #include <sys/time.h>
00041 #include <pluginlib/class_list_macros.h>
00042 #include <boost/tokenizer.hpp>
00043 
00044 #include "geometry_msgs/PolygonStamped.h"
00045 #include "nav_msgs/Path.h"
00046 #include "iri_diff_local_planner/goal_functions.h"
00047 
00048 using namespace std;
00049 using namespace costmap_2d;
00050 
00051 //register this planner as a BaseLocalPlanner plugin
00052 PLUGINLIB_DECLARE_CLASS(iri_diff_local_planner, TrajectoryPlannerROS, iri_diff_local_planner::TrajectoryPlannerROS, nav_core::BaseLocalPlanner)
00053 
00054 namespace iri_diff_local_planner {
00055 
00056   void TrajectoryPlannerROS::reconfigureCB(IriDiffLocalPlannerConfig &config, uint32_t level) {
00057       if(setup_ && config.restore_defaults) {
00058         config = default_config_;
00059         //Avoid looping
00060         config.restore_defaults = false;
00061       }
00062       if(!setup_) {
00063         default_config_ = config;
00064         setup_ = true;
00065       }
00066       else if(setup_) {
00067         tc_->reconfigure(config);
00068       }
00069   }
00070 
00071   TrajectoryPlannerROS::TrajectoryPlannerROS() : world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), initialized_(false), setup_(false) {}
00072 
00073   TrajectoryPlannerROS::TrajectoryPlannerROS(std::string name, tf::TransformListener* tf, Costmap2DROS* costmap_ros) 
00074     : world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), initialized_(false), setup_(false) {
00075 
00076       //initialize the planner
00077       initialize(name, tf, costmap_ros);
00078   }
00079 
00080   void TrajectoryPlannerROS::initialize(std::string name, tf::TransformListener* tf, Costmap2DROS* costmap_ros){
00081     if(!initialized_){
00082       tf_ = tf;
00083       costmap_ros_ = costmap_ros;
00084       rot_stopped_velocity_ = 1e-2;
00085       trans_stopped_velocity_ = 1e-2;
00086       double sim_time, sim_granularity, angular_sim_granularity;
00087       int vx_samples, vtheta_samples;
00088       double pdist_scale, gdist_scale, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta;
00089       bool holonomic_robot, dwa, simple_attractor, heading_scoring;
00090       double heading_scoring_timestep;
00091       double min_vel_x;
00092       double backup_vel;
00093       double stop_time_buffer;
00094       string world_model_type;
00095       rotating_to_goal_ = false;
00096 
00097       //initialize the copy of the costmap the controller will use
00098       costmap_ros_->getCostmapCopy(costmap_);
00099 
00100       ros::NodeHandle private_nh("~/" + name);
00101       
00102       g_plan_pub_ = private_nh.advertise<nav_msgs::Path>("global_plan", 1);
00103       l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
00104 
00105       global_frame_ = costmap_ros_->getGlobalFrameID();
00106       robot_base_frame_ = costmap_ros_->getBaseFrameID();
00107       private_nh.param("prune_plan", prune_plan_, true);
00108 
00109       private_nh.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05);
00110       private_nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.10);
00111 
00112       //to get odometery information, we need to get a handle to the topic in the global namespace of the node
00113       ros::NodeHandle global_node;
00114       odom_sub_ = global_node.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&TrajectoryPlannerROS::odomCallback, this, _1));
00115 
00116       //we'll get the parameters for the robot radius from the costmap we're associated with
00117       inflation_radius_ = costmap_ros_->getInflationRadius();
00118 
00119       private_nh.param("acc_lim_x", acc_lim_x_, 2.5);
00120       private_nh.param("acc_lim_y", acc_lim_y_, 2.5);
00121       private_nh.param("acc_lim_th", acc_lim_theta_, 3.2);
00122 
00123       private_nh.param("stop_time_buffer", stop_time_buffer, 0.2);
00124 
00125       private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false);
00126 
00127       //Since I screwed up nicely in my documentation, I'm going to add errors
00128       //informing the user if they've set one of the wrong parameters
00129       if(private_nh.hasParam("acc_limit_x"))
00130         ROS_ERROR("You are using acc_limit_x where you should be using acc_lim_x. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
00131 
00132       if(private_nh.hasParam("acc_limit_y"))
00133         ROS_ERROR("You are using acc_limit_y where you should be using acc_lim_y. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
00134 
00135       if(private_nh.hasParam("acc_limit_th"))
00136         ROS_ERROR("You are using acc_limit_th where you should be using acc_lim_th. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
00137 
00138       //Assuming this planner is being run within the navigation stack, we can
00139       //just do an upward search for the frequency at which its being run. This
00140       //also allows the frequency to be overwritten locally.
00141       std::string controller_frequency_param_name;
00142       if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name))
00143         sim_period_ = 0.05;
00144       else
00145       {
00146         double controller_frequency = 0;
00147         private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
00148         if(controller_frequency > 0)
00149           sim_period_ = 1.0 / controller_frequency;
00150         else
00151         {
00152           ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
00153           sim_period_ = 0.05;
00154         }
00155       }
00156       ROS_INFO("Sim period is set to %.2f", sim_period_);
00157 
00158       private_nh.param("sim_time", sim_time, 1.0);
00159       private_nh.param("sim_granularity", sim_granularity, 0.025);
00160       private_nh.param("angular_sim_granularity", angular_sim_granularity, sim_granularity);
00161       private_nh.param("vx_samples", vx_samples, 3);
00162       private_nh.param("vtheta_samples", vtheta_samples, 20);
00163 
00164       private_nh.param("path_distance_bias", pdist_scale, 0.6);
00165       private_nh.param("goal_distance_bias", gdist_scale, 0.8);
00166 
00167       bool meter_scoring;
00168       private_nh.param("meter_scoring", meter_scoring, false);
00169 
00170       if(meter_scoring)
00171       {
00172         //if we use meter scoring, then we want to multiply the biases by the resolution of the costmap
00173         double resolution = costmap_ros_->getResolution();
00174         gdist_scale *= resolution;
00175         pdist_scale *= resolution;
00176       }
00177 
00178       private_nh.param("occdist_scale", occdist_scale, 0.01);
00179       private_nh.param("heading_lookahead", heading_lookahead, 0.325);
00180       private_nh.param("oscillation_reset_dist", oscillation_reset_dist, 0.05);
00181       private_nh.param("escape_reset_dist", escape_reset_dist, 0.10);
00182       private_nh.param("escape_reset_theta", escape_reset_theta, M_PI_4);
00183       private_nh.param("holonomic_robot", holonomic_robot, true);
00184       private_nh.param("max_vel_x", this->max_vel_x_, 0.5);
00185       private_nh.param("min_vel_x", min_vel_x, 0.1);
00186 
00187       double max_rotational_vel;
00188       private_nh.param("max_rotational_vel", max_rotational_vel, 1.0);
00189       max_vel_th_ = max_rotational_vel;
00190       min_vel_th_ = -1.0 * max_rotational_vel;
00191       private_nh.param("min_in_place_rotational_vel", min_in_place_vel_th_, 0.4);
00192 
00193       backup_vel = -0.1;
00194       if(private_nh.getParam("backup_vel", backup_vel))
00195         ROS_WARN("The backup_vel parameter has been deprecated in favor of the escape_vel parameter. To switch, just change the parameter name in your configuration files.");
00196 
00197       //if both backup_vel and escape_vel are set... we'll use escape_vel
00198       private_nh.getParam("escape_vel", backup_vel);
00199 
00200       if(backup_vel >= 0.0)
00201         ROS_WARN("You've specified a positive escape velocity. This is probably not what you want and will cause the robot to move forward instead of backward. You should probably change your escape_vel parameter to be negative");
00202 
00203       private_nh.param("world_model", world_model_type, string("costmap")); 
00204       private_nh.param("dwa", dwa, true);
00205       private_nh.param("heading_scoring", heading_scoring, false);
00206       private_nh.param("heading_scoring_timestep", heading_scoring_timestep, 0.8);
00207 
00208       simple_attractor = false;
00209 
00210       //parameters for using the freespace controller
00211       double min_pt_separation, max_obstacle_height, grid_resolution;
00212       private_nh.param("point_grid/max_sensor_range", max_sensor_range_, 2.0);
00213       private_nh.param("point_grid/min_pt_separation", min_pt_separation, 0.01);
00214       private_nh.param("point_grid/max_obstacle_height", max_obstacle_height, 2.0);
00215       private_nh.param("point_grid/grid_resolution", grid_resolution, 0.2);
00216 
00217       ROS_ASSERT_MSG(world_model_type == "costmap", "At this time, only costmap world models are supported by this controller");
00218       world_model_ = new CostmapModel(costmap_);
00219       std::vector<double> y_vels = loadYVels(private_nh);
00220 
00221       tc_ = new TrajectoryPlanner(*world_model_, costmap_, costmap_ros_->getRobotFootprint(),
00222           acc_lim_x_, acc_lim_y_, acc_lim_theta_, sim_time, sim_granularity, vx_samples, vtheta_samples, pdist_scale,
00223           gdist_scale, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta, holonomic_robot,
00224           &this->max_vel_x_, min_vel_x, max_vel_th_, min_vel_th_, min_in_place_vel_th_, backup_vel,
00225           dwa, heading_scoring, heading_scoring_timestep, simple_attractor, y_vels, stop_time_buffer, sim_period_, angular_sim_granularity);
00226 
00227       map_viz_.initialize(name, &costmap_, boost::bind(&TrajectoryPlanner::getCellCosts, tc_, _1, _2, _3, _4, _5, _6));
00228       initialized_ = true;
00229 
00230       dsrv_ = new dynamic_reconfigure::Server<IriDiffLocalPlannerConfig>(private_nh);
00231       dynamic_reconfigure::Server<IriDiffLocalPlannerConfig>::CallbackType cb = boost::bind(&TrajectoryPlannerROS::reconfigureCB, this, _1, _2);
00232       dsrv_->setCallback(cb);
00233 
00234       change_max_vel=global_node.advertiseService("change_max_vel",&TrajectoryPlannerROS::change_max_velCallback,this);
00235     }
00236     else
00237       ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing");
00238   }
00239 
00240   bool TrajectoryPlannerROS::change_max_velCallback(iri_diff_local_planner::change_max_vel::Request &req,iri_diff_local_planner::change_max_vel::Response &res)
00241   {
00242     this->max_vel_x_=req.new_max_vel;
00243 
00244     return true;
00245   }
00246 
00247   std::vector<double> TrajectoryPlannerROS::loadYVels(ros::NodeHandle node){
00248     std::vector<double> y_vels;
00249 
00250     std::string y_vel_list;
00251     if(node.getParam("y_vels", y_vel_list)){
00252       typedef boost::tokenizer<boost::char_separator<char> > tokenizer;
00253       boost::char_separator<char> sep("[], ");
00254       tokenizer tokens(y_vel_list, sep);
00255 
00256       for(tokenizer::iterator i = tokens.begin(); i != tokens.end(); i++){
00257         y_vels.push_back(atof((*i).c_str()));
00258       }
00259     }
00260     else{
00261       //if no values are passed in, we'll provide defaults
00262       y_vels.push_back(-0.3);
00263       y_vels.push_back(-0.1);
00264       y_vels.push_back(0.1);
00265       y_vels.push_back(0.3);
00266     }
00267 
00268     return y_vels;
00269   }
00270 
00271   TrajectoryPlannerROS::~TrajectoryPlannerROS(){
00272     //make sure to clean things up
00273     delete dsrv_;
00274 
00275     if(tc_ != NULL)
00276       delete tc_;
00277 
00278     if(world_model_ != NULL)
00279       delete world_model_;
00280   }
00281 
00282   bool TrajectoryPlannerROS::stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, geometry_msgs::Twist& cmd_vel){
00283     //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible
00284     //but we'll use a tenth of a second to be consistent with the implementation of the local planner.
00285     double vx = sign(robot_vel.getOrigin().x()) * std::max(0.0, (fabs(robot_vel.getOrigin().x()) - acc_lim_x_ * sim_period_));
00286     double vy = sign(robot_vel.getOrigin().y()) * std::max(0.0, (fabs(robot_vel.getOrigin().y()) - acc_lim_y_ * sim_period_));
00287 
00288     double vel_yaw = tf::getYaw(robot_vel.getRotation());
00289     double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim_theta_ * sim_period_));
00290 
00291     //we do want to check whether or not the command is valid
00292     double yaw = tf::getYaw(global_pose.getRotation());
00293     bool valid_cmd = tc_->checkTrajectory(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw, 
00294         robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw, vx, vy, vth);
00295 
00296     //if we have a valid command, we'll pass it on, otherwise we'll command all zeros
00297     if(valid_cmd){
00298       ROS_DEBUG("Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth);
00299       cmd_vel.linear.x = vx;
00300       cmd_vel.linear.y = vy;
00301       cmd_vel.angular.z = vth;
00302       return true;
00303     }
00304 
00305     cmd_vel.linear.x = 0.0;
00306     cmd_vel.linear.y = 0.0;
00307     cmd_vel.angular.z = 0.0;
00308     return false;
00309   }
00310 
00311   bool TrajectoryPlannerROS::rotateToGoal(const tf::Stamped<tf::Pose>& global_pose, const tf::Stamped<tf::Pose>& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel){
00312     double yaw = tf::getYaw(global_pose.getRotation());
00313     double vel_yaw = tf::getYaw(robot_vel.getRotation());
00314     cmd_vel.linear.x = 0;
00315     cmd_vel.linear.y = 0;
00316     double ang_diff = angles::shortest_angular_distance(yaw, goal_th);
00317 
00318     double v_theta_samp = ang_diff > 0.0 ? std::min(max_vel_th_,
00319         std::max(min_in_place_vel_th_, ang_diff)) : std::max(min_vel_th_,
00320         std::min(-1.0 * min_in_place_vel_th_, ang_diff));
00321 
00322     //take the acceleration limits of the robot into account
00323 //    double max_acc_vel = fabs(vel_yaw) + acc_lim_theta_ * sim_period_;
00324 //    double min_acc_vel = fabs(vel_yaw) - acc_lim_theta_ * sim_period_;
00325 
00326 //    v_theta_samp = sign(v_theta_samp) * std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
00327 
00328     //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits
00329 //    double max_speed_to_stop = sqrt(2 * acc_lim_theta_ * fabs(ang_diff)); 
00330 
00331 //    v_theta_samp = sign(v_theta_samp) * std::min(max_speed_to_stop, fabs(v_theta_samp));
00332 
00333     //we still want to lay down the footprint of the robot and check if the action is legal
00334     bool valid_cmd = tc_->checkTrajectory(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw, 
00335         robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw, 0.0, 0.0, v_theta_samp);
00336 
00337     ROS_DEBUG("Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd);
00338 
00339     if(valid_cmd){
00340       cmd_vel.angular.z = v_theta_samp;
00341       return true;
00342     }
00343 
00344     cmd_vel.angular.z = 0.0;
00345     return false;
00346 
00347   }
00348 
00349   void TrajectoryPlannerROS::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){
00350     //we assume that the odometry is published in the frame of the base
00351     boost::recursive_mutex::scoped_lock lock(odom_lock_);
00352     base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
00353     base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
00354     base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
00355     ROS_DEBUG("In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
00356         base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
00357   }
00358 
00359   bool TrajectoryPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan){
00360     if(!initialized_){
00361       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00362       return false;
00363     }
00364 
00365     //reset the global plan
00366     global_plan_.clear();
00367     global_plan_ = orig_global_plan;
00368 
00369     //when we get a new plan, we also want to clear any latch we may have on goal tolerances
00370     xy_tolerance_latch_ = false;
00371     rotating_to_goal_ = false;
00372 
00373     return true;
00374   }
00375 
00376   bool TrajectoryPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
00377     if(!initialized_){
00378       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00379       return false;
00380     }
00381 
00382     std::vector<geometry_msgs::PoseStamped> local_plan;
00383     tf::Stamped<tf::Pose> global_pose;
00384     if(!costmap_ros_->getRobotPose(global_pose))
00385       return false;
00386 
00387     std::vector<geometry_msgs::PoseStamped> transformed_plan;
00388     //get the global plan in our frame
00389     if(!transformGlobalPlan(*tf_, global_plan_, *costmap_ros_, global_frame_, transformed_plan)){
00390       ROS_WARN("Could not transform the global plan to the frame of the controller");
00391       return false;
00392     }
00393 
00394     //now we'll prune the plan based on the position of the robot
00395     if(prune_plan_)
00396       prunePlan(global_pose, transformed_plan, global_plan_);
00397 
00398 
00399     //we also want to clear the robot footprint from the costmap we're using
00400     costmap_ros_->clearRobotFootprint();
00401 
00402     //make sure to update the costmap we'll use for this cycle
00403     costmap_ros_->getCostmapCopy(costmap_);
00404 
00405     // Set current velocities from odometry
00406     geometry_msgs::Twist global_vel;
00407 
00408     odom_lock_.lock();
00409     global_vel.linear.x = base_odom_.twist.twist.linear.x;
00410     global_vel.linear.y = base_odom_.twist.twist.linear.y;
00411     global_vel.angular.z = base_odom_.twist.twist.angular.z;
00412     odom_lock_.unlock();
00413 
00414     tf::Stamped<tf::Pose> drive_cmds;
00415     drive_cmds.frame_id_ = robot_base_frame_;
00416 
00417     tf::Stamped<tf::Pose> robot_vel;
00418     robot_vel.setData(tf::Transform(tf::createQuaternionFromYaw(global_vel.angular.z), tf::Vector3(global_vel.linear.x, global_vel.linear.y, 0)));
00419     robot_vel.frame_id_ = robot_base_frame_;
00420     robot_vel.stamp_ = ros::Time();
00421 
00422     /* For timing uncomment
00423     struct timeval start, end;
00424     double start_t, end_t, t_diff;
00425     gettimeofday(&start, NULL);
00426     */
00427 
00428     //if the global plan passed in is empty... we won't do anything
00429     if(transformed_plan.empty())
00430       return false;
00431 
00432     tf::Stamped<tf::Pose> goal_point;
00433     tf::poseStampedMsgToTF(transformed_plan.back(), goal_point);
00434     //we assume the global goal is the last point in the global plan
00435     double goal_x = goal_point.getOrigin().getX();
00436     double goal_y = goal_point.getOrigin().getY();
00437 
00438     double yaw = tf::getYaw(goal_point.getRotation());
00439 
00440     double goal_th = yaw;
00441 
00442     //check to see if we've reached the goal position
00443     if(goalPositionReached(global_pose, goal_x, goal_y, xy_goal_tolerance_) || xy_tolerance_latch_){
00444 
00445       //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll
00446       //just rotate in place
00447       if(latch_xy_goal_tolerance_)
00448         xy_tolerance_latch_ = true;
00449 
00450       //check to see if the goal orientation has been reached
00451       if(goalOrientationReached(global_pose, goal_th, yaw_goal_tolerance_)){
00452         //set the velocity command to zero
00453         cmd_vel.linear.x = 0.0;
00454         cmd_vel.linear.y = 0.0;
00455         cmd_vel.angular.z = 0.0;
00456         //rotating_to_goal_ = false;
00457         //xy_tolerance_latch_ = false;
00458       }
00459       else {
00460         //we need to call the next two lines to make sure that the trajectory
00461         //planner updates its path distance and goal distance grids
00462         tc_->updatePlan(transformed_plan);
00463         Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds);
00464         map_viz_.publishCostCloud();
00465 
00466         //copy over the odometry information
00467         nav_msgs::Odometry base_odom;
00468         {
00469           boost::recursive_mutex::scoped_lock lock(odom_lock_);
00470           base_odom = base_odom_;
00471         }
00472 
00473         //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot
00474         if(!rotating_to_goal_ && !iri_diff_local_planner::stopped(base_odom, rot_stopped_velocity_, trans_stopped_velocity_)){
00475           if(!stopWithAccLimits(global_pose, robot_vel, cmd_vel))
00476             return false;
00477         }
00478         //if we're stopped... then we want to rotate to goal
00479         else{
00480           //set this so that we know its OK to be moving
00481           rotating_to_goal_ = true;
00482           if(!rotateToGoal(global_pose, robot_vel, goal_th, cmd_vel))
00483             return false;
00484         }
00485       }
00486 
00487       //publish an empty plan because we've reached our goal position
00488       publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0);
00489       publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0);
00490 
00491       //we don't actually want to run the controller when we're just rotating to goal
00492       return true;
00493     }
00494 
00495     tc_->updatePlan(transformed_plan);
00496 
00497     //compute what trajectory to drive along
00498     Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds);
00499 
00500     map_viz_.publishCostCloud();
00501     /* For timing uncomment
00502     gettimeofday(&end, NULL);
00503     start_t = start.tv_sec + double(start.tv_usec) / 1e6;
00504     end_t = end.tv_sec + double(end.tv_usec) / 1e6;
00505     t_diff = end_t - start_t;
00506     ROS_INFO("Cycle time: %.9f", t_diff);
00507     */
00508 
00509     //pass along drive commands
00510     cmd_vel.linear.x = drive_cmds.getOrigin().getX();
00511     cmd_vel.linear.y = drive_cmds.getOrigin().getY();
00512     yaw = tf::getYaw(drive_cmds.getRotation());
00513 
00514     cmd_vel.angular.z = yaw;
00515 
00516     //if we cannot move... tell someone
00517     if(path.cost_ < 0){
00518       local_plan.clear();
00519       publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0);
00520       publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0);
00521       return false;
00522     }
00523 
00524     // Fill out the local plan
00525     for(unsigned int i = 0; i < path.getPointsSize(); ++i){
00526       double p_x, p_y, p_th;
00527       path.getPoint(i, p_x, p_y, p_th);
00528 
00529       tf::Stamped<tf::Pose> p = tf::Stamped<tf::Pose>(tf::Pose(tf::createQuaternionFromYaw(p_th), tf::Point(p_x, p_y, 0.0)), ros::Time::now(), global_frame_);
00530       geometry_msgs::PoseStamped pose;
00531       tf::poseStampedTFToMsg(p, pose);
00532       local_plan.push_back(pose);
00533     }
00534 
00535     //publish information to the visualizer
00536     publishPlan(transformed_plan, g_plan_pub_, 0.0, 1.0, 0.0, 0.0);
00537     publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0);
00538     return true;
00539   }
00540 
00541   bool TrajectoryPlannerROS::checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){
00542     tf::Stamped<tf::Pose> global_pose;
00543     if(costmap_ros_->getRobotPose(global_pose)){
00544       if(update_map){
00545         //we also want to clear the robot footprint from the costmap we're using
00546         costmap_ros_->clearRobotFootprint();
00547 
00548         //make sure to update the costmap we'll use for this cycle
00549         costmap_ros_->getCostmapCopy(costmap_);
00550 
00551         //we need to give the planne some sort of global plan, since we're only checking for legality
00552         //we'll just give the robots current position
00553         std::vector<geometry_msgs::PoseStamped> plan;
00554         geometry_msgs::PoseStamped pose_msg;
00555         tf::poseStampedTFToMsg(global_pose, pose_msg);
00556         plan.push_back(pose_msg);
00557         tc_->updatePlan(plan, true);
00558       }
00559 
00560       //copy over the odometry information
00561       nav_msgs::Odometry base_odom;
00562       {
00563         boost::recursive_mutex::scoped_lock lock(odom_lock_);
00564         base_odom = base_odom_;
00565       }
00566 
00567       return tc_->checkTrajectory(global_pose.getOrigin().x(), global_pose.getOrigin().y(), tf::getYaw(global_pose.getRotation()),
00568           base_odom.twist.twist.linear.x,
00569           base_odom.twist.twist.linear.y,
00570           base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp);
00571 
00572     }
00573     ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
00574     return false;
00575   }
00576 
00577 
00578   double TrajectoryPlannerROS::scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){
00579     // Copy of checkTrajectory that returns a score instead of True / False
00580     tf::Stamped<tf::Pose> global_pose;
00581     if(costmap_ros_->getRobotPose(global_pose)){
00582       if(update_map){
00583         //we also want to clear the robot footprint from the costmap we're using
00584         costmap_ros_->clearRobotFootprint();
00585 
00586         //make sure to update the costmap we'll use for this cycle
00587         costmap_ros_->getCostmapCopy(costmap_);
00588 
00589         //we need to give the planne some sort of global plan, since we're only checking for legality
00590         //we'll just give the robots current position
00591         std::vector<geometry_msgs::PoseStamped> plan;
00592         geometry_msgs::PoseStamped pose_msg;
00593         tf::poseStampedTFToMsg(global_pose, pose_msg);
00594         plan.push_back(pose_msg);
00595         tc_->updatePlan(plan, true);
00596       }
00597 
00598       //copy over the odometry information
00599       nav_msgs::Odometry base_odom;
00600       {
00601         boost::recursive_mutex::scoped_lock lock(odom_lock_);
00602         base_odom = base_odom_;
00603       }
00604 
00605       return tc_->scoreTrajectory(global_pose.getOrigin().x(), global_pose.getOrigin().y(), tf::getYaw(global_pose.getRotation()),
00606           base_odom.twist.twist.linear.x,
00607           base_odom.twist.twist.linear.y,
00608           base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp);
00609 
00610     }
00611     ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
00612     return -1.0;
00613   }
00614 
00615   bool TrajectoryPlannerROS::isGoalReached(){
00616     if(!initialized_){
00617       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00618       return false;
00619     }
00620 
00621     //copy over the odometry information
00622     nav_msgs::Odometry base_odom;
00623     {
00624       boost::recursive_mutex::scoped_lock lock(odom_lock_);
00625       base_odom = base_odom_;
00626     }
00627 
00628     return iri_diff_local_planner::isGoalReached(*tf_, global_plan_, *costmap_ros_, global_frame_, base_odom, 
00629         rot_stopped_velocity_, trans_stopped_velocity_, xy_goal_tolerance_, yaw_goal_tolerance_,xy_tolerance_latch_);
00630   }
00631 };


iri_diff_local_planner
Author(s): Iri Lab
autogenerated on Fri Dec 6 2013 20:32:36