Skip to content

Commit

Permalink
Only get parameter if it is set
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz authored and wjwwood committed Oct 12, 2018
1 parent ffa4ae4 commit 886bb52
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,8 +363,12 @@ NodeParameters::get_parameter(
{
std::lock_guard<std::mutex> lock(mutex_);

if (parameters_.count(name)) {
parameter = {name, parameters_.at(name).value};
auto param_iter = parameters_.find(name);
if (
parameters_.end() != param_iter &&
param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
{
parameter = {name, param_iter->second.value};
return true;
} else {
return false;
Expand Down

0 comments on commit 886bb52

Please sign in to comment.