Skip to content

Commit

Permalink
obsolete param
Browse files Browse the repository at this point in the history
  • Loading branch information
Thibault Kruse committed Apr 24, 2012
1 parent 8140c25 commit 55d9a47
Show file tree
Hide file tree
Showing 3 changed files with 0 additions and 6 deletions.
2 changes: 0 additions & 2 deletions dwa_local_planner/cfg/DWAPlanner.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@ gen.add("vx_samples", int_t, 0, "The number of samples to use when exploring the
gen.add("vy_samples", int_t, 0, "The number of samples to use when exploring the y velocity space", 10, 1)
gen.add("vth_samples", int_t, 0, "The number of samples to use when exploring the theta velocity space", 20, 1)

gen.add("penalize_negative_x", bool_t, 0, "Whether to penalize trajectories that have negative x velocities.", True)

gen.add("restore_defaults", bool_t,0, "Restore to the original configuration.", False)

exit(gen.generate(PACKAGE, "dwa_local_planner", "DWAPlanner"))
1 change: 0 additions & 1 deletion dwa_local_planner/include/dwa_local_planner/dwa_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,6 @@ namespace dwa_local_planner {
std::vector<geometry_msgs::PoseStamped> global_plan_;

boost::mutex configuration_mutex_;
bool penalize_negative_x_;
pcl::PointCloud<base_local_planner::MapGridCostPoint> traj_cloud_;
pcl_ros::Publisher<base_local_planner::MapGridCostPoint> traj_cloud_pub_;
bool publish_cost_grid_pc_; ///< @brief Whether or not to build and publish a PointCloud
Expand Down
3 changes: 0 additions & 3 deletions dwa_local_planner/src/dwa_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,6 @@ namespace dwa_local_planner {
vsamples_[1] = vy_samp;
vsamples_[2] = vth_samp;

penalize_negative_x_ = config.penalize_negative_x;

base_local_planner::LocalPlannerLimits limits;
limits.max_trans_vel = config.max_trans_vel;
limits.min_trans_vel = config.min_trans_vel;
Expand All @@ -131,7 +129,6 @@ namespace dwa_local_planner {
}

DWAPlanner::DWAPlanner(std::string name, tf::TransformListener* tf, costmap_2d::Costmap2DROS* costmap_ros) :
penalize_negative_x_(true),
obstacle_costs_(costmap_ros),
prefer_forward_costs_(0.0),
path_costs_(costmap_ros),
Expand Down

0 comments on commit 55d9a47

Please sign in to comment.