eband_trajectory_controller.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_trajectory_controller.h>
00039 #include <tf/transform_datatypes.h>
00040 
00041 
00042 namespace eband_local_planner{
00043 
00044   using std::min;
00045   using std::max;
00046 
00047 
00048   EBandTrajectoryCtrl::EBandTrajectoryCtrl() : costmap_ros_(NULL), initialized_(false), band_set_(false), visualization_(false) {}
00049 
00050 
00051   EBandTrajectoryCtrl::EBandTrajectoryCtrl(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00052     : costmap_ros_(NULL), initialized_(false), band_set_(false), visualization_(false)
00053   {
00054     // initialize planner
00055     initialize(name, costmap_ros);
00056 
00057     // Initialize pid object (note we'll be further clamping its output)
00058     pid_.initPid(1, 0, 0, 10, -10);
00059   }
00060 
00061 
00062   EBandTrajectoryCtrl::~EBandTrajectoryCtrl() {}
00063 
00064 
00065   void EBandTrajectoryCtrl::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00066   {
00067 
00068     // check if trajectory controller is already initialized
00069     if(!initialized_)
00070     {
00071       // create Node Handle with name of plugin (as used in move_base for loading)
00072       ros::NodeHandle node_private("~/" + name);
00073 
00074       // read parameters from parameter server
00075       node_private.param("max_vel_lin", max_vel_lin_, 0.75);
00076       node_private.param("max_vel_th", max_vel_th_, 1.0);
00077 
00078       node_private.param("min_vel_lin", min_vel_lin_, 0.1);
00079       node_private.param("min_vel_th", min_vel_th_, 0.0);
00080 
00081       node_private.param("min_in_place_vel_th", min_in_place_vel_th_, 0.0);
00082       node_private.param("in_place_trans_vel", in_place_trans_vel_, 0.0);
00083 
00084       node_private.param("xy_goal_tolerance", tolerance_trans_, 0.02);
00085       node_private.param("yaw_goal_tolerance", tolerance_rot_, 0.04);
00086       node_private.param("tolerance_timeout", tolerance_timeout_, 0.5);
00087 
00088       node_private.param("k_prop", k_p_, 4.0);
00089       node_private.param("k_damp", k_nu_, 3.5);
00090 
00091       node_private.param("Ctrl_Rate", ctrl_freq_, 10.0); // TODO retrieve this from move base parameters
00092 
00093       node_private.param("max_acceleration", acc_max_, 0.5);
00094       node_private.param("virtual_mass", virt_mass_, 0.75);
00095 
00096       node_private.param("max_translational_acceleration", acc_max_trans_, 0.5);
00097       node_private.param("max_rotational_acceleration", acc_max_rot_, 1.5);
00098 
00099       node_private.param("rotation_correction_threshold", rotation_correction_threshold_, 0.5);
00100 
00101       // diffferential drive parameters
00102       node_private.param("differential_drive", differential_drive_hack_, true);
00103       node_private.param("k_int", k_int_, 0.005);
00104       node_private.param("k_diff", k_diff_, -0.005);
00105       node_private.param("bubble_velocity_multiplier", bubble_velocity_multiplier_, 2.0);
00106       node_private.param("rotation_threshold_multiplier", rotation_threshold_multiplier_, 1.0); //0.75);
00107       node_private.param("disallow_hysteresis", disallow_hysteresis_, false); //0.75);
00108       // Ctrl_rate, k_prop, max_vel_lin, max_vel_th, tolerance_trans, tolerance_rot, min_in_place_vel_th
00109       in_final_goal_turn_ = false;
00110 
00111       // copy adress of costmap and Transform Listener (handed over from move_base)
00112       costmap_ros_ = costmap_ros;
00113 
00114       // init velocity for interpolation
00115       last_vel_.linear.x = 0.0;
00116       last_vel_.linear.y = 0.0;
00117       last_vel_.linear.z = 0.0;
00118       last_vel_.angular.x = 0.0;
00119       last_vel_.angular.y = 0.0;
00120       last_vel_.angular.z = 0.0;
00121 
00122       // set the general refernce frame to that in which the band is given
00123       geometry_msgs::Pose2D tmp_pose2D;
00124       tmp_pose2D.x = 0.0;
00125       tmp_pose2D.y = 0.0;
00126       tmp_pose2D.theta = 0.0;
00127       Pose2DToPose(ref_frame_band_, tmp_pose2D);
00128 
00129       // set initialized flag
00130       initialized_ = true;
00131     }
00132     else
00133     {
00134       ROS_WARN("This planner has already been initialized, doing nothing.");
00135     }
00136   }
00137 
00138 
00139   void EBandTrajectoryCtrl::setVisualization(boost::shared_ptr<EBandVisualization> target_visual)
00140   {
00141     target_visual_ = target_visual;
00142 
00143     visualization_ = true;
00144   }
00145 
00146   bool EBandTrajectoryCtrl::setBand(const std::vector<Bubble>& elastic_band)
00147   {
00148     elastic_band_ = elastic_band;
00149     band_set_ = true;
00150     return true;
00151   }
00152 
00153 
00154   bool EBandTrajectoryCtrl::setOdometry(const nav_msgs::Odometry& odometry)
00155   {
00156     odom_vel_.linear.x = odometry.twist.twist.linear.x;
00157     odom_vel_.linear.y = odometry.twist.twist.linear.y;
00158     odom_vel_.linear.z = 0.0;
00159     odom_vel_.angular.x = 0.0;
00160     odom_vel_.angular.y = 0.0;
00161     odom_vel_.angular.z = odometry.twist.twist.angular.z;
00162 
00163     return true;
00164   }
00165 
00166   // Return the angular difference between the direction we're pointing
00167   // and the direction we want to move in
00168   double angularDiff (const geometry_msgs::Twist& heading,
00169       const geometry_msgs::Pose& pose)
00170   {
00171     const double pi = 3.14159265;
00172     const double t1 = atan2(heading.linear.y, heading.linear.x);
00173     const double t2 = tf::getYaw(pose.orientation);
00174     const double d = t1-t2;
00175 
00176     if (fabs(d)<pi)
00177       return d;
00178     else if (d<0)
00179       return d+2*pi;
00180     else
00181       return d-2*pi;
00182   }
00183 
00184   bool EBandTrajectoryCtrl::getTwistDifferentialDrive(geometry_msgs::Twist& twist_cmd, bool& goal_reached) {
00185     goal_reached = false;
00186 
00187     geometry_msgs::Twist robot_cmd, bubble_diff;
00188     robot_cmd.linear.x = 0.0;
00189     robot_cmd.angular.z = 0.0;
00190 
00191     bool command_provided = false;
00192 
00193     // check if plugin initialized
00194     if(!initialized_)   {
00195       ROS_ERROR("Requesting feedforward command from not initialized planner. Please call initialize() before using this planner");
00196       return false;
00197     }
00198 
00199     // check there is a plan at all (minimum 1 frame in this case, as robot + goal = plan)
00200     if( (!band_set_) || (elastic_band_.size() < 2) ) {
00201       ROS_WARN("Requesting feedforward command from empty band.");
00202       return false;
00203     }
00204 
00205     // Get the differences between the first 2 bubbles in the robot's frame
00206     bubble_diff = getFrame1ToFrame2InRefFrameNew(
00207         elastic_band_.at(0).center.pose,
00208         elastic_band_.at(1).center.pose,
00209         elastic_band_.at(0).center.pose);
00210 
00211     float distance_from_goal = -1.0f;
00212 
00213     // Check 1
00214     // We need to check if we are within the threshold of the final destination
00215     if (!command_provided) {
00216       int curr_target_bubble = 1;
00217 
00218       while(curr_target_bubble < ((int) elastic_band_.size()) - 1) {
00219         curr_target_bubble++;
00220         bubble_diff =
00221           getFrame1ToFrame2InRefFrameNew(
00222               elastic_band_.at(0).center.pose,
00223               elastic_band_.at(curr_target_bubble).center.pose,
00224               elastic_band_.at(0).center.pose);
00225       }
00226 
00227       // if you go past tolerance, then try to get closer again
00228       if (!disallow_hysteresis_) {
00229         if(fabs(bubble_diff.linear.x) > tolerance_trans_ ||
00230             fabs(bubble_diff.linear.y) > tolerance_trans_) {
00231           in_final_goal_turn_ = false;
00232         }
00233       }
00234 
00235       // Get the differences between the first 2 bubbles in the robot's frame
00236       int goal_bubble = (((int) elastic_band_.size()) - 1);
00237       bubble_diff = getFrame1ToFrame2InRefFrameNew(
00238           elastic_band_.at(0).center.pose,
00239           elastic_band_.at(goal_bubble).center.pose,
00240           elastic_band_.at(0).center.pose);
00241 
00242       distance_from_goal = sqrtf(bubble_diff.linear.x * bubble_diff.linear.x +
00243                                  bubble_diff.linear.y * bubble_diff.linear.y);
00244 
00245       // Get closer to the goal than the tolerance requires before starting the
00246       // final turn. The final turn may cause you to move slightly out of
00247       // position
00248       if((fabs(bubble_diff.linear.x) <= 0.6 * tolerance_trans_ &&
00249           fabs(bubble_diff.linear.y) <= 0.6 * tolerance_trans_) ||
00250           in_final_goal_turn_) {
00251         // Calculate orientation difference to goal orientation (not captured in bubble_diff)
00252         double robot_yaw = tf::getYaw(elastic_band_.at(0).center.pose.orientation);
00253         double goal_yaw = tf::getYaw(elastic_band_.at((int)elastic_band_.size() - 1).center.pose.orientation);
00254         float orientation_diff = angles::normalize_angle(goal_yaw - robot_yaw);
00255         if (fabs(orientation_diff) > tolerance_rot_) {
00256           in_final_goal_turn_ = true;
00257           ROS_DEBUG("Performing in place rotation for goal (diff): %f", orientation_diff);
00258           double rotation_sign = -2 * (orientation_diff < 0) + 1;
00259           robot_cmd.angular.z =
00260             rotation_sign * min_in_place_vel_th_ + k_p_ * orientation_diff;
00261           if (fabs(robot_cmd.angular.z) > max_vel_th_) { // limit max rotation
00262             robot_cmd.angular.z = rotation_sign * max_vel_th_;
00263           }
00264         } else {
00265           in_final_goal_turn_ = false; // Goal reached
00266           ROS_INFO ("TrajectoryController: Goal reached with distance %.2f, %.2f (od = %.2f)"
00267               "; sending zero velocity",
00268               bubble_diff.linear.x, bubble_diff.linear.y, orientation_diff);
00269           // goal position reached
00270           robot_cmd.linear.x = 0.0;
00271           robot_cmd.angular.z = 0.0;
00272           goal_reached = true;
00273         }
00274         command_provided = true;
00275       }
00276     }
00277 
00278     // Get the differences between the first 2 bubbles in the robot's frame
00279     bubble_diff = getFrame1ToFrame2InRefFrameNew(
00280         elastic_band_.at(0).center.pose,
00281         elastic_band_.at(1).center.pose,
00282         elastic_band_.at(0).center.pose);
00283 
00284     // Check 1 - check if the robot's current pose is too misaligned with the next bubble
00285     if (!command_provided) {
00286       ROS_DEBUG("Goal has not been reached, performing checks to move towards goal");
00287 
00288       // calculate an estimate of the in-place rotation threshold
00289       double distance_to_next_bubble = sqrt(
00290           bubble_diff.linear.x * bubble_diff.linear.x +
00291           bubble_diff.linear.y * bubble_diff.linear.y);
00292       double radius_of_next_bubble = 0.7 * elastic_band_.at(1).expansion;
00293       double in_place_rotation_threshold =
00294         rotation_threshold_multiplier_ *
00295         fabs(atan2(radius_of_next_bubble,distance_to_next_bubble));
00296       ROS_DEBUG("In-place rotation threshold: %f(%f,%f)",
00297           in_place_rotation_threshold, radius_of_next_bubble, distance_to_next_bubble);
00298 
00299       // check if we are above this threshold, if so then perform in-place rotation
00300       if (fabs(bubble_diff.angular.z) > in_place_rotation_threshold) {
00301         robot_cmd.angular.z = k_p_ * bubble_diff.angular.z;
00302         double rotation_sign = (bubble_diff.angular.z < 0) ? -1.0 : +1.0;
00303         if (fabs(robot_cmd.angular.z) < min_in_place_vel_th_) {
00304           robot_cmd.angular.z = rotation_sign * min_in_place_vel_th_;
00305         }
00306         if (fabs(robot_cmd.angular.z) > max_vel_th_) { // limit max rotation
00307           robot_cmd.angular.z = rotation_sign * max_vel_th_;
00308         }
00309         ROS_DEBUG("Performing in place rotation for start (diff): %f", bubble_diff.angular.z, robot_cmd.angular.z);
00310         command_provided = true;
00311       }
00312     }
00313 
00314     // Check 3 - If we reach here, it means we need to use our PID controller to
00315     // move towards the next bubble
00316     if (!command_provided) {
00317 
00318       // Select a linear velocity (based on the current bubble radius)
00319       double forward_sign = -2 * (bubble_diff.linear.x < 0) + 1;
00320       double bubble_radius = 0.7 * elastic_band_.at(0).expansion;
00321       double velocity_multiplier = bubble_velocity_multiplier_ * bubble_radius;
00322 
00323       double max_vel_lin = max_vel_lin_;
00324       if (distance_from_goal < 0.75f) {
00325         max_vel_lin = (max_vel_lin < 0.3) ? 0.15 : max_vel_lin / 2;
00326       }
00327 
00328       double linear_velocity = velocity_multiplier * max_vel_lin;
00329       linear_velocity *= cos(bubble_diff.angular.z); //decrease while turning
00330       if (fabs(linear_velocity) > max_vel_lin_) {
00331         linear_velocity = forward_sign * max_vel_lin_;
00332       } else if (fabs(linear_velocity) < min_vel_lin_) {
00333         linear_velocity = forward_sign * min_vel_lin_;
00334       }
00335 
00336       // Select an angular velocity (based on PID controller)
00337       double error = bubble_diff.angular.z;
00338       double rotation_sign = -2 * (bubble_diff.angular.z < 0) + 1;
00339       double angular_velocity = k_p_ * error;
00340       if (fabs(angular_velocity) > max_vel_th_) {
00341         angular_velocity = rotation_sign * max_vel_th_;
00342       } else if (fabs(angular_velocity) < min_vel_th_) {
00343         angular_velocity = rotation_sign * min_vel_th_;
00344       }
00345 
00346       ROS_DEBUG("Selected velocity: lin: %f, ang: %f",
00347           linear_velocity, angular_velocity);
00348 
00349       robot_cmd.linear.x = linear_velocity;
00350       robot_cmd.angular.z = angular_velocity;
00351       command_provided = true;
00352     }
00353 
00354     twist_cmd = robot_cmd;
00355     ROS_DEBUG("Final command: %f, %f", twist_cmd.linear.x, twist_cmd.angular.z);
00356     return true;
00357   }
00358 
00359 
00360   bool EBandTrajectoryCtrl::getTwist(geometry_msgs::Twist& twist_cmd, bool& goal_reached)
00361   {
00362     goal_reached = false;
00363     if (differential_drive_hack_) {
00364       return getTwistDifferentialDrive(twist_cmd, goal_reached);
00365     }
00366 
00367     // init twist cmd to be handed back to caller
00368     geometry_msgs::Twist robot_cmd, bubble_diff, control_deviation;
00369     robot_cmd.linear.x = 0.0;
00370     robot_cmd.linear.y = 0.0;
00371     robot_cmd.linear.z = 0.0;
00372     robot_cmd.angular.x = 0.0;
00373     robot_cmd.angular.y = 0.0;
00374     robot_cmd.angular.z = 0.0;
00375 
00376     // make sure command vector is clean
00377     twist_cmd = robot_cmd;
00378     control_deviation = robot_cmd;
00379 
00380     // check if plugin initialized
00381     if(!initialized_)
00382     {
00383       ROS_ERROR("Requesting feedforward command from not initialized planner. Please call initialize() before using this planner");
00384       return false;
00385     }
00386 
00387     // check there is a plan at all (minimum 1 frame in this case, as robot + goal = plan)
00388     if( (!band_set_) || (elastic_band_.size() < 2) )
00389     {
00390       ROS_WARN("Requesting feedforward command from empty band.");
00391       return false;
00392     }
00393 
00394     // calc intersection of bubble-radius with sequence of vector connecting the bubbles
00395 
00396     // get distance to target from bubble-expansion
00397     double scaled_radius = 0.7 * elastic_band_.at(0).expansion;
00398 
00399     // get difference and distance between bubbles in odometry frame
00400     double bubble_distance, ang_pseudo_dist;
00401     bubble_diff = getFrame1ToFrame2InRefFrame(elastic_band_.at(0).center.pose,
00402         elastic_band_.at(1).center.pose,
00403         ref_frame_band_);
00404     ang_pseudo_dist = bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
00405     bubble_distance = sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) + (bubble_diff.linear.y * bubble_diff.linear.y) +
00406         (ang_pseudo_dist * ang_pseudo_dist) );
00407 
00408     if(visualization_)
00409     {
00410       target_visual_->publishBubble("ctrl_target", 1, target_visual_->blue, elastic_band_.at(0));
00411       target_visual_->publishBubble("ctrl_target", 2, target_visual_->blue, elastic_band_.at(1));
00412     }
00413 
00414     // by default our control deviation is the difference between the bubble centers
00415     double abs_ctrl_dev;
00416     control_deviation = bubble_diff;
00417 
00418 
00419     ang_pseudo_dist = control_deviation.angular.z * getCircumscribedRadius(*costmap_ros_);
00420     abs_ctrl_dev = sqrt( (control_deviation.linear.x * control_deviation.linear.x) +
00421         (control_deviation.linear.y * control_deviation.linear.y) +
00422         (ang_pseudo_dist * ang_pseudo_dist) );
00423 
00424     // yet depending on the expansion of our bubble we might want to adapt this point
00425     if(scaled_radius < bubble_distance)
00426     {
00427       // triviale case - simply scale bubble_diff
00428       double scale_difference = scaled_radius / bubble_distance;
00429       bubble_diff.linear.x *= scale_difference;
00430       bubble_diff.linear.y *= scale_difference;
00431       bubble_diff.angular.z *= scale_difference;
00432       // set controls
00433       control_deviation = bubble_diff;
00434     }
00435 
00436     // if scaled_radius = bubble_distance -- we have nothing to do at all
00437 
00438     if(scaled_radius > bubble_distance)
00439     {
00440       // o.k. now we have to do a little bit more -> check next but one bubble
00441       if(elastic_band_.size() > 2)
00442       {
00443         // get difference between next and next but one bubble
00444         double next_bubble_distance;
00445         geometry_msgs::Twist next_bubble_diff;
00446         next_bubble_diff = getFrame1ToFrame2InRefFrame(elastic_band_.at(1).center.pose,
00447             elastic_band_.at(2).center.pose,
00448             ref_frame_band_);
00449         ang_pseudo_dist = next_bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
00450         next_bubble_distance = sqrt( (next_bubble_diff.linear.x * next_bubble_diff.linear.x) +
00451             (next_bubble_diff.linear.y * next_bubble_diff.linear.y) +
00452             (ang_pseudo_dist * ang_pseudo_dist) );
00453 
00454         if(scaled_radius > (bubble_distance + next_bubble_distance) )
00455         {
00456           // we should normally not end up here - but just to be sure
00457           control_deviation.linear.x = bubble_diff.linear.x + next_bubble_diff.linear.x;
00458           control_deviation.linear.y = bubble_diff.linear.y + next_bubble_diff.linear.y;
00459           control_deviation.angular.z = bubble_diff.angular.z + next_bubble_diff.angular.z;
00460           // done
00461           if(visualization_)
00462             target_visual_->publishBubble("ctrl_target", 3, target_visual_->red, elastic_band_.at(2));
00463         }
00464         else
00465         {
00466           if(visualization_)
00467             target_visual_->publishBubble("ctrl_target", 3, target_visual_->red, elastic_band_.at(2));
00468 
00469           // we want to calculate intersection point of bubble ...
00470           // ... and vector connecting the following bubbles
00471           double b_distance, cosine_at_bub;
00472           double vec_prod, norm_vec1, norm_vec2;
00473           double ang_pseudo_dist1, ang_pseudo_dist2;
00474 
00475           // get distance between next bubble center and intersection point
00476           ang_pseudo_dist1 = bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
00477           ang_pseudo_dist2 = next_bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
00478           // careful! - we need this sign because of the direction of the vectors and the definition of the vector-product
00479           vec_prod = - ( (bubble_diff.linear.x * next_bubble_diff.linear.x) +
00480               (bubble_diff.linear.y * next_bubble_diff.linear.y) +
00481               (ang_pseudo_dist1 * ang_pseudo_dist2) );
00482 
00483           norm_vec1 = sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) +
00484               (bubble_diff.linear.y * bubble_diff.linear.y) +
00485               (ang_pseudo_dist1 * ang_pseudo_dist1) );
00486 
00487           norm_vec2 = sqrt( (next_bubble_diff.linear.x * next_bubble_diff.linear.x) +
00488               (next_bubble_diff.linear.y * next_bubble_diff.linear.y) +
00489               (ang_pseudo_dist2 * ang_pseudo_dist2) );
00490 
00491           // reform the cosine-rule
00492           cosine_at_bub = vec_prod / norm_vec1 / norm_vec2;
00493           b_distance = bubble_distance * cosine_at_bub + sqrt( scaled_radius*scaled_radius -
00494               bubble_distance*bubble_distance * (1.0 - cosine_at_bub*cosine_at_bub) );
00495 
00496           // get difference vector from next_bubble to intersection point
00497           double scale_next_difference = b_distance / next_bubble_distance;
00498           next_bubble_diff.linear.x *= scale_next_difference;
00499           next_bubble_diff.linear.y *= scale_next_difference;
00500           next_bubble_diff.angular.z *= scale_next_difference;
00501 
00502           // and finally get the control deviation
00503           control_deviation.linear.x = bubble_diff.linear.x + next_bubble_diff.linear.x;
00504           control_deviation.linear.y = bubble_diff.linear.y + next_bubble_diff.linear.y;
00505           control_deviation.angular.z = bubble_diff.angular.z + next_bubble_diff.angular.z;
00506           // done
00507         }
00508       }
00509     }
00510 
00511     // plot control deviation
00512     ang_pseudo_dist = control_deviation.angular.z * getCircumscribedRadius(*costmap_ros_);
00513     abs_ctrl_dev = sqrt( (control_deviation.linear.x * control_deviation.linear.x) +
00514         (control_deviation.linear.y * control_deviation.linear.y) +
00515         (ang_pseudo_dist * ang_pseudo_dist) );
00516 
00517 
00518     if(visualization_)
00519     {
00520       // compose bubble from ctrl-target
00521       geometry_msgs::Pose2D tmp_bubble_2d, curr_bubble_2d;
00522       geometry_msgs::Pose tmp_pose;
00523       // init bubble for visualization
00524       Bubble new_bubble = elastic_band_.at(0);
00525       PoseToPose2D(elastic_band_.at(0).center.pose, curr_bubble_2d);
00526       tmp_bubble_2d.x = curr_bubble_2d.x + control_deviation.linear.x;
00527       tmp_bubble_2d.y = curr_bubble_2d.y + control_deviation.linear.y;
00528       tmp_bubble_2d.theta = curr_bubble_2d.theta + control_deviation.angular.z;
00529       Pose2DToPose(tmp_pose, tmp_bubble_2d);
00530       new_bubble.center.pose = tmp_pose;
00531       new_bubble.expansion = 0.1; // just draw a small bubble
00532       target_visual_->publishBubble("ctrl_target", 0, target_visual_->red, new_bubble);
00533     }
00534 
00535 
00536     const geometry_msgs::Point& goal = (--elastic_band_.end())->center.pose.position;
00537     const double dx = elastic_band_.at(0).center.pose.position.x - goal.x;
00538     const double dy = elastic_band_.at(0).center.pose.position.y - goal.y;
00539     const double dist_to_goal = sqrt(dx*dx + dy*dy);
00540 
00541     // Assuming we're far enough from the final goal, make sure to rotate so
00542     // we're facing the right way
00543     if (dist_to_goal > rotation_correction_threshold_)
00544     {
00545 
00546       const double angular_diff = angularDiff(control_deviation, elastic_band_.at(0).center.pose);
00547       const double vel = pid_.computeCommand(angular_diff, ros::Duration(1/ctrl_freq_));
00548       const double mult = fabs(vel) > max_vel_th_ ? max_vel_th_/fabs(vel) : 1.0;
00549       control_deviation.angular.z = vel*mult;
00550       const double abs_vel = fabs(control_deviation.angular.z);
00551 
00552       ROS_DEBUG_THROTTLE_NAMED (1.0, "angle_correction",
00553           "Angular diff is %.2f and desired angular "
00554           "vel is %.2f.  Initial translation velocity "
00555           "is %.2f, %.2f", angular_diff,
00556           control_deviation.angular.z,
00557           control_deviation.linear.x,
00558           control_deviation.linear.y);
00559       const double trans_mult = max(0.01, 1.0 - abs_vel/max_vel_th_); // There are some weird tf errors if I let it be 0
00560       control_deviation.linear.x *= trans_mult;
00561       control_deviation.linear.y *= trans_mult;
00562       ROS_DEBUG_THROTTLE_NAMED (1.0, "angle_correction",
00563           "Translation multiplier is %.2f and scaled "
00564           "translational velocity is %.2f, %.2f",
00565           trans_mult, control_deviation.linear.x,
00566           control_deviation.linear.y);
00567     }
00568     else
00569       ROS_DEBUG_THROTTLE_NAMED (1.0, "angle_correction",
00570           "Not applying angle correction because "
00571           "distance to goal is %.2f", dist_to_goal);
00572 
00573 
00574 
00575 
00576     // now the actual control procedure start (using attractive Potentials)
00577     geometry_msgs::Twist desired_velocity, currbub_maxvel_dir;
00578     double desvel_abs, desvel_abs_trans, currbub_maxvel_abs;
00579     double scale_des_vel;
00580     desired_velocity = robot_cmd;
00581     currbub_maxvel_dir = robot_cmd;
00582 
00583     // calculate "equilibrium velocity" (Khatib86 - Realtime Obstacle Avoidance)
00584     desired_velocity.linear.x = k_p_/k_nu_ * control_deviation.linear.x;
00585     desired_velocity.linear.y = k_p_/k_nu_ * control_deviation.linear.y;
00586     desired_velocity.angular.z = k_p_/k_nu_ * control_deviation.angular.z;
00587 
00588     //robot_cmd = desired_velocity;
00589 
00590     // get max vel for current bubble
00591     int curr_bub_num = 0;
00592     currbub_maxvel_abs = getBubbleTargetVel(curr_bub_num, elastic_band_, currbub_maxvel_dir);
00593 
00594     // if neccessarry scale desired vel to stay lower than currbub_maxvel_abs
00595     ang_pseudo_dist = desired_velocity.angular.z * getCircumscribedRadius(*costmap_ros_);
00596     desvel_abs = sqrt( (desired_velocity.linear.x * desired_velocity.linear.x) +
00597         (desired_velocity.linear.y * desired_velocity.linear.y) +
00598         (ang_pseudo_dist * ang_pseudo_dist) );
00599     if(desvel_abs > currbub_maxvel_abs)
00600     {
00601       scale_des_vel = currbub_maxvel_abs / desvel_abs;
00602       desired_velocity.linear.x *= scale_des_vel;
00603       desired_velocity.linear.y *= scale_des_vel;
00604       desired_velocity.angular.z *= scale_des_vel;
00605     }
00606 
00607     // make sure to stay within velocity bounds for the robot
00608     desvel_abs_trans = sqrt( (desired_velocity.linear.x * desired_velocity.linear.x) + (desired_velocity.linear.y * desired_velocity.linear.y) );
00609     // for translation
00610     if(desvel_abs_trans > max_vel_lin_)
00611     {
00612       scale_des_vel = max_vel_lin_ / desvel_abs_trans;
00613       desired_velocity.linear.x *= scale_des_vel;
00614       desired_velocity.linear.y *= scale_des_vel;
00615       // to make sure we are staying inside the bubble also scale rotation
00616       desired_velocity.angular.z *= scale_des_vel;
00617     }
00618 
00619     // for rotation
00620     if(fabs(desired_velocity.angular.z) > max_vel_th_)
00621     {
00622       scale_des_vel = max_vel_th_ / fabs(desired_velocity.angular.z);
00623       desired_velocity.angular.z *= scale_des_vel;
00624       // to make sure we are staying inside the bubble also scale translation
00625       desired_velocity.linear.x *= scale_des_vel;
00626       desired_velocity.linear.y *= scale_des_vel;
00627     }
00628 
00629     // calculate resulting force (accel. resp.) (Khatib86 - Realtime Obstacle Avoidance)
00630     geometry_msgs::Twist acc_desired;
00631     acc_desired = robot_cmd;
00632     acc_desired.linear.x = (1.0/virt_mass_) * k_nu_ * (desired_velocity.linear.x - last_vel_.linear.x);
00633     acc_desired.linear.y = (1.0/virt_mass_) * k_nu_ * (desired_velocity.linear.y - last_vel_.linear.y);
00634     acc_desired.angular.z = (1.0/virt_mass_) * k_nu_ * (desired_velocity.angular.z - last_vel_.angular.z);
00635 
00636     // constrain acceleration
00637     double scale_acc;
00638     double abs_acc_trans = sqrt( (acc_desired.linear.x*acc_desired.linear.x) + (acc_desired.linear.y*acc_desired.linear.y) );
00639     if(abs_acc_trans > acc_max_trans_)
00640     {
00641       scale_acc = acc_max_trans_ / abs_acc_trans;
00642       acc_desired.linear.x *= scale_acc;
00643       acc_desired.linear.y *= scale_acc;
00644       // again - keep relations - stay in bubble
00645       acc_desired.angular.z *= scale_acc;
00646     }
00647 
00648     if(fabs(acc_desired.angular.z) > acc_max_rot_)
00649     {
00650       scale_acc = fabs(acc_desired.angular.z) / acc_max_rot_;
00651       acc_desired.angular.z *= scale_acc;
00652       // again - keep relations - stay in bubble
00653       acc_desired.linear.x *= scale_acc;
00654       acc_desired.linear.y *= scale_acc;
00655     }
00656 
00657     // and get velocity-cmds by integrating them over one time-step
00658     last_vel_.linear.x = last_vel_.linear.x + acc_desired.linear.x / ctrl_freq_;
00659     last_vel_.linear.y = last_vel_.linear.y + acc_desired.linear.y / ctrl_freq_;
00660     last_vel_.angular.z = last_vel_.angular.z + acc_desired.angular.z / ctrl_freq_;
00661 
00662 
00663     // we are almost done now take into accoun stick-slip and similar nasty things
00664 
00665     // last checks - limit current twist cmd (upper and lower bounds)
00666     last_vel_ = limitTwist(last_vel_);
00667 
00668     // finally set robot_cmd (to non-zero value)
00669     robot_cmd = last_vel_;
00670 
00671     // now convert into robot-body frame
00672     robot_cmd = transformTwistFromFrame1ToFrame2(robot_cmd, ref_frame_band_, elastic_band_.at(0).center.pose);
00673 
00674     // check whether we reached the end of the band
00675     int curr_target_bubble = 1;
00676     while(fabs(bubble_diff.linear.x) <= tolerance_trans_ &&
00677         fabs(bubble_diff.linear.y) <= tolerance_trans_ &&
00678         fabs(bubble_diff.angular.z) <= tolerance_rot_)
00679     {
00680       if(curr_target_bubble < ((int) elastic_band_.size()) - 1)
00681       {
00682         curr_target_bubble++;
00683         // transform next target bubble into robot-body frame
00684         // and get difference to robot bubble
00685         bubble_diff = getFrame1ToFrame2InRefFrame(elastic_band_.at(0).center.pose, elastic_band_.at(curr_target_bubble).center.pose,
00686             ref_frame_band_);
00687       }
00688       else
00689       {
00690         ROS_DEBUG_THROTTLE_NAMED (1.0, "controller_state",
00691             "Goal reached with distance %.2f, %.2f, %.2f"
00692             "; sending zero velocity",
00693             bubble_diff.linear.x, bubble_diff.linear.y,
00694             bubble_diff.angular.z);
00695         // goal position reached
00696         robot_cmd.linear.x = 0.0;
00697         robot_cmd.linear.y = 0.0;
00698         robot_cmd.angular.z = 0.0;
00699         // reset velocity
00700         last_vel_.linear.x = 0.0;
00701         last_vel_.linear.y = 0.0;
00702         last_vel_.angular.z = 0.0;
00703         goal_reached = true;
00704         break;
00705       }
00706     }
00707 
00708     twist_cmd = robot_cmd;
00709 
00710     return true;
00711   }
00712 
00713 
00714   double EBandTrajectoryCtrl::getBubbleTargetVel(const int& target_bub_num, const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir)
00715   {
00716     // init reference for direction vector
00717     VelDir.linear.x = 0.0;
00718     VelDir.linear.y = 0.0;
00719     VelDir.linear.z = 0.0;
00720     VelDir.angular.x = 0.0;
00721     VelDir.angular.y = 0.0;
00722     VelDir.angular.z = 0.0;
00723 
00724     // if we are looking at the last bubble - target vel is always zero
00725     if(target_bub_num >= ((int) band.size() - 1))
00726       return 0.0;
00727 
00728 
00729     // otherwise check for max_vel calculated from current bubble size
00730     double v_max_curr_bub, v_max_next_bub;
00731     double bubble_distance, angle_to_pseudo_vel, delta_vel_max;
00732     geometry_msgs::Twist bubble_diff;
00733 
00734     // distance for braking s = 0.5*v*v/a
00735     v_max_curr_bub = sqrt(2 * elastic_band_.at(target_bub_num).expansion * acc_max_);
00736 
00737     // get distance to next bubble center
00738     ROS_ASSERT( (target_bub_num >= 0) && ((target_bub_num +1) < (int) band.size()) );
00739     bubble_diff = getFrame1ToFrame2InRefFrame(band.at(target_bub_num).center.pose, band.at(target_bub_num + 1).center.pose,
00740         ref_frame_band_);
00741     angle_to_pseudo_vel = bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
00742 
00743     bubble_distance = sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) + (bubble_diff.linear.y * bubble_diff.linear.y) +
00744         (angle_to_pseudo_vel * angle_to_pseudo_vel) );
00745 
00746     // calculate direction vector - norm of diference
00747     VelDir.linear.x =bubble_diff.linear.x/bubble_distance;
00748     VelDir.linear.y =bubble_diff.linear.y/bubble_distance;
00749     VelDir.angular.z =bubble_diff.angular.z/bubble_distance;
00750 
00751     // if next bubble outside this one we will always be able to break fast enough
00752     if(bubble_distance > band.at(target_bub_num).expansion )
00753       return v_max_curr_bub;
00754 
00755 
00756     // next bubble center inside this bubble - take into account restrictions on next bubble
00757     int next_bub_num = target_bub_num + 1;
00758     geometry_msgs::Twist dummy_twist;
00759     v_max_next_bub = getBubbleTargetVel(next_bub_num, band, dummy_twist); // recursive call
00760 
00761     // if velocity at next bubble bigger (or equal) than our velocity - we are on the safe side
00762     if(v_max_next_bub >= v_max_curr_bub)
00763       return v_max_curr_bub;
00764 
00765 
00766     // otherwise max. allowed vel is next vel + plus possible reduction on the way between the bubble-centers
00767     delta_vel_max = sqrt(2 * bubble_distance * acc_max_);
00768     v_max_curr_bub = v_max_next_bub + delta_vel_max;
00769 
00770     return v_max_curr_bub;
00771   }
00772 
00773 
00774   geometry_msgs::Twist EBandTrajectoryCtrl::getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame)
00775   {
00776 
00777     geometry_msgs::Pose2D frame1_pose2D, frame2_pose2D, ref_frame_pose2D;
00778     geometry_msgs::Pose2D frame1_pose2D_rf, frame2_pose2D_rf;
00779     geometry_msgs::Twist frame_diff;
00780 
00781     // transform all frames to Pose2d
00782     PoseToPose2D(frame1, frame1_pose2D);
00783     PoseToPose2D(frame2, frame2_pose2D);
00784     PoseToPose2D(ref_frame, ref_frame_pose2D);
00785 
00786     // transform frame1 into ref frame
00787     frame1_pose2D_rf.x = (frame1_pose2D.x - ref_frame_pose2D.x) * cos(ref_frame_pose2D.theta) +
00788       (frame1_pose2D.y - ref_frame_pose2D.y) * sin(ref_frame_pose2D.theta);
00789     frame1_pose2D_rf.y = -(frame1_pose2D.x - ref_frame_pose2D.x) * sin(ref_frame_pose2D.theta) +
00790       (frame1_pose2D.y - ref_frame_pose2D.y) * cos(ref_frame_pose2D.theta);
00791     frame1_pose2D_rf.theta = frame1_pose2D.theta - ref_frame_pose2D.theta;
00792     frame1_pose2D_rf.theta = angles::normalize_angle(frame1_pose2D_rf.theta);
00793     // transform frame2 into ref frame
00794     frame2_pose2D_rf.x = (frame2_pose2D.x - ref_frame_pose2D.x) * cos(ref_frame_pose2D.theta) +
00795       (frame2_pose2D.y - ref_frame_pose2D.y) * sin(ref_frame_pose2D.theta);
00796     frame2_pose2D_rf.y = -(frame2_pose2D.x - ref_frame_pose2D.x) * sin(ref_frame_pose2D.theta) +
00797       (frame2_pose2D.y - ref_frame_pose2D.y) * cos(ref_frame_pose2D.theta);
00798     frame2_pose2D_rf.theta = frame2_pose2D.theta - ref_frame_pose2D.theta;
00799     frame2_pose2D_rf.theta = angles::normalize_angle(frame2_pose2D_rf.theta);
00800 
00801     // get differences
00802     frame_diff.linear.x = frame2_pose2D_rf.x - frame1_pose2D_rf.x;
00803     frame_diff.linear.y = frame2_pose2D_rf.y - frame1_pose2D_rf.y;
00804     frame_diff.linear.z = 0.0;
00805     frame_diff.angular.x = 0.0;
00806     frame_diff.angular.y = 0.0;
00807     frame_diff.angular.z = frame2_pose2D_rf.theta - frame1_pose2D_rf.theta;
00808     // normalize angle
00809     frame_diff.angular.z = angles::normalize_angle(frame_diff.angular.z);
00810 
00811     return frame_diff;
00812   }
00813 
00814   geometry_msgs::Twist EBandTrajectoryCtrl::getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame)
00815   {
00816 
00817     double x1 = frame1.position.x - ref_frame.position.x;
00818     double y1 = frame1.position.y - ref_frame.position.y;
00819     double x2 = frame2.position.x - ref_frame.position.x;
00820     double y2 = frame2.position.y - ref_frame.position.y;
00821     double yaw_ref = tf::getYaw(ref_frame.orientation);
00822 
00823     double x_diff = x2 - x1;
00824     double y_diff = y2 - y1;
00825     double theta_diff = atan2(y_diff, x_diff);
00826 
00827     // Now project this vector on to the reference frame
00828     double rotation = angles::normalize_angle(yaw_ref);
00829     double x_final = x_diff * cos(rotation) + y_diff * sin(rotation);
00830     double y_final = - x_diff * sin(rotation) + y_diff * cos(rotation);
00831 
00832     geometry_msgs::Twist twist_msg;
00833     twist_msg.linear.x = x_final;
00834     twist_msg.linear.y = y_final;
00835     twist_msg.angular.z = angles::normalize_angle(theta_diff - yaw_ref);
00836 
00837     return twist_msg;
00838   }
00839 
00840 
00841   geometry_msgs::Twist EBandTrajectoryCtrl::transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist& curr_twist,
00842       const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2)
00843   {
00844     geometry_msgs::Pose2D frame1_pose2D, frame2_pose2D;
00845     geometry_msgs::Twist tmp_transformed;
00846     double delta_ang;
00847 
00848     tmp_transformed = curr_twist;
00849 
00850     // transform all frames to Pose2d
00851     PoseToPose2D(frame1, frame1_pose2D);
00852     PoseToPose2D(frame2, frame2_pose2D);
00853 
00854     // get orientation diff of frames
00855     delta_ang = frame2_pose2D.theta - frame1_pose2D.theta;
00856     delta_ang = angles::normalize_angle(delta_ang);
00857 
00858     // tranform twist
00859     tmp_transformed.linear.x = curr_twist.linear.x * cos(delta_ang) + curr_twist.linear.y * sin(delta_ang);
00860     tmp_transformed.linear.y = -curr_twist.linear.x * sin(delta_ang) + curr_twist.linear.y * cos(delta_ang);
00861 
00862     return tmp_transformed;
00863   }
00864 
00865 
00866   geometry_msgs::Twist EBandTrajectoryCtrl::limitTwist(const geometry_msgs::Twist& twist)
00867   {
00868     geometry_msgs::Twist res = twist;
00869 
00870     //make sure to bound things by our velocity limits
00871     double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
00872     double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
00873     if (lin_overshoot > 1.0)
00874     {
00875       res.linear.x /= lin_overshoot;
00876       res.linear.y /= lin_overshoot;
00877       // keep relations
00878       res.angular.z /= lin_overshoot;
00879     }
00880 
00881     //we only want to enforce a minimum velocity if we're not rotating in place
00882     if(lin_undershoot > 1.0)
00883     {
00884       res.linear.x *= lin_undershoot;
00885       res.linear.y *= lin_undershoot;
00886       // we cannot keep relations here for stability reasons
00887     }
00888 
00889     if (fabs(res.angular.z) > max_vel_th_)
00890     {
00891       double scale = max_vel_th_/fabs(res.angular.z);
00892       //res.angular.z = max_vel_th_ * sign(res.angular.z);
00893       res.angular.z *= scale;
00894       // keep relations
00895       res.linear.x *= scale;
00896       res.linear.y *= scale;
00897     }
00898 
00899     if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z);
00900     // we cannot keep relations here for stability reasons
00901 
00902     //we want to check for whether or not we're desired to rotate in place
00903     if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_)
00904     {
00905       if (fabs(res.angular.z) < min_in_place_vel_th_)
00906         res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
00907 
00908       res.linear.x = 0.0;
00909       res.linear.y = 0.0;
00910     }
00911 
00912     ROS_DEBUG("Angular command %f", res.angular.z);
00913     return res;
00914   }
00915 
00916 
00917 }


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