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