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
00038 #include <eband_local_planner/eband_local_planner_ros.h>
00039
00040
00041 #include <pluginlib/class_list_macros.h>
00042
00043
00044 #include <nav_core/base_local_planner.h>
00045
00046
00047
00048
00049 PLUGINLIB_DECLARE_CLASS(eband_local_planner, EBandPlannerROS, eband_local_planner::EBandPlannerROS, nav_core::BaseLocalPlanner)
00050
00051
00052 namespace eband_local_planner{
00053
00054 EBandPlannerROS::EBandPlannerROS() : costmap_ros_(NULL), tf_(NULL), initialized_(false) {}
00055
00056
00057 EBandPlannerROS::EBandPlannerROS(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
00058 : costmap_ros_(NULL), tf_(NULL), initialized_(false)
00059 {
00060
00061 initialize(name, tf, costmap_ros);
00062 }
00063
00064
00065 EBandPlannerROS::~EBandPlannerROS() {}
00066
00067
00068 void EBandPlannerROS::initialize(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros)
00069 {
00070
00071 if(!initialized_)
00072 {
00073
00074 costmap_ros_ = costmap_ros;
00075 tf_ = tf;
00076
00077
00078
00079 ros::NodeHandle pn("~/" + name);
00080
00081
00082
00083 pn.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05);
00084 pn.param("xy_goal_tolerance", xy_goal_tolerance_, 0.1);
00085
00086
00087 pn.param("rot_stopped_vel", rot_stopped_vel_, 1e-2);
00088 pn.param("trans_stopped_vel", trans_stopped_vel_, 1e-2);
00089
00090
00091 g_plan_pub_ = pn.advertise<nav_msgs::Path>("global_plan", 1);
00092 l_plan_pub_ = pn.advertise<nav_msgs::Path>("local_plan", 1);
00093
00094
00095
00096 ros::NodeHandle gn;
00097 odom_sub_ = gn.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&EBandPlannerROS::odomCallback, this, _1));
00098
00099
00100
00101
00102 eband_ = boost::shared_ptr<EBandPlanner>(new EBandPlanner(name, costmap_ros_));
00103
00104
00105 eband_trj_ctrl_ = boost::shared_ptr<EBandTrajectoryCtrl>(new EBandTrajectoryCtrl(name, costmap_ros_));
00106
00107
00108 eband_visual_ = boost::shared_ptr<EBandVisualization>(new EBandVisualization);
00109
00110
00111 eband_->setVisualization(eband_visual_);
00112
00113
00114 eband_trj_ctrl_->setVisualization(eband_visual_);
00115
00116
00117 eband_visual_->initialize(pn, costmap_ros);
00118
00119
00120
00121 initialized_ = true;
00122
00123
00124 ROS_DEBUG("Elastic Band plugin initialized.");
00125 }
00126 else
00127 {
00128 ROS_WARN("This planner has already been initialized, doing nothing.");
00129 }
00130 }
00131
00132
00133
00134 bool EBandPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
00135 {
00136
00137
00138 if(!initialized_)
00139 {
00140 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00141 return false;
00142 }
00143
00144
00145 global_plan_.clear();
00146 global_plan_ = orig_global_plan;
00147
00148
00149
00150 std::vector<int> start_end_counts (2, (int) global_plan_.size());
00151 if(!eband_local_planner::transformGlobalPlan(*tf_, global_plan_, *costmap_ros_, costmap_ros_->getGlobalFrameID(), transformed_plan_, start_end_counts))
00152 {
00153
00154 ROS_WARN("Could not transform the global plan to the frame of the controller");
00155 return false;
00156 }
00157
00158
00159 if(transformed_plan_.empty())
00160 {
00161
00162 ROS_WARN("Transformed plan is empty. Aborting local planner!");
00163 return false;
00164 }
00165
00166
00167 if(!eband_->setPlan(transformed_plan_))
00168 {
00169
00170
00171 costmap_ros_->resetLayers();
00172 if (!eband_->setPlan(transformed_plan_)) {
00173 ROS_ERROR("Setting plan to Elastic Band method failed!");
00174 return false;
00175 }
00176 }
00177 ROS_DEBUG("Global plan set to elastic band for optimization");
00178
00179
00180 plan_start_end_counter_ = start_end_counts;
00181
00182
00183 eband_->optimizeBand();
00184
00185
00186
00187 std::vector<eband_local_planner::Bubble> current_band;
00188 if(eband_->getBand(current_band))
00189 eband_visual_->publishBand("bubbles", current_band);
00190
00191
00192 goal_reached_ = false;
00193
00194 return true;
00195 }
00196
00197
00198 bool EBandPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
00199 {
00200
00201 if(!initialized_)
00202 {
00203 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00204 return false;
00205 }
00206
00207
00208
00209 tf::Stamped<tf::Pose> global_pose;
00210 geometry_msgs::PoseStamped global_pose_msg;
00211 std::vector<geometry_msgs::PoseStamped> tmp_plan;
00212
00213
00214 ROS_DEBUG("Reading current robot Position from costmap and appending it to elastic band.");
00215 if(!costmap_ros_->getRobotPose(global_pose))
00216 {
00217 ROS_WARN("Could not retrieve up to date robot pose from costmap for local planning.");
00218 return false;
00219 }
00220
00221
00222 tf::poseStampedTFToMsg(global_pose, global_pose_msg);
00223 tmp_plan.assign(1, global_pose_msg);
00224 eband_local_planner::AddAtPosition add_frames_at = add_front;
00225
00226
00227 if(!eband_->addFrames(tmp_plan, add_frames_at))
00228 {
00229 ROS_WARN("Could not connect robot pose to existing elastic band.");
00230 return false;
00231 }
00232
00233
00234 ROS_DEBUG("Checking for new path frames in moving window");
00235 std::vector<int> plan_start_end_counter = plan_start_end_counter_;
00236 std::vector<geometry_msgs::PoseStamped> append_transformed_plan;
00237
00238 if(!eband_local_planner::transformGlobalPlan(*tf_, global_plan_, *costmap_ros_, costmap_ros_->getGlobalFrameID(), transformed_plan_, plan_start_end_counter))
00239 {
00240
00241 ROS_WARN("Could not transform the global plan to the frame of the controller");
00242 return false;
00243 }
00244
00245
00246 if(transformed_plan_.empty())
00247 {
00248
00249 ROS_WARN("Transformed plan is empty. Aborting local planner!");
00250 return false;
00251 }
00252
00253 ROS_DEBUG("Retrieved start-end-counts are: (%d, %d)", plan_start_end_counter.at(0), plan_start_end_counter.at(1));
00254 ROS_DEBUG("Current start-end-counts are: (%d, %d)", plan_start_end_counter_.at(0), plan_start_end_counter_.at(1));
00255
00256
00257 append_transformed_plan.clear();
00258
00259 if(plan_start_end_counter_.at(1) > plan_start_end_counter.at(1))
00260 {
00261
00262 if(plan_start_end_counter_.at(1) > plan_start_end_counter.at(0))
00263 {
00264
00265 append_transformed_plan = transformed_plan_;
00266 }
00267 else
00268 {
00269
00270 int discarded_frames = plan_start_end_counter.at(0) - plan_start_end_counter_.at(1);
00271 ROS_ASSERT(transformed_plan_.begin() + discarded_frames + 1 >= transformed_plan_.begin());
00272 ROS_ASSERT(transformed_plan_.begin() + discarded_frames + 1 < transformed_plan_.end());
00273 append_transformed_plan.assign(transformed_plan_.begin() + discarded_frames + 1, transformed_plan_.end());
00274 }
00275
00276
00277 ROS_DEBUG("Adding %d new frames to current band", (int) append_transformed_plan.size());
00278 add_frames_at = add_back;
00279 if(eband_->addFrames(append_transformed_plan, add_back))
00280 {
00281
00282 ROS_DEBUG("Sucessfully added frames to band");
00283 plan_start_end_counter_ = plan_start_end_counter;
00284 }
00285 else {
00286 ROS_WARN("Failed to add frames to existing band");
00287 return false;
00288 }
00289 }
00290 else
00291 ROS_DEBUG("Nothing to add");
00292
00293
00294 ROS_DEBUG("Calling optimization method for elastic band");
00295 std::vector<eband_local_planner::Bubble> current_band;
00296 if(!eband_->optimizeBand())
00297 {
00298 ROS_WARN("Optimization failed - Band invalid - No controls availlable");
00299
00300 if(eband_->getBand(current_band))
00301 eband_visual_->publishBand("bubbles", current_band);
00302 return false;
00303 }
00304
00305
00306 eband_->getBand(current_band);
00307
00308 if(!eband_trj_ctrl_->setBand(current_band))
00309 {
00310 ROS_DEBUG("Failed to to set current band to Trajectory Controller");
00311 return false;
00312 }
00313
00314
00315 if(!eband_trj_ctrl_->setOdometry(base_odom_))
00316 {
00317 ROS_DEBUG("Failed to to set current odometry to Trajectory Controller");
00318 return false;
00319 }
00320
00321
00322 geometry_msgs::Twist cmd_twist;
00323 if(!eband_trj_ctrl_->getTwist(cmd_twist, goal_reached_))
00324 {
00325 ROS_DEBUG("Failed to calculate Twist from band in Trajectory Controller");
00326 return false;
00327 }
00328
00329
00330
00331 ROS_DEBUG("Retrieving velocity command: (%f, %f, %f)", cmd_twist.linear.x, cmd_twist.linear.y, cmd_twist.angular.z);
00332 cmd_vel = cmd_twist;
00333
00334
00335
00336 std::vector<geometry_msgs::PoseStamped> refined_plan;
00337 if(eband_->getPlan(refined_plan))
00338
00339 base_local_planner::publishPlan(refined_plan, g_plan_pub_);
00340
00341
00342
00343 if(eband_->getBand(current_band))
00344 eband_visual_->publishBand("bubbles", current_band);
00345
00346 return true;
00347 }
00348
00349
00350 bool EBandPlannerROS::isGoalReached()
00351 {
00352
00353 if(!initialized_)
00354 {
00355 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00356 return false;
00357 }
00358
00359 return goal_reached_;
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380
00381
00382 }
00383
00384
00385 void EBandPlannerROS::odomCallback(const nav_msgs::Odometry::ConstPtr& msg)
00386 {
00387
00388 boost::mutex::scoped_lock lock(odom_mutex_);
00389
00390
00391 base_odom_.twist.twist.linear.x = msg->twist.twist.linear.x;
00392 base_odom_.twist.twist.linear.y = msg->twist.twist.linear.y;
00393 base_odom_.twist.twist.angular.z = msg->twist.twist.angular.z;
00394 }
00395
00396
00397 }
00398
00399