Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <rotate_recovery/rotate_recovery.h>
00038 #include <pluginlib/class_list_macros.h>
00039
00040
00041 PLUGINLIB_DECLARE_CLASS(rotate_recovery, RotateRecovery, rotate_recovery::RotateRecovery, nav_core::RecoveryBehavior)
00042
00043 namespace rotate_recovery {
00044 RotateRecovery::RotateRecovery(): global_costmap_(NULL), local_costmap_(NULL),
00045 tf_(NULL), initialized_(false), world_model_(NULL) {}
00046
00047 void RotateRecovery::initialize(std::string name, tf::TransformListener* tf,
00048 costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap){
00049 if(!initialized_){
00050 name_ = name;
00051 tf_ = tf;
00052 global_costmap_ = global_costmap;
00053 local_costmap_ = local_costmap;
00054
00055
00056 ros::NodeHandle private_nh("~/" + name_);
00057 ros::NodeHandle blp_nh("~/TrajectoryPlannerROS");
00058
00059
00060 private_nh.param("sim_granularity", sim_granularity_, 0.017);
00061 private_nh.param("frequency", frequency_, 20.0);
00062
00063 blp_nh.param("acc_lim_th", acc_lim_th_, 3.2);
00064 blp_nh.param("max_rotational_vel", max_rotational_vel_, 1.0);
00065 blp_nh.param("min_in_place_rotational_vel", min_rotational_vel_, 0.4);
00066 blp_nh.param("yaw_goal_tolerance", tolerance_, 0.10);
00067
00068 world_model_ = new base_local_planner::CostmapModel(*local_costmap_->getCostmap());
00069
00070 initialized_ = true;
00071 }
00072 else{
00073 ROS_ERROR("You should not call initialize twice on this object, doing nothing");
00074 }
00075 }
00076
00077 RotateRecovery::~RotateRecovery(){
00078 delete world_model_;
00079 }
00080
00081 void RotateRecovery::runBehavior(){
00082 if(!initialized_){
00083 ROS_ERROR("This object must be initialized before runBehavior is called");
00084 return;
00085 }
00086
00087 if(global_costmap_ == NULL || local_costmap_ == NULL){
00088 ROS_ERROR("The costmaps passed to the RotateRecovery object cannot be NULL. Doing nothing.");
00089 return;
00090 }
00091 ROS_WARN("Rotate recovery behavior started.");
00092
00093 ros::Rate r(frequency_);
00094 ros::NodeHandle n;
00095 ros::Publisher vel_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 10);
00096
00097 tf::Stamped<tf::Pose> global_pose;
00098 local_costmap_->getRobotPose(global_pose);
00099
00100 double current_angle = -1.0 * M_PI;
00101
00102 bool got_180 = false;
00103
00104 double start_offset = 0 - angles::normalize_angle(tf::getYaw(global_pose.getRotation()));
00105 while(n.ok()){
00106 local_costmap_->getRobotPose(global_pose);
00107
00108 double norm_angle = angles::normalize_angle(tf::getYaw(global_pose.getRotation()));
00109 current_angle = angles::normalize_angle(norm_angle + start_offset);
00110
00111
00112 double dist_left = M_PI - current_angle;
00113
00114 double x = global_pose.getOrigin().x(), y = global_pose.getOrigin().y();
00115
00116
00117 double sim_angle = 0.0;
00118 while(sim_angle < dist_left){
00119 double theta = tf::getYaw(global_pose.getRotation()) + sim_angle;
00120
00121
00122 double footprint_cost = world_model_->footprintCost(x, y, theta, local_costmap_->getRobotFootprint(), 0.0, 0.0);
00123 if(footprint_cost < 0.0){
00124 ROS_ERROR("Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f", footprint_cost);
00125 return;
00126 }
00127
00128 sim_angle += sim_granularity_;
00129 }
00130
00131
00132 double vel = sqrt(2 * acc_lim_th_ * dist_left);
00133
00134
00135 vel = std::min(std::max(vel, min_rotational_vel_), max_rotational_vel_);
00136
00137 geometry_msgs::Twist cmd_vel;
00138 cmd_vel.linear.x = 0.0;
00139 cmd_vel.linear.y = 0.0;
00140 cmd_vel.angular.z = vel;
00141
00142 vel_pub.publish(cmd_vel);
00143
00144
00145 if(current_angle < 0.0)
00146 got_180 = true;
00147
00148
00149 if(got_180 && current_angle >= (0.0 - tolerance_))
00150 return;
00151
00152 r.sleep();
00153 }
00154 }
00155 };