Skip to content

Commit 9f6c2c7

Browse files
committed
re-enable ParameterMutationRecursionGuard.
Signed-off-by: Tomoya Fujita <[email protected]>
1 parent 9b0881b commit 9f6c2c7

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -579,7 +579,7 @@ NodeParameters::declare_parameter(
579579
bool ignore_override)
580580
{
581581
std::lock_guard<std::recursive_mutex> lock(mutex_);
582-
// ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
582+
ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
583583

584584
return declare_parameter_helper(
585585
name,
@@ -604,7 +604,7 @@ NodeParameters::declare_parameter(
604604
bool ignore_override)
605605
{
606606
std::lock_guard<std::recursive_mutex> lock(mutex_);
607-
// ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
607+
ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
608608

609609
if (rclcpp::PARAMETER_NOT_SET == type) {
610610
throw std::invalid_argument{
@@ -696,7 +696,7 @@ NodeParameters::set_parameters_atomically(const std::vector<rclcpp::Parameter> &
696696
{
697697
std::lock_guard<std::recursive_mutex> lock(mutex_);
698698

699-
// ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
699+
ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
700700

701701
rcl_interfaces::msg::SetParametersResult result;
702702

0 commit comments

Comments
 (0)