Skip to content

Commit

Permalink
Check if parameter is already declared to avoid re-declaring it. (#227)
Browse files Browse the repository at this point in the history
* Check if parameter is already declared to avoid re-declaring it.

A parameter can only be declared once. When implementing a LicecycleNode
one would normally do all the initialization in `on_configure()` and the
cleanup, deinitialization in the `on_cleanup` method. Furthermore, these
transitions could potentially be called multiple times, depending on how
the node is t ransitioned from the lifecycles are triggered. However,
this approach doesn't currently work well with Diagnostics since, in the
constructor, of `diagnostic_updater::Updater` it's declaring a static
parameter without checking whether that parameter has already been
declared. In subsequent calls to `on_configure` (and thus,
if Diagnostics are initialized there, in subsequent calls to the
`Updater` constructor, this results in the following message:

```
Original error: parameter 'diagnostic_updater.period' has already been declared
```

To avoid this, until the Foxy version, the wrapper code could explicitly
call `undeclare_parameter` on the parameter that the `Updater` is
declaring, but as of Galactic, undeclaring a static parameter is not
allowed anymore. See e.g., ros2/rclcpp#1850.

In this commit, I'm checking explicitly if the parameter has already
been registered and if so, I'm just reading its value before attempting
to re-declare it.

* Replaced try-catch with has_parameter check.

Co-authored-by: Nikos Koukis <nikolaos@slamcore.com>
Co-authored-by: Ralph Lange <ralph-lange@users.noreply.github.com>
  • Loading branch information
3 people committed Nov 12, 2022
1 parent 0d2c532 commit 5c9fc46
Showing 1 changed file with 9 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -394,8 +394,15 @@ class Updater : public DiagnosticTaskVector
node_name_(base_interface->get_name()),
warn_nohwid_done_(false)
{
period = parameters_interface->declare_parameter(
"diagnostic_updater.period", rclcpp::ParameterValue(period)).get<double>();
constexpr const char * period_param_name = "diagnostic_updater.period";
rclcpp::ParameterValue period_param;
if (parameters_interface->has_parameter(period_param_name)) {
period_param = parameters_interface->get_parameter(period_param_name).get_parameter_value();
} else {
period_param = parameters_interface->declare_parameter(
period_param_name, rclcpp::ParameterValue(period));
}
period = period_param.get<double>();
period_ = rclcpp::Duration::from_seconds(period);

reset_timer();
Expand Down

0 comments on commit 5c9fc46

Please sign in to comment.