Skip to content

Commit

Permalink
Fix uninitialized variable warnings and change default value (#1728)
Browse files Browse the repository at this point in the history
* Fix uninitialized warning for variable temp_tf_tol.

* Change default GridBased.tolerance to 0.5 meters
  • Loading branch information
QQting committed May 14, 2020
1 parent 3cf9223 commit ee719c9
Show file tree
Hide file tree
Showing 5 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ planner_server:
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
planner_plugin_ids: ["GridBased"]
use_sim_time: True
GridBased.tolerance: 2.0
GridBased.tolerance: 0.5
GridBased.use_astar: false
GridBased.allow_unknown: true

Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ planner_server:
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
planner_plugin_ids: ["GridBased"]
use_sim_time: True
GridBased.tolerance: 2.0
GridBased.tolerance: 0.5
GridBased.use_astar: false
GridBased.allow_unknown: true

Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ planner_server:
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
planner_plugin_ids: ["GridBased"]
use_sim_time: True
GridBased.tolerance: 2.0
GridBased.tolerance: 0.5
GridBased.use_astar: false
GridBased.allow_unknown: true

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ void
StaticLayer::getParameters()
{
int temp_lethal_threshold = 0;
double temp_tf_tol;
double temp_tf_tol = 0.0;

declareParameter("enabled", rclcpp::ParameterValue(true));
declareParameter("subscribe_to_updates", rclcpp::ParameterValue(false));
Expand Down
2 changes: 1 addition & 1 deletion nav2_navfn_planner/src/navfn_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ NavfnPlanner::configure(

// Initialize parameters
// Declare this plugin's parameters
declare_parameter_if_not_declared(node_, name + ".tolerance", rclcpp::ParameterValue(2.0));
declare_parameter_if_not_declared(node_, name + ".tolerance", rclcpp::ParameterValue(0.5));
node_->get_parameter(name + ".tolerance", tolerance_);
declare_parameter_if_not_declared(node_, name + ".use_astar", rclcpp::ParameterValue(false));
node_->get_parameter(name + ".use_astar", use_astar_);
Expand Down

0 comments on commit ee719c9

Please sign in to comment.