Skip to content

Commit

Permalink
Initialize variabes to avoid errors during build (ros-navigation#1654)
Browse files Browse the repository at this point in the history
Signed-off-by: Pablo Vega <epvega@gmail.com>
  • Loading branch information
p-vega authored Apr 25, 2020
1 parent 5fd07b4 commit a0279a1
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion nav2_controller/src/progress_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ ProgressChecker::ProgressChecker(const rclcpp_lifecycle::LifecycleNode::SharedPt
nh_, "movement_time_allowance", rclcpp::ParameterValue(10.0));
// Scale is set to 0 by default, so if it was not set otherwise, set to 0
nh_->get_parameter_or("required_movement_radius", radius_, 0.5);
double time_allowance_param;
double time_allowance_param = 0.0;
nh_->get_parameter_or("movement_time_allowance", time_allowance_param, 10.0);
time_allowance_ = rclcpp::Duration::from_seconds(time_allowance_param);
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_core/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ DWBPublisher::on_configure()
marker_pub_ = node_->create_publisher<visualization_msgs::msg::MarkerArray>("marker", 1);
cost_grid_pc_pub_ = node_->create_publisher<sensor_msgs::msg::PointCloud>("cost_cloud", 1);

double marker_lifetime;
double marker_lifetime = 0.0;
node_->get_parameter(plugin_name_ + ".marker_lifetime", marker_lifetime);
marker_lifetime_ = rclcpp::Duration::from_seconds(marker_lifetime);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ param_t searchAndGetParam(
// nh->param(resolved_name, value, default_value);
// return value;
// }
param_t value;
param_t value = 0;
nav2_util::declare_parameter_if_not_declared(
nh, param_name,
rclcpp::ParameterValue(default_value));
Expand Down Expand Up @@ -147,7 +147,7 @@ void moveParameter(
const nav2_util::LifecycleNode::SharedPtr & nh, std::string old_name,
std::string current_name, param_t default_value, bool should_delete = true)
{
param_t value;
param_t value = 0;
if (nh->get_parameter(current_name, value)) {
if (should_delete) {nh->undeclare_parameter(old_name);}
return;
Expand Down

0 comments on commit a0279a1

Please sign in to comment.