pose_follower.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2009, 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: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #include <pose_follower/pose_follower.h>
00038 #include <pluginlib/class_list_macros.h>
00039 
00040 PLUGINLIB_DECLARE_CLASS(pose_follower, PoseFollower, pose_follower::PoseFollower, nav_core::BaseLocalPlanner)
00041 
00042 namespace pose_follower {
00043   PoseFollower::PoseFollower(): tf_(NULL), costmap_ros_(NULL) {}
00044 
00045   void PoseFollower::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros){
00046     tf_ = tf;
00047     costmap_ros_ = costmap_ros;
00048     current_waypoint_ = 0;
00049     goal_reached_time_ = ros::Time::now();
00050     ros::NodeHandle node_private("~/" + name);
00051 
00052     collision_planner_.initialize(name, tf_, costmap_ros_);
00053 
00054     node_private.param("k_trans", K_trans_, 2.0);
00055     node_private.param("k_rot", K_rot_, 2.0);
00056 
00057     node_private.param("tolerance_trans", tolerance_trans_, 0.02);
00058     node_private.param("tolerance_rot", tolerance_rot_, 0.04);
00059     node_private.param("tolerance_timeout", tolerance_timeout_, 0.5);
00060 
00061     node_private.param("holonomic", holonomic_, true);
00062 
00063     node_private.param("samples", samples_, 10);
00064 
00065     node_private.param("max_vel_lin", max_vel_lin_, 0.9);
00066     node_private.param("max_vel_th", max_vel_th_, 1.4);
00067 
00068     node_private.param("min_vel_lin", min_vel_lin_, 0.1);
00069     node_private.param("min_vel_th", min_vel_th_, 0.0);
00070     node_private.param("min_in_place_vel_th", min_in_place_vel_th_, 0.0);
00071     node_private.param("in_place_trans_vel", in_place_trans_vel_, 0.0);
00072 
00073     node_private.param("trans_stopped_velocity", trans_stopped_velocity_, 1e-4);
00074     node_private.param("rot_stopped_velocity", rot_stopped_velocity_, 1e-4);
00075 
00076     ros::NodeHandle node;
00077     odom_sub_ = node.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&PoseFollower::odomCallback, this, _1));
00078     vel_pub_ = node.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00079 
00080     ROS_DEBUG("Initialized");
00081   }
00082 
00083   void PoseFollower::odomCallback(const nav_msgs::Odometry::ConstPtr& msg){
00084     //we assume that the odometry is published in the frame of the base
00085     boost::mutex::scoped_lock lock(odom_lock_);
00086     base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
00087     base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
00088     base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
00089     ROS_DEBUG("In the odometry callback with velocity values: (%.2f, %.2f, %.2f)",
00090         base_odom_.twist.twist.linear.x, base_odom_.twist.twist.linear.y, base_odom_.twist.twist.angular.z);
00091   }
00092 
00093   double PoseFollower::headingDiff(double x, double y, double pt_x, double pt_y, double heading)
00094   {
00095     double v1_x = x - pt_x;
00096     double v1_y = y - pt_y;
00097     double v2_x = cos(heading);
00098     double v2_y = sin(heading);
00099 
00100     double perp_dot = v1_x * v2_y - v1_y * v2_x;
00101     double dot = v1_x * v2_x + v1_y * v2_y;
00102 
00103     //get the signed angle
00104     double vector_angle = atan2(perp_dot, dot);
00105 
00106     return -1.0 * vector_angle;
00107   }
00108 
00109   bool PoseFollower::stopped(){
00110     //copy over the odometry information
00111     nav_msgs::Odometry base_odom;
00112     {
00113       boost::mutex::scoped_lock lock(odom_lock_);
00114       base_odom = base_odom_;
00115     }
00116 
00117     return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity_
00118       && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity_
00119       && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity_;
00120   }
00121 
00122   bool PoseFollower::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
00123     //get the current pose of the robot in the fixed frame
00124     tf::Stamped<tf::Pose> robot_pose;
00125     if(!costmap_ros_->getRobotPose(robot_pose)){
00126       ROS_ERROR("Can't get robot pose");
00127       geometry_msgs::Twist empty_twist;
00128       cmd_vel = empty_twist;
00129       return false;
00130     }
00131 
00132     //we want to compute a velocity command based on our current waypoint
00133     tf::Stamped<tf::Pose> target_pose;
00134     tf::poseStampedMsgToTF(global_plan_[current_waypoint_], target_pose);
00135 
00136     ROS_DEBUG("PoseFollower: current robot pose %f %f ==> %f", robot_pose.getOrigin().x(), robot_pose.getOrigin().y(), tf::getYaw(robot_pose.getRotation()));
00137     ROS_DEBUG("PoseFollower: target robot pose %f %f ==> %f", target_pose.getOrigin().x(), target_pose.getOrigin().y(), tf::getYaw(target_pose.getRotation()));
00138 
00139     //get the difference between the two poses
00140     geometry_msgs::Twist diff = diff2D(target_pose, robot_pose);
00141     ROS_DEBUG("PoseFollower: diff %f %f ==> %f", diff.linear.x, diff.linear.y, diff.angular.z);
00142 
00143     geometry_msgs::Twist limit_vel = limitTwist(diff);
00144 
00145     geometry_msgs::Twist test_vel = limit_vel;
00146     bool legal_traj = collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z, true);
00147 
00148     double scaling_factor = 1.0;
00149     double ds = scaling_factor / samples_;
00150 
00151     //let's make sure that the velocity command is legal... and if not, scale down
00152     if(!legal_traj){
00153       for(int i = 0; i < samples_; ++i){
00154         test_vel.linear.x = limit_vel.linear.x * scaling_factor;
00155         test_vel.linear.y = limit_vel.linear.y * scaling_factor;
00156         test_vel.angular.z = limit_vel.angular.z * scaling_factor;
00157         test_vel = limitTwist(test_vel);
00158         if(collision_planner_.checkTrajectory(test_vel.linear.x, test_vel.linear.y, test_vel.angular.z, false)){
00159           legal_traj = true;
00160           break;
00161         }
00162         scaling_factor -= ds;
00163       }
00164     }
00165 
00166     if(!legal_traj){
00167       ROS_ERROR("Not legal (%.2f, %.2f, %.2f)", limit_vel.linear.x, limit_vel.linear.y, limit_vel.angular.z);
00168       geometry_msgs::Twist empty_twist;
00169       cmd_vel = empty_twist;
00170       return false;
00171     }
00172 
00173     //if it is legal... we'll pass it on
00174     cmd_vel = test_vel;
00175 
00176     bool in_goal_position = false;
00177     while(fabs(diff.linear.x) <= tolerance_trans_ &&
00178           fabs(diff.linear.y) <= tolerance_trans_ &&
00179           fabs(diff.angular.z) <= tolerance_rot_)
00180     {
00181       if(current_waypoint_ < global_plan_.size() - 1)
00182       {
00183         current_waypoint_++;
00184         tf::poseStampedMsgToTF(global_plan_[current_waypoint_], target_pose);
00185         diff = diff2D(target_pose, robot_pose);
00186       }
00187       else
00188       {
00189         ROS_INFO("Reached goal: %d", current_waypoint_);
00190         in_goal_position = true;
00191         break;
00192       }
00193     }
00194 
00195     //if we're not in the goal position, we need to update time
00196     if(!in_goal_position)
00197       goal_reached_time_ = ros::Time::now();
00198 
00199     //check if we've reached our goal for long enough to succeed
00200     if(goal_reached_time_ + ros::Duration(tolerance_timeout_) < ros::Time::now()){
00201       geometry_msgs::Twist empty_twist;
00202       cmd_vel = empty_twist;
00203     }
00204 
00205     return true;
00206   }
00207 
00208   bool PoseFollower::setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan){
00209     current_waypoint_ = 0;
00210     goal_reached_time_ = ros::Time::now();
00211     if(!transformGlobalPlan(*tf_, global_plan, *costmap_ros_, costmap_ros_->getGlobalFrameID(), global_plan_)){
00212       ROS_ERROR("Could not transform the global plan to the frame of the controller");
00213       return false;
00214     }
00215     return true;
00216   }
00217 
00218   bool PoseFollower::isGoalReached(){
00219     if(goal_reached_time_ + ros::Duration(tolerance_timeout_) < ros::Time::now() && stopped()){
00220       return true;
00221     }
00222     return false;
00223   }
00224 
00225   geometry_msgs::Twist PoseFollower::diff2D(const tf::Pose& pose1, const tf::Pose& pose2)
00226   {
00227     geometry_msgs::Twist res;
00228     tf::Pose diff = pose2.inverse() * pose1;
00229     res.linear.x = diff.getOrigin().x();
00230     res.linear.y = diff.getOrigin().y();
00231     res.angular.z = tf::getYaw(diff.getRotation());
00232 
00233     if(holonomic_ || (fabs(res.linear.x) <= tolerance_trans_ && fabs(res.linear.y) <= tolerance_trans_))
00234       return res;
00235 
00236     //in the case that we're not rotating to our goal position and we have a non-holonomic robot
00237     //we'll need to command a rotational velocity that will help us reach our desired heading
00238     
00239     //we want to compute a goal based on the heading difference between our pose and the target
00240     double yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(), 
00241         pose2.getOrigin().x(), pose2.getOrigin().y(), tf::getYaw(pose2.getRotation()));
00242 
00243     //we'll also check if we can move more effectively backwards
00244     double neg_yaw_diff = headingDiff(pose1.getOrigin().x(), pose1.getOrigin().y(), 
00245         pose2.getOrigin().x(), pose2.getOrigin().y(), M_PI + tf::getYaw(pose2.getRotation()));
00246 
00247     //check if its faster to just back up
00248     if(fabs(neg_yaw_diff) < fabs(yaw_diff)){
00249       ROS_DEBUG("Negative is better: %.2f", neg_yaw_diff);
00250       yaw_diff = neg_yaw_diff;
00251     }
00252 
00253     //compute the desired quaterion
00254     tf::Quaternion rot_diff = tf::createQuaternionFromYaw(yaw_diff);
00255     tf::Quaternion rot = pose2.getRotation() * rot_diff;
00256     tf::Pose new_pose = pose1;
00257     new_pose.setRotation(rot);
00258 
00259     diff = pose2.inverse() * new_pose;
00260     res.linear.x = diff.getOrigin().x();
00261     res.linear.y = diff.getOrigin().y();
00262     res.angular.z = tf::getYaw(diff.getRotation());
00263     return res;
00264   }
00265 
00266 
00267   geometry_msgs::Twist PoseFollower::limitTwist(const geometry_msgs::Twist& twist)
00268   {
00269     geometry_msgs::Twist res = twist;
00270     res.linear.x *= K_trans_;
00271     if(!holonomic_)
00272       res.linear.y = 0.0;
00273     else    
00274       res.linear.y *= K_trans_;
00275     res.angular.z *= K_rot_;
00276 
00277     //make sure to bound things by our velocity limits
00278     double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
00279     double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
00280     if (lin_overshoot > 1.0) 
00281     {
00282       res.linear.x /= lin_overshoot;
00283       res.linear.y /= lin_overshoot;
00284     }
00285 
00286     //we only want to enforce a minimum velocity if we're not rotating in place
00287     if(lin_undershoot > 1.0)
00288     {
00289       res.linear.x *= lin_undershoot;
00290       res.linear.y *= lin_undershoot;
00291     }
00292 
00293     if (fabs(res.angular.z) > max_vel_th_) res.angular.z = max_vel_th_ * sign(res.angular.z);
00294     if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z);
00295 
00296     //we want to check for whether or not we're desired to rotate in place
00297     if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_){
00298       if (fabs(res.angular.z) < min_in_place_vel_th_) res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
00299       res.linear.x = 0.0;
00300       res.linear.y = 0.0;
00301     }
00302 
00303     ROS_DEBUG("Angular command %f", res.angular.z);
00304     return res;
00305   }
00306 
00307   bool PoseFollower::transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, 
00308       const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
00309       std::vector<geometry_msgs::PoseStamped>& transformed_plan){
00310     const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
00311 
00312     transformed_plan.clear();
00313 
00314     try{
00315       if (!global_plan.size() > 0)
00316       {
00317         ROS_ERROR("Recieved plan with zero length");
00318         return false;
00319       }
00320 
00321       tf::StampedTransform transform;
00322       tf.lookupTransform(global_frame, ros::Time(), 
00323           plan_pose.header.frame_id, plan_pose.header.stamp, 
00324           plan_pose.header.frame_id, transform);
00325 
00326       tf::Stamped<tf::Pose> tf_pose;
00327       geometry_msgs::PoseStamped newer_pose;
00328       //now we'll transform until points are outside of our distance threshold
00329       for(unsigned int i = 0; i < global_plan.size(); ++i){
00330         const geometry_msgs::PoseStamped& pose = global_plan[i];
00331         poseStampedMsgToTF(pose, tf_pose);
00332         tf_pose.setData(transform * tf_pose);
00333         tf_pose.stamp_ = transform.stamp_;
00334         tf_pose.frame_id_ = global_frame;
00335         poseStampedTFToMsg(tf_pose, newer_pose);
00336 
00337         transformed_plan.push_back(newer_pose);
00338       }
00339     }
00340     catch(tf::LookupException& ex) {
00341       ROS_ERROR("No Transform available Error: %s\n", ex.what());
00342       return false;
00343     }
00344     catch(tf::ConnectivityException& ex) {
00345       ROS_ERROR("Connectivity Error: %s\n", ex.what());
00346       return false;
00347     }
00348     catch(tf::ExtrapolationException& ex) {
00349       ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00350       if (global_plan.size() > 0)
00351         ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
00352 
00353       return false;
00354     }
00355 
00356     return true;
00357   }
00358 };


pose_follower
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Oct 6 2014 02:48:02