eband_local_planner_ros.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2010, 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 Willow Garage, Inc. 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: Christian Connette
00036  *********************************************************************/
00037 
00038 #include <eband_local_planner/eband_local_planner_ros.h>
00039 
00040 // pluginlib macros (defines, ...)
00041 #include <pluginlib/class_list_macros.h>
00042 
00043 // abstract class from which our plugin inherits
00044 #include <nav_core/base_local_planner.h>
00045 
00046 
00047 // register this planner as a BaseGlobalPlanner plugin
00048 // (see http://www.ros.org/wiki/pluginlib/Tutorials/Writing%20and%20Using%20a%20Simple%20Plugin)
00049 PLUGINLIB_DECLARE_CLASS(eband_local_planner, EBandPlannerROS, eband_local_planner::EBandPlannerROS, nav_core::BaseLocalPlanner)
00050 
00051 
00052   namespace eband_local_planner{
00053 
00054     EBandPlannerROS::EBandPlannerROS() : costmap_ros_(NULL), tf_(NULL), initialized_(false) {}
00055 
00056 
00057     EBandPlannerROS::EBandPlannerROS(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
00058       : costmap_ros_(NULL), tf_(NULL), initialized_(false)
00059     {
00060       // initialize planner
00061       initialize(name, tf, costmap_ros);
00062     }
00063 
00064 
00065     EBandPlannerROS::~EBandPlannerROS() {}
00066 
00067 
00068     void EBandPlannerROS::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
00069     {
00070       // check if the plugin is already initialized
00071       if(!initialized_)
00072       {
00073         // copy adress of costmap and Transform Listener (handed over from move_base)
00074         costmap_ros_ = costmap_ros;
00075         tf_ = tf;
00076 
00077 
00078         // create Node Handle with name of plugin (as used in move_base for loading)
00079         ros::NodeHandle pn("~/" + name);
00080 
00081         // read parameters from parameter server
00082         // get tolerances for "Target reached"
00083         pn.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05);
00084         pn.param("xy_goal_tolerance", xy_goal_tolerance_, 0.1);
00085 
00086         // set lower bound for velocity -> if velocity in this region stop! (to avoid limit-cycles or lock)
00087         pn.param("rot_stopped_vel", rot_stopped_vel_, 1e-2);
00088         pn.param("trans_stopped_vel", trans_stopped_vel_, 1e-2);
00089 
00090         // advertise topics (adapted global plan and predicted local trajectory)
00091         g_plan_pub_ = pn.advertise<nav_msgs::Path>("global_plan", 1);
00092         l_plan_pub_ = pn.advertise<nav_msgs::Path>("local_plan", 1);
00093 
00094 
00095         // subscribe to topics (to get odometry information, we need to get a handle to the topic in the global namespace)
00096         ros::NodeHandle gn;
00097         odom_sub_ = gn.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&EBandPlannerROS::odomCallback, this, _1));
00098 
00099 
00100         // create the actual planner that we'll use. Pass Name of plugin and pointer to global costmap to it.
00101         // (configuration is done via parameter server)
00102         eband_ = boost::shared_ptr<EBandPlanner>(new EBandPlanner(name, costmap_ros_));
00103 
00104         // create the according controller
00105         eband_trj_ctrl_ = boost::shared_ptr<EBandTrajectoryCtrl>(new EBandTrajectoryCtrl(name, costmap_ros_));
00106 
00107         // create object for visualization
00108         eband_visual_ = boost::shared_ptr<EBandVisualization>(new EBandVisualization);
00109 
00110         // pass visualization object to elastic band
00111         eband_->setVisualization(eband_visual_);
00112 
00113         // pass visualization object to controller
00114         eband_trj_ctrl_->setVisualization(eband_visual_);
00115 
00116         // initialize visualization - set node handle and pointer to costmap
00117         eband_visual_->initialize(pn, costmap_ros);
00118 
00119 
00120         // set initialized flag
00121         initialized_ = true;
00122 
00123         // this is only here to make this process visible in the rxlogger right from the start
00124         ROS_DEBUG("Elastic Band plugin initialized.");
00125       }
00126       else
00127       {
00128         ROS_WARN("This planner has already been initialized, doing nothing.");
00129       }
00130     }
00131 
00132 
00133     // set global plan to wrapper and pass it to eband
00134     bool EBandPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
00135     {
00136 
00137       // check if plugin initialized
00138       if(!initialized_)
00139       {
00140         ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00141         return false;
00142       }
00143 
00144       //reset the global plan
00145       global_plan_.clear();
00146       global_plan_ = orig_global_plan;
00147 
00148       // transform global plan to the map frame we are working in
00149       // this also cuts the plan off (reduces it to local window)
00150       std::vector<int> start_end_counts (2, (int) global_plan_.size()); // counts from the end() of the plan
00151       if(!eband_local_planner::transformGlobalPlan(*tf_, global_plan_, *costmap_ros_, costmap_ros_->getGlobalFrameID(), transformed_plan_, start_end_counts))
00152       {
00153         // if plan could not be tranformed abort control and local planning
00154         ROS_WARN("Could not transform the global plan to the frame of the controller");
00155         return false;
00156       }
00157 
00158       // also check if there really is a plan
00159       if(transformed_plan_.empty())
00160       {
00161         // if global plan passed in is empty... we won't do anything
00162         ROS_WARN("Transformed plan is empty. Aborting local planner!");
00163         return false;
00164       }
00165 
00166       // set plan - as this is fresh from the global planner robot pose should be identical to start frame
00167       if(!eband_->setPlan(transformed_plan_))
00168       {
00169         // We've had some difficulty where the global planner keeps returning a valid path that runs through an obstacle
00170         // in the local costmap. See issue #5. Here we clear the local costmap and try one more time.
00171         costmap_ros_->resetLayers();
00172         if (!eband_->setPlan(transformed_plan_)) {
00173           ROS_ERROR("Setting plan to Elastic Band method failed!");
00174           return false;
00175         }
00176       }
00177       ROS_DEBUG("Global plan set to elastic band for optimization");
00178 
00179       // plan transformed and set to elastic band successfully - set counters to global variable
00180       plan_start_end_counter_ = start_end_counts;
00181 
00182       // let eband refine the plan before starting continuous operation (to smooth sampling based plans)
00183       eband_->optimizeBand();
00184 
00185 
00186       // display result
00187       std::vector<eband_local_planner::Bubble> current_band;
00188       if(eband_->getBand(current_band))
00189         eband_visual_->publishBand("bubbles", current_band);
00190 
00191       // set goal as not reached
00192       goal_reached_ = false;
00193 
00194       return true;
00195     }
00196 
00197 
00198     bool EBandPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
00199     {
00200       // check if plugin initialized
00201       if(!initialized_)
00202       {
00203         ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00204         return false;
00205       }
00206 
00207       // instantiate local variables
00208       //std::vector<geometry_msgs::PoseStamped> local_plan;
00209       tf::Stamped<tf::Pose> global_pose;
00210       geometry_msgs::PoseStamped global_pose_msg;
00211       std::vector<geometry_msgs::PoseStamped> tmp_plan;
00212 
00213       // get curent robot position
00214       ROS_DEBUG("Reading current robot Position from costmap and appending it to elastic band.");
00215       if(!costmap_ros_->getRobotPose(global_pose))
00216       {
00217         ROS_WARN("Could not retrieve up to date robot pose from costmap for local planning.");
00218         return false;
00219       }
00220 
00221       // convert robot pose to frame in plan and set position in band at which to append
00222       tf::poseStampedTFToMsg(global_pose, global_pose_msg);
00223       tmp_plan.assign(1, global_pose_msg);
00224       eband_local_planner::AddAtPosition add_frames_at = add_front;
00225 
00226       // set it to elastic band and let eband connect it
00227       if(!eband_->addFrames(tmp_plan, add_frames_at))
00228       {
00229         ROS_WARN("Could not connect robot pose to existing elastic band.");
00230         return false;
00231       }
00232 
00233       // get additional path-frames which are now in moving window
00234       ROS_DEBUG("Checking for new path frames in moving window");
00235       std::vector<int> plan_start_end_counter = plan_start_end_counter_;
00236       std::vector<geometry_msgs::PoseStamped> append_transformed_plan;
00237       // transform global plan to the map frame we are working in - careful this also cuts the plan off (reduces it to local window)
00238       if(!eband_local_planner::transformGlobalPlan(*tf_, global_plan_, *costmap_ros_, costmap_ros_->getGlobalFrameID(), transformed_plan_, plan_start_end_counter))
00239       {
00240         // if plan could not be tranformed abort control and local planning
00241         ROS_WARN("Could not transform the global plan to the frame of the controller");
00242         return false;
00243       }
00244 
00245       // also check if there really is a plan
00246       if(transformed_plan_.empty())
00247       {
00248         // if global plan passed in is empty... we won't do anything
00249         ROS_WARN("Transformed plan is empty. Aborting local planner!");
00250         return false;
00251       }
00252 
00253       ROS_DEBUG("Retrieved start-end-counts are: (%d, %d)", plan_start_end_counter.at(0), plan_start_end_counter.at(1));
00254       ROS_DEBUG("Current start-end-counts are: (%d, %d)", plan_start_end_counter_.at(0), plan_start_end_counter_.at(1));
00255 
00256       // identify new frames - if there are any
00257       append_transformed_plan.clear();
00258       // did last transformed plan end futher away from end of complete plan than this transformed plan?
00259       if(plan_start_end_counter_.at(1) > plan_start_end_counter.at(1)) // counting from the back (as start might be pruned)
00260       {
00261         // new frames in moving window
00262         if(plan_start_end_counter_.at(1) > plan_start_end_counter.at(0)) // counting from the back (as start might be pruned)
00263         {
00264           // append everything
00265           append_transformed_plan = transformed_plan_;
00266         }
00267         else
00268         {
00269           // append only the new portion of the plan
00270           int discarded_frames = plan_start_end_counter.at(0) - plan_start_end_counter_.at(1);
00271           ROS_ASSERT(transformed_plan_.begin() + discarded_frames + 1 >= transformed_plan_.begin());
00272           ROS_ASSERT(transformed_plan_.begin() + discarded_frames + 1 < transformed_plan_.end());
00273           append_transformed_plan.assign(transformed_plan_.begin() + discarded_frames + 1, transformed_plan_.end());
00274         }
00275 
00276         // set it to elastic band and let eband connect it
00277         ROS_DEBUG("Adding %d new frames to current band", (int) append_transformed_plan.size());
00278         add_frames_at = add_back;
00279         if(eband_->addFrames(append_transformed_plan, add_back))
00280         {
00281           // appended frames succesfully to global plan - set new start-end counts
00282           ROS_DEBUG("Sucessfully added frames to band");
00283           plan_start_end_counter_ = plan_start_end_counter;
00284         }
00285         else {
00286           ROS_WARN("Failed to add frames to existing band");
00287           return false;
00288         }
00289       }
00290       else
00291         ROS_DEBUG("Nothing to add");
00292 
00293       // update Elastic Band (react on obstacle from costmap, ...)
00294       ROS_DEBUG("Calling optimization method for elastic band");
00295       std::vector<eband_local_planner::Bubble> current_band;
00296       if(!eband_->optimizeBand())
00297       {
00298         ROS_WARN("Optimization failed - Band invalid - No controls availlable");
00299         // display current band
00300         if(eband_->getBand(current_band))
00301           eband_visual_->publishBand("bubbles", current_band);
00302         return false;
00303       }
00304 
00305       // get current Elastic Band and
00306       eband_->getBand(current_band);
00307       // set it to the controller
00308       if(!eband_trj_ctrl_->setBand(current_band))
00309       {
00310         ROS_DEBUG("Failed to to set current band to Trajectory Controller");
00311         return false;
00312       }
00313 
00314       // set Odometry to controller
00315       if(!eband_trj_ctrl_->setOdometry(base_odom_))
00316       {
00317         ROS_DEBUG("Failed to to set current odometry to Trajectory Controller");
00318         return false;
00319       }
00320 
00321       // get resulting commands from the controller
00322       geometry_msgs::Twist cmd_twist;
00323       if(!eband_trj_ctrl_->getTwist(cmd_twist, goal_reached_))
00324       {
00325         ROS_DEBUG("Failed to calculate Twist from band in Trajectory Controller");
00326         return false;
00327       }
00328 
00329 
00330       // set retrieved commands to reference variable
00331       ROS_DEBUG("Retrieving velocity command: (%f, %f, %f)", cmd_twist.linear.x, cmd_twist.linear.y, cmd_twist.angular.z);
00332       cmd_vel = cmd_twist;
00333 
00334 
00335       // publish plan
00336       std::vector<geometry_msgs::PoseStamped> refined_plan;
00337       if(eband_->getPlan(refined_plan))
00338         // TODO publish local and current gloabl plan
00339         base_local_planner::publishPlan(refined_plan, g_plan_pub_);
00340       //base_local_planner::publishPlan(local_plan, l_plan_pub_, 0.0, 0.0, 1.0, 0.0);
00341 
00342       // display current band
00343       if(eband_->getBand(current_band))
00344         eband_visual_->publishBand("bubbles", current_band);
00345 
00346       return true;
00347     }
00348 
00349 
00350     bool EBandPlannerROS::isGoalReached()
00351     {
00352       // check if plugin initialized
00353       if(!initialized_)
00354       {
00355         ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00356         return false;
00357       }
00358 
00359       return goal_reached_;
00360 
00361       // // copy odometry information to local variable
00362       // nav_msgs::Odometry base_odom;
00363       // {
00364       //        // make sure we do not read new date from topic right at the moment
00365       //        boost::mutex::scoped_lock lock(odom_mutex_);
00366       //        base_odom = base_odom_;
00367       // }
00368 
00369       // tf::Stamped<tf::Pose> global_pose;
00370       // costmap_ros_->getRobotPose(global_pose);
00371 
00372       // // analogous to dwa_planner the actual check uses the routine implemented in trajectory_planner (trajectory rollout)
00373       // bool is_goal_reached = base_local_planner::isGoalReached(
00374       //     *tf_, global_plan_, *(costmap_ros_->getCostmap()),
00375       //     costmap_ros_->getGlobalFrameID(), global_pose, base_odom,
00376       //                rot_stopped_vel_, trans_stopped_vel_, xy_goal_tolerance_,
00377       //     yaw_goal_tolerance_
00378       // );
00379 
00380       // return is_goal_reached;
00381 
00382     }
00383 
00384 
00385     void EBandPlannerROS::odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
00386     {
00387       // lock Callback while reading data from topic
00388       boost::mutex::scoped_lock lock(odom_mutex_);
00389 
00390       // get odometry and write it to member variable (we assume that the odometry is published in the frame of the base)
00391       base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
00392       base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
00393       base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
00394     }
00395 
00396 
00397   }
00398 
00399 


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Fri Aug 28 2015 10:35:46