Skip to content

Commit

Permalink
remove previously deprecated param
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson committed Mar 14, 2015
1 parent b2a83c3 commit d9e701e
Showing 1 changed file with 1 addition and 8 deletions.
9 changes: 1 addition & 8 deletions base_local_planner/src/trajectory_planner_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,14 +119,7 @@ namespace base_local_planner {
private_nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.10);
private_nh.param("acc_lim_x", acc_lim_x_, 2.5);
private_nh.param("acc_lim_y", acc_lim_y_, 2.5);
//this was improperly set as acc_lim_th -- TODO: remove this when we get to J turtle
acc_lim_theta_ = 3.2;
if (private_nh.hasParam("acc_lim_th"))
{
ROS_WARN("%s/acc_lim_th should be acc_lim_theta, this param will be removed in J-turtle", private_nh.getNamespace().c_str());
private_nh.param("acc_lim_th", acc_lim_theta_, 3.2);
}
private_nh.param("acc_lim_theta", acc_lim_theta_, acc_lim_theta_);
private_nh.param("acc_lim_theta", acc_lim_theta_, 3.2);

private_nh.param("stop_time_buffer", stop_time_buffer, 0.2);

Expand Down

0 comments on commit d9e701e

Please sign in to comment.