Skip to content

Commit

Permalink
minor updates to parameter loading
Browse files Browse the repository at this point in the history
  • Loading branch information
matemat13 committed Sep 9, 2024
1 parent 9e531b3 commit 0b34026
Showing 1 changed file with 14 additions and 18 deletions.
32 changes: 14 additions & 18 deletions include/fog_lib/params.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,11 @@ namespace fog_lib
RCLCPP_ERROR_STREAM(node.get_logger(), "Could not load param '" << param_name << "': " << e.what());
return false;
}
catch (const rclcpp::exceptions::UninitializedStaticallyTypedParameterException& e)
{
RCLCPP_ERROR_STREAM(node.get_logger(), "Could not load param '" << param_name << "': " << e.what());
return false;
}
return true;
}

Expand All @@ -48,30 +53,21 @@ namespace fog_lib
RCLCPP_ERROR_STREAM(node.get_logger(), "Could not load param '" << param_name << "': " << e.what());
return false;
}
catch (const rclcpp::exceptions::UninitializedStaticallyTypedParameterException& e)
{
RCLCPP_ERROR_STREAM(node.get_logger(), "Could not load param '" << param_name << "': " << e.what());
return false;
}
return true;
}

bool parse_param(const std::string& param_name, rclcpp::Duration& param_dest, rclcpp::Node& node)
{
try
{
using T = double;
#ifdef ROS_FOXY
node.declare_parameter(param_name); // for Foxy
#else
node.declare_parameter<T>(param_name); // for Galactic and newer
#endif
T tmp;
node.get_parameter(param_name, tmp);
double tmp;
const bool ok_out = parse_param<double>(param_name, tmp, node);
if (ok_out)
param_dest = rclcpp::Duration::from_seconds(tmp);
RCLCPP_INFO_STREAM(node.get_logger(), "Loaded '" << param_name << "' = " << tmp << "s");
}
catch (const rclcpp::ParameterTypeException& e)
{
RCLCPP_ERROR_STREAM(node.get_logger(), "Could not load param '" << param_name << "': " << e.what());
return false;
}
return true;
return ok_out;
}

template <class T>
Expand Down

0 comments on commit 0b34026

Please sign in to comment.