Skip to content

Commit b52d21a

Browse files
committed
check before redeclaring the parameter
1 parent 71f8f3e commit b52d21a

File tree

1 file changed

+12
-1
lines changed

1 file changed

+12
-1
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 12 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -592,7 +592,18 @@ void ControllerManager::initialize_parameters()
592592
try
593593
{
594594
use_sim_time_ = this->get_parameter("use_sim_time").as_bool();
595-
this->declare_parameter("overruns.print_warnings", !use_sim_time_);
595+
596+
if (!this->has_parameter("overruns.print_warnings"))
597+
{
598+
rcl_interfaces::msg::ParameterDescriptor descriptor;
599+
descriptor.description =
600+
"If true, the controller manager will print a warning message to the console if an overrun "
601+
"is detected in its real-time loop (read, update and write). By default, it is set to "
602+
"true, except when used with use_sim_time parameter set to true.";
603+
descriptor.read_only = false;
604+
auto parameter = rclcpp::ParameterValue(!use_sim_time_);
605+
this->declare_parameter("overruns.print_warnings", parameter, descriptor);
606+
}
596607
cm_param_listener_ = std::make_shared<controller_manager::ParamListener>(
597608
this->get_node_parameters_interface(), this->get_logger());
598609
params_ = std::make_shared<controller_manager::Params>(cm_param_listener_->get_params());

0 commit comments

Comments
 (0)