From 28b187098a6ed12e6fff2e4276cd2b1f365b4e61 Mon Sep 17 00:00:00 2001 From: Auguste Bourgois Date: Fri, 23 Aug 2024 17:58:00 +0200 Subject: [PATCH] Use int64_t instead of int for parameter integer range, fixes #199 (#214) --- example/test/descriptor_test_gtest.cpp | 4 ++-- .../jinja_templates/cpp/declare_parameter | 4 ++-- .../jinja_templates/cpp/declare_runtime_parameter | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/example/test/descriptor_test_gtest.cpp b/example/test/descriptor_test_gtest.cpp index 15db315..ee81f0b 100644 --- a/example/test/descriptor_test_gtest.cpp +++ b/example/test/descriptor_test_gtest.cpp @@ -79,14 +79,14 @@ TEST_F(DescriptorTest, check_lower_upper_bounds) { TEST_F(DescriptorTest, check_lt_eq) { EXPECT_EQ(descriptors_[3].integer_range.at(0).from_value, - std::numeric_limits::lowest()); + std::numeric_limits::lowest()); EXPECT_EQ(descriptors_[3].integer_range.at(0).to_value, 15); } TEST_F(DescriptorTest, check_gt) { EXPECT_EQ(descriptors_[4].integer_range.at(0).from_value, 15); EXPECT_EQ(descriptors_[4].integer_range.at(0).to_value, - std::numeric_limits::max()); + std::numeric_limits::max()); } int main(int argc, char** 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 5213ee8..ec57f65 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 @@ -26,10 +26,10 @@ descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[1 {%- 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.integer_range.resize({{loop.index}}); descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}}; -descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits::max(); +descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits::max(); {%- 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.integer_range.resize({{loop.index}}); -descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits::lowest(); +descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits::lowest(); descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}}; {%- endif %} {%- endif %} 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 026bb6d..cc8246e 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 @@ -42,10 +42,10 @@ descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[1 {%- 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.integer_range.resize({{loop.index}}); descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}}; -descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits::max(); +descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits::max(); {%- 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.integer_range.resize({{loop.index}}); -descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits::lowest(); +descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits::lowest(); descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}}; {%- endif %} {%- endif %}