Skip to content

Commit ee719c9

Browse files
authored
Fix uninitialized variable warnings and change default value (#1728)
* Fix uninitialized warning for variable temp_tf_tol. * Change default GridBased.tolerance to 0.5 meters
1 parent 3cf9223 commit ee719c9

File tree

5 files changed

+5
-5
lines changed

5 files changed

+5
-5
lines changed

‎nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@ planner_server:
187187
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
188188
planner_plugin_ids: ["GridBased"]
189189
use_sim_time: True
190-
GridBased.tolerance: 2.0
190+
GridBased.tolerance: 0.5
191191
GridBased.use_astar: false
192192
GridBased.allow_unknown: true
193193

‎nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@ planner_server:
187187
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
188188
planner_plugin_ids: ["GridBased"]
189189
use_sim_time: True
190-
GridBased.tolerance: 2.0
190+
GridBased.tolerance: 0.5
191191
GridBased.use_astar: false
192192
GridBased.allow_unknown: true
193193

‎nav2_bringup/bringup/params/nav2_params.yaml‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -232,7 +232,7 @@ planner_server:
232232
planner_plugin_types: ["nav2_navfn_planner/NavfnPlanner"]
233233
planner_plugin_ids: ["GridBased"]
234234
use_sim_time: True
235-
GridBased.tolerance: 2.0
235+
GridBased.tolerance: 0.5
236236
GridBased.use_astar: false
237237
GridBased.allow_unknown: true
238238

‎nav2_costmap_2d/plugins/static_layer.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ void
117117
StaticLayer::getParameters()
118118
{
119119
int temp_lethal_threshold = 0;
120-
double temp_tf_tol;
120+
double temp_tf_tol = 0.0;
121121

122122
declareParameter("enabled", rclcpp::ParameterValue(true));
123123
declareParameter("subscribe_to_updates", rclcpp::ParameterValue(false));

‎nav2_navfn_planner/src/navfn_planner.cpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ NavfnPlanner::configure(
7272

7373
// Initialize parameters
7474
// Declare this plugin's parameters
75-
declare_parameter_if_not_declared(node_, name + ".tolerance", rclcpp::ParameterValue(2.0));
75+
declare_parameter_if_not_declared(node_, name + ".tolerance", rclcpp::ParameterValue(0.5));
7676
node_->get_parameter(name + ".tolerance", tolerance_);
7777
declare_parameter_if_not_declared(node_, name + ".use_astar", rclcpp::ParameterValue(false));
7878
node_->get_parameter(name + ".use_astar", use_astar_);

0 commit comments

Comments
 (0)