latched_stop_rotate_controller.cpp
Go to the documentation of this file.
00001 /*
00002  * latched_stop_rotate_controller.cpp
00003  *
00004  *  Created on: Apr 16, 2012
00005  *      Author: tkruse
00006  */
00007 
00008 #include <base_local_planner/latched_stop_rotate_controller.h>
00009 
00010 #include <cmath>
00011 
00012 #include <Eigen/Core>
00013 
00014 #include <angles/angles.h>
00015 #include <nav_msgs/Odometry.h>
00016 
00017 #include <base_local_planner/goal_functions.h>
00018 #include <base_local_planner/local_planner_limits.h>
00019 
00020 namespace base_local_planner {
00021 
00022 LatchedStopRotateController::LatchedStopRotateController() {
00023   rotating_to_goal_ = false;
00024 }
00025 
00026 LatchedStopRotateController::~LatchedStopRotateController() {}
00027 
00028 
00034 bool LatchedStopRotateController::isPositionReached(LocalPlannerUtil* planner_util,
00035     tf::Stamped<tf::Pose> global_pose) {
00036   double xy_goal_tolerance = planner_util->getCurrentLimits().xy_goal_tolerance;
00037 
00038   //we assume the global goal is the last point in the global plan
00039   tf::Stamped<tf::Pose> goal_pose;
00040   if ( ! planner_util->getGoal(goal_pose)) {
00041     return false;
00042   }
00043 
00044   double goal_x = goal_pose.getOrigin().getX();
00045   double goal_y = goal_pose.getOrigin().getY();
00046 
00047   //check to see if we've reached the goal position
00048   if ((latch_xy_goal_tolerance_ && xy_tolerance_latch_) ||
00049       base_local_planner::getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
00050     xy_tolerance_latch_ = true;
00051     return true;
00052   }
00053   return false;
00054 }
00055 
00056 
00061 bool LatchedStopRotateController::isGoalReached(LocalPlannerUtil* planner_util,
00062     OdometryHelperRos& odom_helper,
00063     tf::Stamped<tf::Pose> global_pose) {
00064   double xy_goal_tolerance = planner_util->getCurrentLimits().xy_goal_tolerance;
00065   double rot_stopped_vel = planner_util->getCurrentLimits().rot_stopped_vel;
00066   double trans_stopped_vel = planner_util->getCurrentLimits().trans_stopped_vel;
00067 
00068   //copy over the odometry information
00069   nav_msgs::Odometry base_odom;
00070   odom_helper.getOdom(base_odom);
00071 
00072   //we assume the global goal is the last point in the global plan
00073   tf::Stamped<tf::Pose> goal_pose;
00074   if ( ! planner_util->getGoal(goal_pose)) {
00075     return false;
00076   }
00077 
00078   double goal_x = goal_pose.getOrigin().getX();
00079   double goal_y = goal_pose.getOrigin().getY();
00080 
00081   base_local_planner::LocalPlannerLimits limits = planner_util->getCurrentLimits();
00082 
00083   //check to see if we've reached the goal position
00084   if ((latch_xy_goal_tolerance_ && xy_tolerance_latch_) ||
00085       base_local_planner::getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
00086     //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll
00087     //just rotate in place
00088     if (latch_xy_goal_tolerance_ && ! xy_tolerance_latch_) {
00089       ROS_DEBUG("Goal position reached (check), stopping and turning in place");
00090       xy_tolerance_latch_ = true;
00091     }
00092     double goal_th = tf::getYaw(goal_pose.getRotation());
00093     double angle = base_local_planner::getGoalOrientationAngleDifference(global_pose, goal_th);
00094     //check to see if the goal orientation has been reached
00095     if (fabs(angle) <= limits.yaw_goal_tolerance) {
00096       //make sure that we're actually stopped before returning success
00097       if (base_local_planner::stopped(base_odom, rot_stopped_vel, trans_stopped_vel)) {
00098         return true;
00099       }
00100     }
00101   }
00102   return false;
00103 }
00104 
00105 bool LatchedStopRotateController::stopWithAccLimits(const tf::Stamped<tf::Pose>& global_pose,
00106     const tf::Stamped<tf::Pose>& robot_vel,
00107     geometry_msgs::Twist& cmd_vel,
00108     Eigen::Vector3f acc_lim,
00109     double sim_period,
00110     boost::function<bool (Eigen::Vector3f pos,
00111                           Eigen::Vector3f vel,
00112                           Eigen::Vector3f vel_samples)> obstacle_check) {
00113 
00114   //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible
00115   //but we'll use a tenth of a second to be consistent with the implementation of the local planner.
00116   double vx = sign(robot_vel.getOrigin().x()) * std::max(0.0, (fabs(robot_vel.getOrigin().x()) - acc_lim[0] * sim_period));
00117   double vy = sign(robot_vel.getOrigin().y()) * std::max(0.0, (fabs(robot_vel.getOrigin().y()) - acc_lim[1] * sim_period));
00118 
00119   double vel_yaw = tf::getYaw(robot_vel.getRotation());
00120   double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim[2] * sim_period));
00121 
00122   //we do want to check whether or not the command is valid
00123   double yaw = tf::getYaw(global_pose.getRotation());
00124   bool valid_cmd = obstacle_check(Eigen::Vector3f(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw),
00125                                   Eigen::Vector3f(robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw),
00126                                   Eigen::Vector3f(vx, vy, vth));
00127 
00128   //if we have a valid command, we'll pass it on, otherwise we'll command all zeros
00129   if(valid_cmd){
00130     ROS_DEBUG_NAMED("latched_stop_rotate", "Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth);
00131     cmd_vel.linear.x = vx;
00132     cmd_vel.linear.y = vy;
00133     cmd_vel.angular.z = vth;
00134     return true;
00135   }
00136   ROS_WARN("Stopping cmd in collision");
00137   cmd_vel.linear.x = 0.0;
00138   cmd_vel.linear.y = 0.0;
00139   cmd_vel.angular.z = 0.0;
00140   return false;
00141 }
00142 
00143 bool LatchedStopRotateController::rotateToGoal(
00144     const tf::Stamped<tf::Pose>& global_pose,
00145     const tf::Stamped<tf::Pose>& robot_vel,
00146     double goal_th,
00147     geometry_msgs::Twist& cmd_vel,
00148     Eigen::Vector3f acc_lim,
00149     double sim_period,
00150     base_local_planner::LocalPlannerLimits& limits,
00151     boost::function<bool (Eigen::Vector3f pos,
00152                           Eigen::Vector3f vel,
00153                           Eigen::Vector3f vel_samples)> obstacle_check) {
00154   double yaw = tf::getYaw(global_pose.getRotation());
00155   double vel_yaw = tf::getYaw(robot_vel.getRotation());
00156   cmd_vel.linear.x = 0;
00157   cmd_vel.linear.y = 0;
00158   double ang_diff = angles::shortest_angular_distance(yaw, goal_th);
00159 
00160   double v_theta_samp = std::min(limits.max_rot_vel, std::max(limits.min_rot_vel, fabs(ang_diff)));
00161 
00162   //take the acceleration limits of the robot into account
00163   double max_acc_vel = fabs(vel_yaw) + acc_lim[2] * sim_period;
00164   double min_acc_vel = fabs(vel_yaw) - acc_lim[2] * sim_period;
00165 
00166   v_theta_samp = std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
00167 
00168   //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits
00169   double max_speed_to_stop = sqrt(2 * acc_lim[2] * fabs(ang_diff));
00170   v_theta_samp = std::min(max_speed_to_stop, fabs(v_theta_samp));
00171 
00172   v_theta_samp = std::min(limits.max_rot_vel, std::max(limits.min_rot_vel, v_theta_samp));
00173 
00174   if (ang_diff < 0) {
00175     v_theta_samp = - v_theta_samp;
00176   }
00177 
00178   //we still want to lay down the footprint of the robot and check if the action is legal
00179   bool valid_cmd = obstacle_check(Eigen::Vector3f(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), yaw),
00180       Eigen::Vector3f(robot_vel.getOrigin().getX(), robot_vel.getOrigin().getY(), vel_yaw),
00181       Eigen::Vector3f( 0.0, 0.0, v_theta_samp));
00182 
00183   if (valid_cmd) {
00184     ROS_DEBUG_NAMED("dwa_local_planner", "Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd);
00185     cmd_vel.angular.z = v_theta_samp;
00186     return true;
00187   }
00188   ROS_WARN("Rotation cmd in collision");
00189   cmd_vel.angular.z = 0.0;
00190   return false;
00191 
00192 }
00193 
00194 bool LatchedStopRotateController::computeVelocityCommandsStopRotate(geometry_msgs::Twist& cmd_vel,
00195     Eigen::Vector3f acc_lim,
00196     double sim_period,
00197     LocalPlannerUtil* planner_util,
00198     OdometryHelperRos& odom_helper_,
00199     tf::Stamped<tf::Pose> global_pose,
00200     boost::function<bool (Eigen::Vector3f pos,
00201                           Eigen::Vector3f vel,
00202                           Eigen::Vector3f vel_samples)> obstacle_check) {
00203   //we assume the global goal is the last point in the global plan
00204   tf::Stamped<tf::Pose> goal_pose;
00205   if ( ! planner_util->getGoal(goal_pose)) {
00206     ROS_ERROR("Could not get goal pose");
00207     return false;
00208   }
00209 
00210   base_local_planner::LocalPlannerLimits limits = planner_util->getCurrentLimits();
00211 
00212   //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll
00213   //just rotate in place
00214   if (latch_xy_goal_tolerance_ && ! xy_tolerance_latch_ ) {
00215     ROS_INFO("Goal position reached, stopping and turning in place");
00216     xy_tolerance_latch_ = true;
00217   }
00218   //check to see if the goal orientation has been reached
00219   double goal_th = tf::getYaw(goal_pose.getRotation());
00220   double angle = base_local_planner::getGoalOrientationAngleDifference(global_pose, goal_th);
00221   if (fabs(angle) <= limits.yaw_goal_tolerance) {
00222     //set the velocity command to zero
00223     cmd_vel.linear.x = 0.0;
00224     cmd_vel.linear.y = 0.0;
00225     cmd_vel.angular.z = 0.0;
00226     rotating_to_goal_ = false;
00227   } else {
00228     ROS_DEBUG("Angle: %f Tolerance: %f", angle, limits.yaw_goal_tolerance);
00229     tf::Stamped<tf::Pose> robot_vel;
00230     odom_helper_.getRobotVel(robot_vel);
00231     nav_msgs::Odometry base_odom;
00232     odom_helper_.getOdom(base_odom);
00233 
00234     //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot
00235     if ( ! rotating_to_goal_ && !base_local_planner::stopped(base_odom, limits.rot_stopped_vel, limits.trans_stopped_vel)) {
00236       if ( ! stopWithAccLimits(
00237           global_pose,
00238           robot_vel,
00239           cmd_vel,
00240           acc_lim,
00241           sim_period,
00242           obstacle_check)) {
00243         ROS_INFO("Error when stopping.");
00244         return false;
00245       }
00246       ROS_DEBUG("Stopping...");
00247     }
00248     //if we're stopped... then we want to rotate to goal
00249     else {
00250       //set this so that we know its OK to be moving
00251       rotating_to_goal_ = true;
00252       if ( ! rotateToGoal(
00253           global_pose,
00254           robot_vel,
00255           goal_th,
00256           cmd_vel,
00257           acc_lim,
00258           sim_period,
00259           limits,
00260           obstacle_check)) {
00261         ROS_INFO("Error when rotating.");
00262         return false;
00263       }
00264       ROS_DEBUG("Rotating...");
00265     }
00266   }
00267 
00268   return true;
00269 
00270 }
00271 
00272 
00273 } /* namespace base_local_planner */


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Mon Oct 6 2014 02:45:34