File tree Expand file tree Collapse file tree 1 file changed +12
-1
lines changed Expand file tree Collapse file tree 1 file changed +12
-1
lines changed Original file line number Diff line number Diff line change @@ -592,7 +592,18 @@ void ControllerManager::initialize_parameters()
592
592
try
593
593
{
594
594
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
+ }
596
607
cm_param_listener_ = std::make_shared<controller_manager::ParamListener>(
597
608
this ->get_node_parameters_interface (), this ->get_logger ());
598
609
params_ = std::make_shared<controller_manager::Params>(cm_param_listener_->get_params ());
You can’t perform that action at this time.
0 commit comments