diff --git a/example/src/parameters.yaml b/example/src/parameters.yaml index 7836c8e..64f8e3d 100644 --- a/example/src/parameters.yaml +++ b/example/src/parameters.yaml @@ -233,6 +233,14 @@ admittance_controller: description: "should be a number greater than 15" validation: gt<>: [ 15 ] + default_infinity: { + type: double, + default_value: .inf, + description: "should be a number greater than zero, which should include infinity", + validation: { + gt_eq<>: [ 0 ], + } + } one_number: type: int default_value: 14540 diff --git a/example/test/descriptor_test_gtest.cpp b/example/test/descriptor_test_gtest.cpp index ee81f0b..60ded6a 100644 --- a/example/test/descriptor_test_gtest.cpp +++ b/example/test/descriptor_test_gtest.cpp @@ -45,9 +45,12 @@ class DescriptorTest : public ::testing::Test { std::make_shared( example_test_node_->get_node_parameters_interface()); params_ = param_listener->get_params(); - std::vector names = {"admittance.damping_ratio", "one_number", - "pid.joint4.p", "lt_eq_fifteen", - "gt_fifteen"}; + std::vector names = {"admittance.damping_ratio", + "one_number", + "pid.joint4.p", + "lt_eq_fifteen", + "gt_fifteen", + "default_infinity"}; descriptors_ = example_test_node_->describe_parameters(names); } @@ -74,7 +77,7 @@ TEST_F(DescriptorTest, check_integer_descriptors) { TEST_F(DescriptorTest, check_lower_upper_bounds) { EXPECT_EQ(descriptors_[2].floating_point_range.at(0).from_value, 0.0001); EXPECT_EQ(descriptors_[2].floating_point_range.at(0).to_value, - std::numeric_limits::max()); + std::numeric_limits::infinity()); } TEST_F(DescriptorTest, check_lt_eq) { @@ -89,6 +92,12 @@ TEST_F(DescriptorTest, check_gt) { std::numeric_limits::max()); } +TEST_F(DescriptorTest, default_infinity) { + EXPECT_EQ(descriptors_[5].floating_point_range.at(0).from_value, 0.0); + EXPECT_EQ(descriptors_[5].floating_point_range.at(0).to_value, + std::numeric_limits::infinity()); +} + int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); rclcpp::init(argc, argv); diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter index 51e4fb4..6ebb653 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter @@ -15,7 +15,7 @@ descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.argu {%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %} descriptor.floating_point_range.resize({{loop.index}}); descriptor.floating_point_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}}; -descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits::max(); +descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits::infinity(); {%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %} descriptor.floating_point_range.resize({{loop.index}}); descriptor.floating_point_range.at({{loop.index0}}).from_value = std::numeric_limits::lowest(); diff --git a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter index 625a842..2c67e33 100644 --- a/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter +++ b/generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter @@ -31,7 +31,7 @@ descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.argu {%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %} descriptor.floating_point_range.resize({{loop.index}}); descriptor.floating_point_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}}; -descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits::max(); +descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits::infinity(); {%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %} descriptor.floating_point_range.resize({{loop.index}}); descriptor.floating_point_range.at({{loop.index0}}).from_value = std::numeric_limits::lowest();