From 7b5d709310883e8323d275a660bbab95555465c2 Mon Sep 17 00:00:00 2001 From: Griswald Brooks Date: Sat, 13 Jan 2024 00:15:03 +0000 Subject: [PATCH 1/2] Change default max of floating point to infinity from max --- .gitignore | 1 + example/src/parameters.yaml | 8 ++++++++ example/test/descriptor_test_gtest.cpp | 10 ++++++++-- .../jinja_templates/cpp/declare_parameter | 2 +- .../jinja_templates/cpp/declare_runtime_parameter | 2 +- 5 files changed, 19 insertions(+), 4 deletions(-) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 00000000..a10efc01 --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +**__pycache__** diff --git a/example/src/parameters.yaml b/example/src/parameters.yaml index ac61e95f..fc908082 100644 --- a/example/src/parameters.yaml +++ b/example/src/parameters.yaml @@ -258,6 +258,14 @@ admittance_controller: 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 15db3153..2391c6f4 100644 --- a/example/test/descriptor_test_gtest.cpp +++ b/example/test/descriptor_test_gtest.cpp @@ -47,7 +47,7 @@ class DescriptorTest : public ::testing::Test { params_ = param_listener->get_params(); std::vector names = {"admittance.damping_ratio", "one_number", "pid.joint4.p", "lt_eq_fifteen", - "gt_fifteen"}; + "gt_fifteen", "default_infinity"}; descriptors_ = example_test_node_->describe_parameters(names); } @@ -74,7 +74,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 +89,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 45dcb61c..ca24c395 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 @@ -12,7 +12,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}}).to_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 b8916917..4ff14c02 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 @@ -16,7 +16,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}}).to_value = std::numeric_limits::lowest(); From 90bf1576cdfa62d17ae951b511af7573e3d30639 Mon Sep 17 00:00:00 2001 From: Griswald Brooks Date: Sat, 13 Jan 2024 15:54:38 +0000 Subject: [PATCH 2/2] Fix formatting --- example/test/descriptor_test_gtest.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/example/test/descriptor_test_gtest.cpp b/example/test/descriptor_test_gtest.cpp index 2391c6f4..edfb073d 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", "default_infinity"}; + 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); }