Skip to content

Commit 226ea4a

Browse files
Skip callback if saturation parameter is not declared (#397) (#398)
(cherry picked from commit 0336ef4) Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent 06752a4 commit 226ea4a

File tree

1 file changed

+15
-1
lines changed

1 file changed

+15
-1
lines changed

control_toolbox/src/pid_ros.cpp

Lines changed: 15 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -570,7 +570,21 @@ void PidROS::set_parameter_event_callback()
570570
// The saturation parameter is special, it can change the u_min and u_max parameters
571571
// so we need to check it first and then proceed with the loop, as if we update only one
572572
// parameter, we need to keep this logic up-to-date. So, do not move it inside the loop
573-
bool saturation = node_params_->get_parameter(param_prefix_ + "saturation").get_value<bool>();
573+
bool saturation = true; // default value
574+
try
575+
{
576+
// we can't use get_parameter_or, because we don't have access to a rclcpp::Node
577+
if (node_params_->has_parameter(param_prefix_ + "saturation"))
578+
{
579+
saturation = node_params_->get_parameter(param_prefix_ + "saturation").get_value<bool>();
580+
}
581+
}
582+
catch (const std::exception & e)
583+
{
584+
RCLCPP_ERROR_STREAM(
585+
node_logging_->get_logger(), "Error with saturation parameter: " << e.what());
586+
}
587+
574588
std::for_each(
575589
parameters.begin(), parameters.end(),
576590
[&, this](const rclcpp::Parameter & parameter)

0 commit comments

Comments
 (0)