Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change default max of floating point to infinity from max #169

Draft
wants to merge 3 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions example/src/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
17 changes: 13 additions & 4 deletions example/test/descriptor_test_gtest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,12 @@ class DescriptorTest : public ::testing::Test {
std::make_shared<admittance_controller::ParamListener>(
example_test_node_->get_node_parameters_interface());
params_ = param_listener->get_params();
std::vector<std::string> names = {"admittance.damping_ratio", "one_number",
"pid.joint4.p", "lt_eq_fifteen",
"gt_fifteen"};
std::vector<std::string> names = {"admittance.damping_ratio",
"one_number",
"pid.joint4.p",
"lt_eq_fifteen",
"gt_fifteen",
"default_infinity"};
descriptors_ = example_test_node_->describe_parameters(names);
}

Expand All @@ -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<double>::max());
std::numeric_limits<double>::infinity());
}

TEST_F(DescriptorTest, check_lt_eq) {
Expand All @@ -89,6 +92,12 @@ TEST_F(DescriptorTest, check_gt) {
std::numeric_limits<int64_t>::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<double>::infinity());
}

int main(int argc, char** argv) {
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<double>::max();
descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits<double>::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<double>::lowest();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<double>::max();
descriptor.floating_point_range.at({{loop.index0}}).to_value = std::numeric_limits<double>::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<double>::lowest();
Expand Down
Loading