ftc_planner.cpp
Go to the documentation of this file.
00001 
00018 #include <ros/ros.h>
00019 
00020 #include <ftc_local_planner/ftc_planner.h>
00021 
00022 #include <pluginlib/class_list_macros.h>
00023 
00024 PLUGINLIB_EXPORT_CLASS(ftc_local_planner::FTCPlanner, nav_core::BaseLocalPlanner)
00025 
00026 namespace ftc_local_planner
00027 {
00028 
00029     FTCPlanner::FTCPlanner()
00030     {
00031     }
00032 
00033     void FTCPlanner::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
00034     {
00035         ros::NodeHandle private_nh("~/" + name);
00036         local_plan_publisher_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
00037         costmap_ros_ = costmap_ros;
00038         tf_ = tf;
00039         first_setPlan_ = true;
00040         rotate_to_global_plan_ = false;
00041         goal_reached_ = false;
00042         stand_at_goal_ = false;
00043         cmd_vel_angular_z_rotate_ = 0;
00044         cmd_vel_linear_x_ = 0;
00045         cmd_vel_angular_z_ = 0;
00046 
00047         //Parameter for dynamic reconfigure
00048         dsrv_ = new dynamic_reconfigure::Server<FTCPlannerConfig>(private_nh);
00049         dynamic_reconfigure::Server<FTCPlannerConfig>::CallbackType cb = boost::bind(&FTCPlanner::reconfigureCB, this, _1, _2);
00050         dsrv_->setCallback(cb);
00051 
00052         joinCostmap_ = new JoinCostmap();
00053 
00054         ROS_INFO("FTCPlanner: Version 2 Init.");
00055     }
00056 
00057     void FTCPlanner::reconfigureCB(FTCPlannerConfig &config, uint32_t level)
00058     {
00059         if (config.restore_defaults)
00060         {
00061             config = default_config_;
00062             config.restore_defaults = false;
00063         }
00064         config_ = config;
00065     }
00066 
00067     bool FTCPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& plan)
00068     {
00069         global_plan_ = plan;
00070 
00071         //First start of the local plan. First global plan.
00072         bool first_use = false;
00073         if(first_setPlan_)
00074         {
00075             if(config_.join_obstacle){
00076                 //init joincostmap with local an global costmap.
00077                 joinCostmap_->initialize(costmap_ros_, global_costmap_ros_);
00078             }
00079 
00080             first_setPlan_ = false;
00081             ftc_local_planner::getXPose(*tf_,global_plan_, costmap_ros_->getGlobalFrameID(),old_goal_pose_,global_plan_.size()-1);
00082             first_use = true;
00083         }
00084 
00085         ftc_local_planner::getXPose(*tf_,global_plan_, costmap_ros_->getGlobalFrameID(),goal_pose_,global_plan_.size()-1);
00086         //Have the new global plan an new goal, reset. Else dont reset.
00087         if(std::abs(std::abs(old_goal_pose_.getOrigin().getX())-std::abs(goal_pose_.getOrigin().getX())) <= config_.position_accuracy &&
00088                 std::abs(std::abs(old_goal_pose_.getOrigin().getY())-std::abs(goal_pose_.getOrigin().getY())) <= config_.position_accuracy && !first_use
00089                 && std::abs(angles::shortest_angular_distance(tf::getYaw(old_goal_pose_.getRotation()), tf::getYaw(goal_pose_.getRotation()))) <= config_.rotation_accuracy)
00090         {
00091             ROS_DEBUG("FTCPlanner: Old Goal == new Goal.");
00092         }
00093         else
00094         {
00095             //Rotate to first global plan point.
00096             rotate_to_global_plan_ = true;
00097             goal_reached_ = false;
00098             stand_at_goal_ = false;
00099             ROS_INFO("FTCPlanner: New Goal. Start new routine.");
00100         }
00101 
00102         old_goal_pose_ = goal_pose_;
00103 
00104         return true;
00105     }
00106 
00107     bool FTCPlanner::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
00108     {
00109 
00110         ros::Time begin = ros::Time::now();
00111 
00112         tf::Stamped<tf::Pose> current_pose;
00113         costmap_ros_->getRobotPose(current_pose);
00114 
00115         //Join the actual global an local costmap in the global costmap.
00116         if(config_.join_obstacle){
00117             joinCostmap_->joinMaps();
00118         }
00119         int max_point = 0;
00120         //First part of the routine. Rotatio to the first global plan orientation.
00121         if(rotate_to_global_plan_)
00122         {
00123             double angle_to_global_plan = calculateGlobalPlanAngle(current_pose, global_plan_, checkMaxDistance(current_pose));
00124             rotate_to_global_plan_ = rotateToOrientation(angle_to_global_plan, cmd_vel, 0.1);
00125         }
00126         //Second part of the routine. Drive alonge the global plan.
00127         else
00128         {
00129 
00130             double distance = sqrt(pow((goal_pose_.getOrigin().getX()-current_pose.getOrigin().getX()),2)+pow((goal_pose_.getOrigin().getY()-current_pose.getOrigin().getY()),2));
00131 
00132             //Check if robot near enough to global goal.
00133             if(distance > config_.position_accuracy && !stand_at_goal_)
00134             {
00135 
00136                 if(fabs(calculateGlobalPlanAngle(current_pose, global_plan_, checkMaxDistance(current_pose)) > 1.2))
00137                 {
00138                     ROS_INFO("FTCPlanner: Excessive deviation from global plan orientation. Start routine new.");
00139                     rotate_to_global_plan_ = true;
00140                 }
00141 
00142                 max_point = driveToward(current_pose, cmd_vel);
00143 
00144                 if(!checkCollision(max_point))
00145                 {
00146                     return false;
00147                 }
00148             }
00149             //Third part of the routine. Rotate at goal to goal orientation.
00150             else
00151             {
00152                 if(!stand_at_goal_)
00153                 {
00154                     ROS_INFO("FTCPlanner: Stand at goal. Rotate to goal orientation.");
00155                 }
00156                 stand_at_goal_ = true;
00157 
00158 
00159                 //Get the goal orientation.
00160                 double angle_to_global_plan = angles::shortest_angular_distance(tf::getYaw(current_pose.getRotation()), tf::getYaw(goal_pose_.getRotation()));
00161                 //Rotate until goalorientation is reached.
00162                 if(!rotateToOrientation(angle_to_global_plan, cmd_vel, config_.rotation_accuracy))
00163                 {
00164                     goal_reached_ = true;
00165                 }
00166                 cmd_vel.linear.x = 0;
00167                 cmd_vel.linear.y = 0;
00168             }
00169         }
00170 
00171         publishPlan(max_point);
00172 
00173         ros::Time end = ros::Time::now();
00174         ros::Duration duration = end - begin;
00175         ROS_DEBUG("FTCPlanner: Calculation time: %f seconds", duration.toSec());
00176         return true;
00177     }
00178 
00179     int FTCPlanner::checkMaxDistance(tf::Stamped<tf::Pose> current_pose)
00180     {
00181         int max_point = 0;
00182         tf::Stamped<tf::Pose> x_pose;
00183         transformed_global_plan_.clear();
00184         for (unsigned int i = 0; i < global_plan_.size(); i++)
00185         {
00186             ftc_local_planner::getXPose(*tf_,global_plan_, costmap_ros_->getGlobalFrameID(),x_pose,i);
00187             double distance = sqrt(pow((x_pose.getOrigin().getX()-current_pose.getOrigin().getX()),2)+pow((x_pose.getOrigin().getY()-current_pose.getOrigin().getY()),2));
00188 
00189             tf::Stamped<tf::Pose> p = tf::Stamped<tf::Pose>(x_pose,
00190                                       ros::Time::now(),
00191                                       costmap_ros_->getGlobalFrameID());
00192             geometry_msgs::PoseStamped pose;
00193             tf::poseStampedTFToMsg(p, pose);
00194             transformed_global_plan_.push_back(pose);
00195 
00196             max_point = i-1;
00197             //If distance higher than maximal moveable distance in sim_time.
00198             if(distance > (config_.max_x_vel*config_.sim_time))
00199             {
00200                 break;
00201             }
00202         }
00203         if(max_point < 0)
00204         {
00205             max_point = 0;
00206         }
00207         return max_point;
00208     }
00209 
00210     int FTCPlanner::checkMaxAngle(int points, tf::Stamped<tf::Pose> current_pose)
00211     {
00212         int max_point = points;
00213         double angle = 0;
00214         for(int i = max_point; i >= 0; i--)
00215         {
00216             angle = calculateGlobalPlanAngle(current_pose, global_plan_, i);
00217 
00218             max_point = i;
00219             //check if the angle is moveable
00220             if(fabs(angle) < config_.max_rotation_vel*config_.sim_time)
00221             {
00222                 break;
00223             }
00224         }
00225         return max_point;
00226     }
00227 
00228     double FTCPlanner::calculateGlobalPlanAngle(tf::Stamped<tf::Pose> current_pose, const std::vector<geometry_msgs::PoseStamped>& plan, int point)
00229     {
00230         if(point >= (int)plan.size())
00231         {
00232             point = plan.size()-1;
00233         }
00234         double angle = 0;
00235         double current_th = tf::getYaw(current_pose.getRotation());
00236         for(int i = 0; i <= point; i++)
00237         {
00238             geometry_msgs::PoseStamped x_pose;
00239             x_pose=transformed_global_plan_.at(i);
00240 
00241             //Calculate the angles between robotpose and global plan point pose
00242             double angle_to_goal = atan2(x_pose.pose.position.y - current_pose.getOrigin().getY(),
00243                                          x_pose.pose.position.x - current_pose.getOrigin().getX());
00244             angle += angle_to_goal;
00245         }
00246 
00247         //average
00248         angle = angle/(point+1);
00249 
00250         return angles::shortest_angular_distance(current_th, angle);
00251     }
00252 
00253     bool FTCPlanner::rotateToOrientation(double angle, geometry_msgs::Twist& cmd_vel, double accuracy)
00254     {
00255 
00256         if((cmd_vel_linear_x_  - 0.1)  >= 0){
00257             cmd_vel.linear.x = cmd_vel_linear_x_ - 0.1;
00258             cmd_vel_linear_x_ = cmd_vel_linear_x_ - 0.1;
00259         }
00260         if(fabs(angle) > accuracy)
00261         {
00262             //Slow down
00263             if(config_.max_rotation_vel >= fabs(angle) * (config_.acceleration_z+config_.slow_down_factor))
00264             {
00265                 ROS_DEBUG("FTCPlanner: Slow down.");
00266                 if(angle < 0)
00267                 {
00268                     if(cmd_vel_angular_z_rotate_ >= -config_.min_rotation_vel)
00269                     {
00270                         cmd_vel_angular_z_rotate_ = - config_.min_rotation_vel;
00271                         cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00272 
00273                     }
00274                     else
00275                     {
00276                         cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ + config_.acceleration_z/config_.local_planner_frequence;
00277                         cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00278                     }
00279                 }
00280                 if(angle > 0)
00281                 {
00282                     if(cmd_vel_angular_z_rotate_  <= config_.min_rotation_vel)
00283                     {
00284                         cmd_vel_angular_z_rotate_ =  config_.min_rotation_vel;
00285                         cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00286 
00287                     }
00288                     else
00289                     {
00290                         cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ - config_.acceleration_z/config_.local_planner_frequence;
00291                         cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00292                     }
00293                 }
00294             }
00295             else
00296             {
00297                 //Speed up
00298                 if(fabs(cmd_vel_angular_z_rotate_) < config_.max_rotation_vel)
00299                 {
00300                     ROS_DEBUG("FTCPlanner: Speeding up");
00301                     if(angle < 0)
00302                     {
00303                         cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ - config_.acceleration_z/config_.local_planner_frequence;
00304 
00305                         if(fabs(cmd_vel_angular_z_rotate_) > config_.max_rotation_vel)
00306                         {
00307                             cmd_vel_angular_z_rotate_ = - config_.max_rotation_vel;
00308                         }
00309                         cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00310                     }
00311                     if(angle > 0)
00312                     {
00313                         cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_rotate_ + config_.acceleration_z/config_.local_planner_frequence;
00314 
00315                         if(fabs(cmd_vel_angular_z_rotate_) > config_.max_rotation_vel)
00316                         {
00317                             cmd_vel_angular_z_rotate_ = config_.max_rotation_vel;
00318                         }
00319 
00320                         cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00321                     }
00322                 }
00323                 else
00324                 {
00325                     cmd_vel.angular.z = cmd_vel_angular_z_rotate_;
00326                 }
00327             }
00328             ROS_DEBUG("FTCPlanner: cmd_vel.z: %f, angle: %f", cmd_vel.angular.z, angle);
00329             return true;
00330         }
00331         else
00332         {
00333             cmd_vel_angular_z_rotate_ = 0;
00334             cmd_vel.angular.z = 0;
00335             return false;
00336         }
00337     }
00338 
00339     int FTCPlanner::driveToward(tf::Stamped<tf::Pose> current_pose, geometry_msgs::Twist& cmd_vel)
00340     {
00341         double distance = 0;
00342         double angle = 0;
00343         int max_point = 0;
00344 
00345         //Search for max achievable point on global plan.
00346         max_point = checkMaxDistance(current_pose);
00347         max_point = checkMaxAngle(max_point, current_pose);
00348 
00349 
00350         double cmd_vel_linear_x_old = cmd_vel_linear_x_;
00351         double cmd_vel_angular_z_old = cmd_vel_angular_z_;
00352 
00353         geometry_msgs::PoseStamped x_pose;
00354         x_pose = transformed_global_plan_.at(max_point);
00355 
00356         distance = sqrt(pow((x_pose.pose.position.x-current_pose.getOrigin().getX()),2)+pow((x_pose.pose.position.y-current_pose.getOrigin().getY()),2));
00357         angle = calculateGlobalPlanAngle(current_pose, global_plan_, max_point);
00358 
00359         //check if max velocity is exceeded
00360         if((distance/config_.sim_time) > config_.max_x_vel)
00361         {
00362             cmd_vel_linear_x_ = config_.max_x_vel;
00363         }
00364         else
00365         {
00366             cmd_vel_linear_x_ = (distance/config_.sim_time);
00367         }
00368 
00369         //check if max rotation velocity is exceeded
00370         if(fabs(angle/config_.sim_time)>config_.max_rotation_vel)
00371         {
00372             cmd_vel_angular_z_ = config_.max_rotation_vel;
00373         }
00374         else
00375         {
00376             cmd_vel_angular_z_ = (angle/config_.sim_time);
00377         }
00378 
00379         //Calculate new velocity with max acceleration
00380         if(cmd_vel_linear_x_ > cmd_vel_linear_x_old+config_.acceleration_x/config_.local_planner_frequence)
00381         {
00382             cmd_vel_linear_x_ = cmd_vel_linear_x_old+config_.acceleration_x/config_.local_planner_frequence;
00383         }
00384         else
00385         {
00386             if(cmd_vel_linear_x_ < cmd_vel_linear_x_old-config_.acceleration_x/config_.local_planner_frequence)
00387             {
00388                 cmd_vel_linear_x_ = cmd_vel_linear_x_old-config_.acceleration_x/config_.local_planner_frequence;
00389             }
00390             else
00391             {
00392                 cmd_vel_linear_x_ = cmd_vel_linear_x_old;
00393             }
00394         }
00395 
00396         //Calculate new velocity with max acceleration
00397         if(fabs(cmd_vel_angular_z_) > fabs(cmd_vel_angular_z_old)+fabs(config_.acceleration_z/config_.local_planner_frequence))
00398         {
00399             if(cmd_vel_angular_z_ < 0)
00400             {
00401                 cmd_vel_angular_z_ = cmd_vel_angular_z_old-config_.acceleration_z/config_.local_planner_frequence;
00402             }
00403             else
00404             {
00405                 cmd_vel_angular_z_ = cmd_vel_angular_z_old+config_.acceleration_z/config_.local_planner_frequence;
00406             }
00407         }
00408 
00409         if(cmd_vel_angular_z_ < 0 && cmd_vel_angular_z_old > 0)
00410         {
00411             if( fabs(cmd_vel_angular_z_ - cmd_vel_angular_z_old) > fabs(config_.acceleration_z/config_.local_planner_frequence))
00412             {
00413                 cmd_vel_angular_z_ = cmd_vel_angular_z_old - config_.acceleration_z/config_.local_planner_frequence;
00414             }
00415         }
00416 
00417         if(cmd_vel_angular_z_ > 0 && cmd_vel_angular_z_old < 0)
00418         {
00419             if( fabs(cmd_vel_angular_z_ - cmd_vel_angular_z_old) > fabs(config_.acceleration_z/config_.local_planner_frequence))
00420             {
00421                 cmd_vel_angular_z_ = cmd_vel_angular_z_old + config_.acceleration_z/config_.local_planner_frequence;
00422             }
00423         }
00424 
00425         //Check at last if velocity is to high.
00426         if(cmd_vel_angular_z_ > config_.max_rotation_vel)
00427         {
00428             cmd_vel_angular_z_ = config_.max_rotation_vel;
00429         }
00430         if(cmd_vel_angular_z_ < -config_.max_rotation_vel)
00431         {
00432             cmd_vel_angular_z_ = (- config_.max_rotation_vel);
00433         }
00434         if(cmd_vel_linear_x_ >  config_.max_x_vel)
00435         {
00436             cmd_vel_linear_x_ = config_.max_x_vel;
00437         }
00438         //Push velocity to cmd_vel for driving.
00439         cmd_vel.linear.x = cmd_vel_linear_x_;
00440         cmd_vel.angular.z = cmd_vel_angular_z_;
00441         cmd_vel_angular_z_rotate_ = cmd_vel_angular_z_;
00442         ROS_DEBUG("FTCPlanner: max_point: %d, distance: %f, x_vel: %f, rot_vel: %f, angle: %f", max_point, distance, cmd_vel.linear.x, cmd_vel.angular.z, angle);
00443 
00444         return max_point;
00445     }
00446 
00447 
00448     bool FTCPlanner::isGoalReached()
00449     {
00450         if(goal_reached_)
00451         {
00452             ROS_INFO("FTCPlanner: Goal reached.");
00453         }
00454         return goal_reached_;
00455     }
00456 
00457     bool FTCPlanner::checkCollision(int max_points)
00458     {
00459         //maximal costs
00460         unsigned char previous_cost = 255;
00461 
00462         for (int i = 0; i <= max_points; i++)
00463         {
00464             geometry_msgs::PoseStamped x_pose;
00465             x_pose = transformed_global_plan_.at(i);
00466 
00467             unsigned int x;
00468             unsigned int y;
00469             costmap_ros_->getCostmap()->worldToMap(x_pose.pose.position.x, x_pose.pose.position.y, x, y);
00470             unsigned char costs = costmap_ros_->getCostmap()->getCost(x, y);
00471             //Near at obstacel
00472             if(costs > 0)
00473             {
00474                 if(!rotate_to_global_plan_)
00475                 {
00476                     ROS_INFO("FTCPlanner: Obstacel detected. Start routine new.");
00477                 }
00478                 rotate_to_global_plan_ = true;
00479 
00480                 //Possible collision
00481                 if(costs > 127 && costs > previous_cost)
00482                 {
00483                     ROS_WARN("FTCPlanner: Possible collision. Stop local planner.");
00484                     return false;
00485                 }
00486             }
00487             previous_cost = costs;
00488         }
00489         return true;
00490     }
00491 
00492     void FTCPlanner::publishPlan(int max_point)
00493     {
00494         std::vector<geometry_msgs::PoseStamped> path;
00495         path = transformed_global_plan_;
00496 
00497         //given an empty path we won't do anything
00498         if(path.empty())
00499             return;
00500 
00501         //create a path message
00502         nav_msgs::Path gui_path;
00503         gui_path.poses.resize(path.size());
00504         gui_path.header.frame_id = path[0].header.frame_id;
00505         gui_path.header.stamp = path[0].header.stamp;
00506 
00507         // Extract the plan in world co-ordinates, we assume the path is all in the same frame
00508         for(unsigned int i=0; i < path.size(); i++)
00509         {
00510             gui_path.poses[i] = path[i];
00511         }
00512 
00513         local_plan_publisher_.publish(gui_path);
00514     }
00515 
00516     FTCPlanner::~FTCPlanner()
00517     {
00518     }
00519 }


asr_ftc_local_planner
Author(s): Marek Felix
autogenerated on Wed Jun 19 2019 19:38:18