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 <dwa_local_planner/dwa_planner.h>
00038 #include <cmath>
00039
00040
00041 #include <queue>
00042
00043 #include <angles/angles.h>
00044
00045 #include <ros/ros.h>
00046
00047 namespace dwa_local_planner {
00048 void DWAPlanner::reconfigure(DWAPlannerConfig &config)
00049 {
00050
00051 boost::mutex::scoped_lock l(configuration_mutex_);
00052
00053 generator_.setParameters(
00054 config.sim_time,
00055 config.sim_granularity,
00056 config.angular_sim_granularity,
00057 config.use_dwa,
00058 sim_period_);
00059
00060 double resolution = planner_util_->getCostmap()->getResolution();
00061 pdist_scale_ = config.path_distance_bias;
00062
00063 path_costs_.setScale(resolution * pdist_scale_ * 0.5);
00064 alignment_costs_.setScale(resolution * pdist_scale_ * 0.5);
00065
00066 gdist_scale_ = config.goal_distance_bias;
00067 goal_costs_.setScale(resolution * gdist_scale_ * 0.5);
00068 goal_front_costs_.setScale(resolution * gdist_scale_ * 0.5);
00069
00070 occdist_scale_ = config.occdist_scale;
00071 obstacle_costs_.setScale(resolution * occdist_scale_);
00072
00073 stop_time_buffer_ = config.stop_time_buffer;
00074 oscillation_costs_.setOscillationResetDist(config.oscillation_reset_dist, config.oscillation_reset_angle);
00075 forward_point_distance_ = config.forward_point_distance;
00076 goal_front_costs_.setXShift(forward_point_distance_);
00077 alignment_costs_.setXShift(forward_point_distance_);
00078
00079
00080 obstacle_costs_.setParams(config.max_trans_vel, config.max_scaling_factor, config.scaling_speed);
00081
00082 int vx_samp, vy_samp, vth_samp;
00083 vx_samp = config.vx_samples;
00084 vy_samp = config.vy_samples;
00085 vth_samp = config.vth_samples;
00086
00087 if (vx_samp <= 0) {
00088 ROS_WARN("You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead");
00089 vx_samp = 1;
00090 config.vx_samples = vx_samp;
00091 }
00092
00093 if (vy_samp <= 0) {
00094 ROS_WARN("You've specified that you don't want any samples in the y dimension. We'll at least assume that you want to sample one value... so we're going to set vy_samples to 1 instead");
00095 vy_samp = 1;
00096 config.vy_samples = vy_samp;
00097 }
00098
00099 if (vth_samp <= 0) {
00100 ROS_WARN("You've specified that you don't want any samples in the th dimension. We'll at least assume that you want to sample one value... so we're going to set vth_samples to 1 instead");
00101 vth_samp = 1;
00102 config.vth_samples = vth_samp;
00103 }
00104
00105 vsamples_[0] = vx_samp;
00106 vsamples_[1] = vy_samp;
00107 vsamples_[2] = vth_samp;
00108
00109
00110 }
00111
00112 DWAPlanner::DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util) :
00113 planner_util_(planner_util),
00114 obstacle_costs_(planner_util->getCostmap()),
00115 path_costs_(planner_util->getCostmap()),
00116 goal_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
00117 goal_front_costs_(planner_util->getCostmap(), 0.0, 0.0, true),
00118 alignment_costs_(planner_util->getCostmap())
00119 {
00120 ros::NodeHandle private_nh("~/" + name);
00121
00122 goal_front_costs_.setStopOnFailure( false );
00123 alignment_costs_.setStopOnFailure( false );
00124
00125
00126
00127
00128 std::string controller_frequency_param_name;
00129 if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name)) {
00130 sim_period_ = 0.05;
00131 } else {
00132 double controller_frequency = 0;
00133 private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
00134 if(controller_frequency > 0) {
00135 sim_period_ = 1.0 / controller_frequency;
00136 } else {
00137 ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
00138 sim_period_ = 0.05;
00139 }
00140 }
00141 ROS_INFO("Sim period is set to %.2f", sim_period_);
00142
00143 oscillation_costs_.resetOscillationFlags();
00144
00145 private_nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
00146 map_viz_.initialize(name, boost::bind(&DWAPlanner::getCellCosts, this, _1, _2, _3, _4, _5, _6));
00147
00148 std::string frame_id;
00149 private_nh.param("global_frame_id", frame_id, std::string("odom"));
00150
00151 traj_cloud_.header.frame_id = frame_id;
00152 traj_cloud_pub_.advertise(private_nh, "trajectory_cloud", 1);
00153
00154
00155
00156 std::vector<base_local_planner::TrajectoryCostFunction*> critics;
00157 critics.push_back(&oscillation_costs_);
00158 critics.push_back(&obstacle_costs_);
00159 critics.push_back(&goal_front_costs_);
00160 critics.push_back(&alignment_costs_);
00161 critics.push_back(&path_costs_);
00162 critics.push_back(&goal_costs_);
00163
00164
00165 std::vector<base_local_planner::TrajectorySampleGenerator*> generator_list;
00166 generator_list.push_back(&generator_);
00167
00168 scored_sampling_planner_ = base_local_planner::SimpleScoredSamplingPlanner(generator_list, critics);
00169 }
00170
00171
00172 bool DWAPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
00173
00174 path_cost = path_costs_.getCellCosts(cx, cy);
00175 goal_cost = goal_costs_.getCellCosts(cx, cy);
00176 occ_cost = planner_util_->getCostmap()->getCost(cx, cy);
00177 if (path_cost == path_costs_.obstacleCosts() ||
00178 path_cost == path_costs_.unreachableCellCosts() ||
00179 occ_cost >= costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
00180 return false;
00181 }
00182
00183 double resolution = planner_util_->getCostmap()->getResolution();
00184 total_cost =
00185 pdist_scale_ * resolution * path_cost +
00186 gdist_scale_ * resolution * goal_cost +
00187 occdist_scale_ * occ_cost;
00188 return true;
00189 }
00190
00191 bool DWAPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
00192 oscillation_costs_.resetOscillationFlags();
00193 return planner_util_->setPlan(orig_global_plan);
00194 }
00195
00200 bool DWAPlanner::checkTrajectory(
00201 Eigen::Vector3f pos,
00202 Eigen::Vector3f vel,
00203 Eigen::Vector3f vel_samples){
00204 oscillation_costs_.resetOscillationFlags();
00205 base_local_planner::Trajectory traj;
00206 geometry_msgs::PoseStamped goal_pose = global_plan_.back();
00207 Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf::getYaw(goal_pose.pose.orientation));
00208 base_local_planner::LocalPlannerLimits limits = planner_util_->getCurrentLimits();
00209 generator_.initialise(pos,
00210 vel,
00211 goal,
00212 &limits,
00213 vsamples_);
00214 generator_.generateTrajectory(pos, vel, vel_samples, traj);
00215 double cost = scored_sampling_planner_.scoreTrajectory(traj, -1);
00216
00217 if(cost >= 0) {
00218 return true;
00219 }
00220 ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vel_samples[0], vel_samples[1], vel_samples[2], cost);
00221
00222
00223 return false;
00224 }
00225
00226
00227 void DWAPlanner::updatePlanAndLocalCosts(
00228 tf::Stamped<tf::Pose> global_pose,
00229 const std::vector<geometry_msgs::PoseStamped>& new_plan) {
00230 global_plan_.resize(new_plan.size());
00231 for (unsigned int i = 0; i < new_plan.size(); ++i) {
00232 global_plan_[i] = new_plan[i];
00233 }
00234
00235
00236 path_costs_.setTargetPoses(global_plan_);
00237
00238
00239 goal_costs_.setTargetPoses(global_plan_);
00240
00241
00242 geometry_msgs::PoseStamped goal_pose = global_plan_.back();
00243
00244 Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation()));
00245 double sq_dist =
00246 (pos[0] - goal_pose.pose.position.x) * (pos[0] - goal_pose.pose.position.x) +
00247 (pos[1] - goal_pose.pose.position.y) * (pos[1] - goal_pose.pose.position.y);
00248
00249
00250
00251
00252
00253
00254 std::vector<geometry_msgs::PoseStamped> front_global_plan = global_plan_;
00255 double angle_to_goal = atan2(goal_pose.pose.position.y - pos[1], goal_pose.pose.position.x - pos[0]);
00256 front_global_plan.back().pose.position.x = front_global_plan.back().pose.position.x +
00257 forward_point_distance_ * cos(angle_to_goal);
00258 front_global_plan.back().pose.position.y = front_global_plan.back().pose.position.y + forward_point_distance_ *
00259 sin(angle_to_goal);
00260
00261 goal_front_costs_.setTargetPoses(front_global_plan);
00262
00263
00264 if (sq_dist > forward_point_distance_ * forward_point_distance_ ) {
00265 alignment_costs_.setScale(1.0);
00266
00267 alignment_costs_.setTargetPoses(global_plan_);
00268 } else {
00269
00270 alignment_costs_.setScale(0.0);
00271 }
00272 }
00273
00274
00275
00276
00277
00278 base_local_planner::Trajectory DWAPlanner::findBestPath(
00279 tf::Stamped<tf::Pose> global_pose,
00280 tf::Stamped<tf::Pose> global_vel,
00281 tf::Stamped<tf::Pose>& drive_velocities,
00282 std::vector<geometry_msgs::Point> footprint_spec) {
00283
00284 obstacle_costs_.setFootprint(footprint_spec);
00285
00286
00287 boost::mutex::scoped_lock l(configuration_mutex_);
00288
00289 Eigen::Vector3f pos(global_pose.getOrigin().getX(), global_pose.getOrigin().getY(), tf::getYaw(global_pose.getRotation()));
00290 Eigen::Vector3f vel(global_vel.getOrigin().getX(), global_vel.getOrigin().getY(), tf::getYaw(global_vel.getRotation()));
00291 geometry_msgs::PoseStamped goal_pose = global_plan_.back();
00292 Eigen::Vector3f goal(goal_pose.pose.position.x, goal_pose.pose.position.y, tf::getYaw(goal_pose.pose.orientation));
00293 base_local_planner::LocalPlannerLimits limits = planner_util_->getCurrentLimits();
00294
00295
00296 generator_.initialise(pos,
00297 vel,
00298 goal,
00299 &limits,
00300 vsamples_);
00301
00302 result_traj_.cost_ = -7;
00303
00304 scored_sampling_planner_.findBestTrajectory(result_traj_, NULL);
00305
00306
00307 if (publish_cost_grid_pc_) {
00308
00309 map_viz_.publishCostCloud(*(planner_util_->getCostmap()));
00310 }
00311
00312
00313 oscillation_costs_.updateOscillationFlags(pos, &result_traj_, planner_util_->getCurrentLimits().min_trans_vel);
00314
00315
00316 if (result_traj_.cost_ < 0) {
00317 drive_velocities.setIdentity();
00318 } else {
00319 tf::Vector3 start(result_traj_.xv_, result_traj_.yv_, 0);
00320 drive_velocities.setOrigin(start);
00321 tf::Matrix3x3 matrix;
00322 matrix.setRotation(tf::createQuaternionFromYaw(result_traj_.thetav_));
00323 drive_velocities.setBasis(matrix);
00324 }
00325
00326 return result_traj_;
00327 }
00328 };