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 <dwa_local_planner/dwa_planner_ros.h>
00039
00040 #include <Eigen/Core>
00041 #include <cmath>
00042
00043 #include <ros/console.h>
00044
00045 #include <pluginlib/class_list_macros.h>
00046
00047 #include <base_local_planner/goal_functions.h>
00048 #include <nav_msgs/Path.h>
00049
00050
00051 PLUGINLIB_EXPORT_CLASS( dwa_local_planner::DWAPlannerROS, nav_core::BaseLocalPlanner)
00052
00053 namespace dwa_local_planner {
00054
00055 void DWAPlannerROS::reconfigureCB(DWAPlannerConfig &config, uint32_t level) {
00056 if (setup_ && config.restore_defaults) {
00057 config = default_config_;
00058 config.restore_defaults = false;
00059 }
00060 if ( ! setup_) {
00061 default_config_ = config;
00062 setup_ = true;
00063 }
00064
00065
00066 base_local_planner::LocalPlannerLimits limits;
00067 limits.max_trans_vel = config.max_trans_vel;
00068 limits.min_trans_vel = config.min_trans_vel;
00069 limits.max_vel_x = config.max_vel_x;
00070 limits.min_vel_x = config.min_vel_x;
00071 limits.max_vel_y = config.max_vel_y;
00072 limits.min_vel_y = config.min_vel_y;
00073 limits.max_rot_vel = config.max_rot_vel;
00074 limits.min_rot_vel = config.min_rot_vel;
00075 limits.acc_lim_x = config.acc_lim_x;
00076 limits.acc_lim_y = config.acc_lim_y;
00077 limits.acc_lim_theta = config.acc_lim_theta;
00078 limits.acc_limit_trans = config.acc_limit_trans;
00079 limits.xy_goal_tolerance = config.xy_goal_tolerance;
00080 limits.yaw_goal_tolerance = config.yaw_goal_tolerance;
00081 limits.prune_plan = config.prune_plan;
00082 limits.trans_stopped_vel = config.trans_stopped_vel;
00083 limits.rot_stopped_vel = config.rot_stopped_vel;
00084 planner_util_.reconfigureCB(limits, config.restore_defaults);
00085
00086
00087 dp_->reconfigure(config);
00088 }
00089
00090 DWAPlannerROS::DWAPlannerROS() : initialized_(false),
00091 odom_helper_("odom") {
00092
00093 }
00094
00095 void DWAPlannerROS::initialize(
00096 std::string name,
00097 tf::TransformListener* tf,
00098 costmap_2d::Costmap2DROS* costmap_ros) {
00099 if (! isInitialized()) {
00100
00101 ros::NodeHandle private_nh("~/" + name);
00102 g_plan_pub_ = private_nh.advertise<nav_msgs::Path>("global_plan", 1);
00103 l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
00104 tf_ = tf;
00105 costmap_ros_ = costmap_ros;
00106 costmap_ros_->getRobotPose(current_pose_);
00107
00108
00109 costmap_ros_->getCostmapCopy(costmap_);
00110
00111 planner_util_.initialize(tf, &costmap_, costmap_ros_->getGlobalFrameID());
00112
00113
00114 dp_ = boost::shared_ptr<DWAPlanner>(new DWAPlanner(name, &planner_util_));
00115
00116 initialized_ = true;
00117
00118 dsrv_ = new dynamic_reconfigure::Server<DWAPlannerConfig>(private_nh);
00119 dynamic_reconfigure::Server<DWAPlannerConfig>::CallbackType cb = boost::bind(&DWAPlannerROS::reconfigureCB, this, _1, _2);
00120 dsrv_->setCallback(cb);
00121 }
00122 else{
00123 ROS_WARN("This planner has already been initialized, doing nothing.");
00124 }
00125 }
00126
00127 bool DWAPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
00128 if (! isInitialized()) {
00129 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00130 return false;
00131 }
00132
00133 latchedStopRotateController_.resetLatching();
00134
00135 ROS_INFO("Got new plan");
00136 return dp_->setPlan(orig_global_plan);
00137 }
00138
00139 bool DWAPlannerROS::isGoalReached() {
00140 if (! isInitialized()) {
00141 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00142 return false;
00143 }
00144 if ( ! costmap_ros_->getRobotPose(current_pose_)) {
00145 ROS_ERROR("Could not get robot pose");
00146 return false;
00147 }
00148 if(latchedStopRotateController_.isGoalReached(&planner_util_, odom_helper_, current_pose_)) {
00149 ROS_INFO("Goal reached");
00150 return true;
00151 } else {
00152 return false;
00153 }
00154 }
00155
00156 void DWAPlannerROS::publishLocalPlan(std::vector<geometry_msgs::PoseStamped>& path) {
00157 base_local_planner::publishPlan(path, l_plan_pub_);
00158 }
00159
00160
00161 void DWAPlannerROS::publishGlobalPlan(std::vector<geometry_msgs::PoseStamped>& path) {
00162 base_local_planner::publishPlan(path, g_plan_pub_);
00163 }
00164
00165 DWAPlannerROS::~DWAPlannerROS(){
00166
00167 delete dsrv_;
00168 }
00169
00170
00171
00172 bool DWAPlannerROS::dwaComputeVelocityCommands(tf::Stamped<tf::Pose> &global_pose, geometry_msgs::Twist& cmd_vel) {
00173
00174 if(! isInitialized()){
00175 ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00176 return false;
00177 }
00178
00179 tf::Stamped<tf::Pose> robot_vel;
00180 odom_helper_.getRobotVel(robot_vel);
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191 tf::Stamped<tf::Pose> drive_cmds;
00192 drive_cmds.frame_id_ = costmap_ros_->getBaseFrameID();
00193
00194 base_local_planner::Trajectory path = dp_->findBestPath(global_pose, robot_vel, drive_cmds, costmap_ros_->getRobotFootprint());
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206 cmd_vel.linear.x = drive_cmds.getOrigin().getX();
00207 cmd_vel.linear.y = drive_cmds.getOrigin().getY();
00208 cmd_vel.angular.z = tf::getYaw(drive_cmds.getRotation());
00209
00210
00211 std::vector<geometry_msgs::PoseStamped> local_plan;
00212 if(path.cost_ < 0) {
00213 ROS_DEBUG_NAMED("dwa_local_planner",
00214 "The dwa local planner failed to find a valid plan, cost functions discarded all candidates. This can mean there is an obstacle too close to the robot.");
00215 local_plan.clear();
00216 publishLocalPlan(local_plan);
00217 return false;
00218 }
00219
00220 ROS_DEBUG_NAMED("dwa_local_planner", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.",
00221 cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
00222
00223
00224 for(unsigned int i = 0; i < path.getPointsSize(); ++i) {
00225 double p_x, p_y, p_th;
00226 path.getPoint(i, p_x, p_y, p_th);
00227
00228 tf::Stamped<tf::Pose> p =
00229 tf::Stamped<tf::Pose>(tf::Pose(
00230 tf::createQuaternionFromYaw(p_th),
00231 tf::Point(p_x, p_y, 0.0)),
00232 ros::Time::now(),
00233 costmap_ros_->getGlobalFrameID());
00234 geometry_msgs::PoseStamped pose;
00235 tf::poseStampedTFToMsg(p, pose);
00236 local_plan.push_back(pose);
00237 }
00238
00239
00240
00241 publishLocalPlan(local_plan);
00242 return true;
00243 }
00244
00245
00246
00247
00248 bool DWAPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel) {
00249
00250 if ( ! costmap_ros_->getRobotPose(current_pose_)) {
00251 ROS_ERROR("Could not get robot pose");
00252 return false;
00253 }
00254 std::vector<geometry_msgs::PoseStamped> transformed_plan;
00255 if ( ! planner_util_.getLocalPlan(current_pose_, transformed_plan)) {
00256 ROS_ERROR("Could not get local plan");
00257 return false;
00258 }
00259
00260
00261 if(transformed_plan.empty()) {
00262 ROS_WARN_NAMED("dwa_local_planner", "Received an empty transformed plan.");
00263 return false;
00264 }
00265 ROS_DEBUG_NAMED("dwa_local_planner", "Received a transformed plan with %zu points.", transformed_plan.size());
00266
00267
00268 costmap_ros_->clearRobotFootprint();
00269
00270
00271 costmap_ros_->getCostmapCopy(costmap_);
00272
00273
00274 dp_->updatePlanAndLocalCosts(current_pose_, transformed_plan);
00275
00276 if (latchedStopRotateController_.isPositionReached(&planner_util_, current_pose_)) {
00277
00278 std::vector<geometry_msgs::PoseStamped> local_plan;
00279 std::vector<geometry_msgs::PoseStamped> transformed_plan;
00280 publishGlobalPlan(transformed_plan);
00281 publishLocalPlan(local_plan);
00282 base_local_planner::LocalPlannerLimits limits = planner_util_.getCurrentLimits();
00283 return latchedStopRotateController_.computeVelocityCommandsStopRotate(
00284 cmd_vel,
00285 limits.getAccLimits(),
00286 dp_->getSimPeriod(),
00287 &planner_util_,
00288 odom_helper_,
00289 current_pose_,
00290 boost::bind(&DWAPlanner::checkTrajectory, dp_, _1, _2, _3));
00291 } else {
00292 bool isOk = dwaComputeVelocityCommands(current_pose_, cmd_vel);
00293 if (isOk) {
00294 publishGlobalPlan(transformed_plan);
00295 } else {
00296 ROS_WARN_NAMED("dwa_local_planner", "DWA planner failed to produce path.");
00297 std::vector<geometry_msgs::PoseStamped> empty_plan;
00298 publishGlobalPlan(empty_plan);
00299 }
00300 return isOk;
00301 }
00302 }
00303
00304
00305 };