Skip to content

Commit 833b8bd

Browse files
fixes #199
1 parent 0bc532a commit 833b8bd

File tree

3 files changed

+6
-6
lines changed

3 files changed

+6
-6
lines changed

example/test/descriptor_test_gtest.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -79,14 +79,14 @@ TEST_F(DescriptorTest, check_lower_upper_bounds) {
7979

8080
TEST_F(DescriptorTest, check_lt_eq) {
8181
EXPECT_EQ(descriptors_[3].integer_range.at(0).from_value,
82-
std::numeric_limits<int>::lowest());
82+
std::numeric_limits<int64_t>::lowest());
8383
EXPECT_EQ(descriptors_[3].integer_range.at(0).to_value, 15);
8484
}
8585

8686
TEST_F(DescriptorTest, check_gt) {
8787
EXPECT_EQ(descriptors_[4].integer_range.at(0).from_value, 15);
8888
EXPECT_EQ(descriptors_[4].integer_range.at(0).to_value,
89-
std::numeric_limits<int>::max());
89+
std::numeric_limits<int64_t>::max());
9090
}
9191

9292
int main(int argc, char** argv) {

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_parameter

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,10 +26,10 @@ descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[1
2626
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
2727
descriptor.integer_range.resize({{loop.index}});
2828
descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
29-
descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits<int>::max();
29+
descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits<int64_t>::max();
3030
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
3131
descriptor.integer_range.resize({{loop.index}});
32-
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int>::lowest();
32+
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int64_t>::lowest();
3333
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
3434
{%- endif %}
3535
{%- endif %}

generate_parameter_library_py/generate_parameter_library_py/jinja_templates/cpp/declare_runtime_parameter

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,10 +42,10 @@ descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[1
4242
{%- elif ("lower" in validation.function_name or "gt" == validation.function_base_name or "gt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
4343
descriptor.integer_range.resize({{loop.index}});
4444
descriptor.integer_range.at({{loop.index0}}).from_value = {{validation.arguments[0]}};
45-
descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits<int>::max();
45+
descriptor.integer_range.at({{loop.index0}}).to_value = std::numeric_limits<int64_t>::max();
4646
{%- elif ("upper" in validation.function_name or "lt" == validation.function_base_name or "lt_eq" == validation.function_base_name) and validation.arguments|length == 1 %}
4747
descriptor.integer_range.resize({{loop.index}});
48-
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int>::lowest();
48+
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int64_t>::lowest();
4949
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
5050
{%- endif %}
5151
{%- endif %}

0 commit comments

Comments
 (0)