diff --git a/control_toolbox/src/pid_ros.cpp b/control_toolbox/src/pid_ros.cpp index 84dbeabd..2654b580 100644 --- a/control_toolbox/src/pid_ros.cpp +++ b/control_toolbox/src/pid_ros.cpp @@ -274,9 +274,18 @@ bool PidROS::initialize_from_ros_parameters() all_params_available &= get_double_param(param_prefix_ + "tracking_time_constant", tracking_time_constant); + bool saturation = std::isfinite(u_max) || std::isfinite(u_min); + get_boolean_param(param_prefix_ + "saturation", saturation); + if (!saturation) + { + u_max = UMAX_INFINITY; + u_min = -UMAX_INFINITY; + } get_boolean_param(param_prefix_ + "antiwindup", antiwindup); get_string_param(param_prefix_ + "antiwindup_strategy", antiwindup_strat_str); declare_param(param_prefix_ + "save_i_term", rclcpp::ParameterValue(false)); + declare_param( + param_prefix_ + "activate_state_publisher", rclcpp::ParameterValue(rt_state_pub_ != nullptr)); if (all_params_available) { @@ -385,7 +394,9 @@ bool PidROS::initialize_from_args( rclcpp::ParameterValue(antiwindup_strat.tracking_time_constant)); declare_param( param_prefix_ + "error_deadband", rclcpp::ParameterValue(antiwindup_strat.error_deadband)); - declare_param(param_prefix_ + "saturation", rclcpp::ParameterValue(true)); + declare_param( + param_prefix_ + "saturation", + rclcpp::ParameterValue(std::isfinite(gains.u_max_) || std::isfinite(gains.u_min_))); declare_param( param_prefix_ + "antiwindup_strategy", rclcpp::ParameterValue(gains.antiwindup_strat_.to_string())); diff --git a/control_toolbox/test/pid_ros_parameters_tests.cpp b/control_toolbox/test/pid_ros_parameters_tests.cpp index 127ad6ba..6c39f3f5 100644 --- a/control_toolbox/test/pid_ros_parameters_tests.cpp +++ b/control_toolbox/test/pid_ros_parameters_tests.cpp @@ -605,42 +605,50 @@ TEST(PidParametersTest, GetParametersTest) TEST(PidParametersTest, GetParametersFromParams) { rclcpp::Node::SharedPtr node = std::make_shared("pid_parameters_test"); - - TestablePidROS pid(node, "", "", false); + const bool ACTIVATE_STATE_PUBLISHER = false; + TestablePidROS pid(node, "", "", ACTIVATE_STATE_PUBLISHER); ASSERT_FALSE(pid.initialize_from_ros_parameters()); rclcpp::Parameter param_p; ASSERT_TRUE(node->get_parameter("p", param_p)); - ASSERT_TRUE(std::isnan(param_p.get_value())); + EXPECT_TRUE(std::isnan(param_p.get_value())); rclcpp::Parameter param_i; ASSERT_TRUE(node->get_parameter("i", param_i)); - ASSERT_TRUE(std::isnan(param_i.get_value())); + EXPECT_TRUE(std::isnan(param_i.get_value())); rclcpp::Parameter param_d; ASSERT_TRUE(node->get_parameter("d", param_d)); - ASSERT_TRUE(std::isnan(param_d.get_value())); + EXPECT_TRUE(std::isnan(param_d.get_value())); rclcpp::Parameter param_i_clamp_max; ASSERT_TRUE(node->get_parameter("i_clamp_max", param_i_clamp_max)); - ASSERT_TRUE(std::isnan(param_i_clamp_max.get_value())); + EXPECT_TRUE(std::isnan(param_i_clamp_max.get_value())); rclcpp::Parameter param_i_clamp_min; ASSERT_TRUE(node->get_parameter("i_clamp_min", param_i_clamp_min)); - ASSERT_TRUE(std::isnan(param_i_clamp_min.get_value())); + EXPECT_TRUE(std::isnan(param_i_clamp_min.get_value())); rclcpp::Parameter param_u_clamp_max; ASSERT_TRUE(node->get_parameter("u_clamp_max", param_u_clamp_max)); - ASSERT_TRUE(std::isinf(param_u_clamp_max.get_value())); + EXPECT_TRUE(std::isinf(param_u_clamp_max.get_value())); rclcpp::Parameter param_u_clamp_min; ASSERT_TRUE(node->get_parameter("u_clamp_min", param_u_clamp_min)); - ASSERT_TRUE(std::isinf(param_u_clamp_min.get_value())); + EXPECT_TRUE(std::isinf(param_u_clamp_min.get_value())); + + rclcpp::Parameter param_saturation; + ASSERT_TRUE(node->get_parameter("saturation", param_saturation)); + EXPECT_FALSE(param_saturation.get_value()); rclcpp::Parameter param_tracking_time_constant; ASSERT_TRUE(node->get_parameter("tracking_time_constant", param_tracking_time_constant)); - ASSERT_TRUE(std::isnan(param_tracking_time_constant.get_value())); + EXPECT_TRUE(std::isnan(param_tracking_time_constant.get_value())); + + rclcpp::Parameter param_activate_state_publisher; + ASSERT_TRUE(node->get_parameter("activate_state_publisher", param_activate_state_publisher)); + EXPECT_EQ(param_activate_state_publisher.get_value(), ACTIVATE_STATE_PUBLISHER); } TEST(PidParametersTest, MultiplePidInstances)