Skip to content

Commit

Permalink
Populate Range Constraints in Parameter Descriptors from Validation F…
Browse files Browse the repository at this point in the history
…unctions (PickNikRobotics#103)
  • Loading branch information
chancecardona authored Apr 12, 2023
1 parent 6e27f5c commit cea78d7
Show file tree
Hide file tree
Showing 8 changed files with 286 additions and 6 deletions.
6 changes: 6 additions & 0 deletions example/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,10 +37,16 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
# example_test_gtest
add_rostest_with_parameters_gtest(test_example_gtest test/example_test_gtest.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/example_params.yaml)
target_include_directories(test_example_gtest PRIVATE include)
target_link_libraries(test_example_gtest admittance_controller_parameters rclcpp::rclcpp)
# descriptor_test_gtest
add_rostest_with_parameters_gtest(test_descriptor_gtest test/descriptor_test_gtest.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/example_params.yaml)
target_include_directories(test_descriptor_gtest PRIVATE include)
target_link_libraries(test_descriptor_gtest admittance_controller_parameters rclcpp::rclcpp)

find_package(ament_cmake_gmock REQUIRED)
add_rostest_with_parameters_gmock(test_example_gmock test/example_test_gmock.cpp
Expand Down
18 changes: 17 additions & 1 deletion example/src/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ admittance_controller:
default_value: 1.0,
description: "proportional gain term",
validation: {
gt_eq<>: [ 0 ],
gt_eq<>: [ 0.0001 ],
}
}
i: {
Expand Down Expand Up @@ -242,6 +242,22 @@ admittance_controller:
default_value: false,
description: "if enabled, the velocity commanded to the admittance controller is added to its calculated admittance velocity"
}
lt_eq_fifteen: {
type: int,
default_value: 1,
description: "should be a number less than or equal to 15",
validation: {
lt_eq<>: [ 15 ],
}
}
gt_fifteen: {
type: int,
default_value: 16,
description: "should be a number greater than 15",
validation: {
gt<>: [ 15 ],
}
}
one_number: {
type: int,
default_value: 14540,
Expand Down
98 changes: 98 additions & 0 deletions example/test/descriptor_test_gtest.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
// Copyright 2023 Picknik Robotics
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the PickNik Inc. nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Author: Chance Cardona
//

#include "admittance_controller_parameters.hpp"
#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"

#include <limits>
#include <memory>

class DescriptorTest : public ::testing::Test {
public:
void SetUp() {
example_test_node_ = std::make_shared<rclcpp::Node>("example_test_node");

std::shared_ptr<admittance_controller::ParamListener> param_listener =
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"};
descriptors_ = example_test_node_->describe_parameters(names);
}

void TearDown() { example_test_node_.reset(); }

protected:
std::shared_ptr<rclcpp::Node> example_test_node_;
admittance_controller::Params params_;
std::vector<rcl_interfaces::msg::ParameterDescriptor> descriptors_;
};

// Checks element_bounds<> on a float
TEST_F(DescriptorTest, check_floating_point_descriptors) {
EXPECT_EQ(descriptors_[0].floating_point_range.at(0).from_value, 0.1);
EXPECT_EQ(descriptors_[0].floating_point_range.at(0).to_value, 10);
}

// Checks bounds<> on an int
TEST_F(DescriptorTest, check_integer_descriptors) {
EXPECT_EQ(descriptors_[1].integer_range.at(0).from_value, 1024);
EXPECT_EQ(descriptors_[1].integer_range.at(0).to_value, 65535);
}

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());
}

TEST_F(DescriptorTest, check_lt_eq) {
EXPECT_EQ(descriptors_[3].integer_range.at(0).from_value,
std::numeric_limits<int>::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<int>::max());
}

int main(int argc, char** argv) {
::testing::InitGoogleTest(&argc, argv);
rclcpp::init(argc, argv);
int result = RUN_ALL_TESTS();
rclcpp::shutdown();
return result;
}
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,37 @@ if (!parameters_interface_->has_parameter(prefix_ + "{{parameter_name}}")) {
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.description = "{{parameter_description}}";
descriptor.read_only = {{parameter_read_only}};
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if "DOUBLE" in parameter_type %}
{%- if validation.arguments|length == 2 %}
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 = {{validation.arguments[1]}};
{%- elif ("lower" in validation.function_name or "gt" in validation.function_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();
{%- elif ("upper" in validation.function_name or "lt" in validation.function_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<double>::lowest();
descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- endif %}
{%- elif "INTEGER" in parameter_type %}
{%- if validation.arguments|length == 2 %}
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 = {{validation.arguments[1]}};
{%- elif ("lower" in validation.function_name or "gt" in validation.function_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<int>::max();
{%- elif ("upper" in validation.function_name or "lt" in validation.function_name) and validation.arguments|length == 1 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int>::lowest();
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- endif %}
{%- endif %}
{%- endfor %}
{%- if not parameter_value|length %}
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
{% endif -%}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,37 @@ if (!parameters_interface_->has_parameter(param_name)) {
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.description = "{{parameter_description}}";
descriptor.read_only = {{parameter_read_only}};
{%- for validation in parameter_validations if ("bounds" in validation.function_name or "lt" in validation.function_name or "gt" in validation.function_name) %}
{%- if "DOUBLE" in parameter_type %}
{%- if validation.arguments|length == 2 %}
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 = {{validation.arguments[1]}};
{%- elif ("lower" in validation.function_name or "gt" in validation.function_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();
{%- elif ("upper" in validation.function_name or "lt" in validation.function_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<double>::lowest();
descriptor.floating_point_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- endif %}
{%- elif "INTEGER" in parameter_type %}
{%- if validation.arguments|length == 2 %}
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 = {{validation.arguments[1]}};
{%- elif ("lower" in validation.function_name or "gt" in validation.function_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<int>::max();
{%- elif ("upper" in validation.function_name or "lt" in validation.function_name) and validation.arguments|length == 1 %}
descriptor.integer_range.resize({{loop.index}});
descriptor.integer_range.at({{loop.index0}}).from_value = std::numeric_limits<int>::lowest();
descriptor.integer_range.at({{loop.index0}}).to_value = {{validation.arguments[0]}};
{%- endif %}
{%- endif %}
{%- endfor %}
{%- if not default_value|length %}
auto parameter = rclcpp::ParameterType::PARAMETER_{{parameter_type}};
{% endif -%}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <algorithm>
#include <array>
#include <functional>
#include <limits>
#include <mutex>
#include <rclcpp/node.hpp>
#include <rclcpp_lifecycle/lifecycle_node.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -647,10 +647,12 @@ def __init__(
code_gen_variable: CodeGenVariableBase,
parameter_description: str,
parameter_read_only: bool,
parameter_validations: list,
):
self.parameter_name = code_gen_variable.param_name
self.parameter_description = parameter_description
self.parameter_read_only = parameter_read_only
self.parameter_validations = parameter_validations
self.code_gen_variable = code_gen_variable


Expand All @@ -661,14 +663,15 @@ def __str__(self):
else:
self.parameter_value = self.parameter_name

parameter_validations = self.parameter_validations
data = {
"parameter_name": self.parameter_name,
"parameter_value": self.parameter_value,
"parameter_type": self.code_gen_variable.get_parameter_type(),
"parameter_description": self.parameter_description,
"parameter_read_only": bool_to_str(self.parameter_read_only),
"parameter_validations": parameter_validations,
}

j2_template = Template(GenerateCode.templates["declare_parameter"])
code = j2_template.render(data, trim_blocks=True)
return code
Expand All @@ -680,8 +683,14 @@ def __init__(
code_gen_variable: CodeGenVariableBase,
parameter_description: str,
parameter_read_only: bool,
parameter_validations: list,
):
super().__init__(code_gen_variable, parameter_description, parameter_read_only)
super().__init__(
code_gen_variable,
parameter_description,
parameter_read_only,
parameter_validations,
)
self.set_runtime_parameter = None
self.param_struct_instance = "updated_params"

Expand All @@ -695,7 +704,6 @@ def __str__(self):
"add_set_runtime_parameter was not called before str()"
)

# parameter_validations_str = "".join(str(x) for x in self.parameter_validations)
if self.code_gen_variable.default_value is None:
default_value = ""
else:
Expand All @@ -719,6 +727,7 @@ def __str__(self):
"param_struct_instance": self.param_struct_instance,
"parameter_field": parameter_field,
"default_value": default_value,
"parameter_validations": self.parameter_validations,
}

j2_template = Template(GenerateCode.templates["declare_runtime_parameter"])
Expand Down Expand Up @@ -873,13 +882,13 @@ def parse_params(self, name, value, nested_name_list):
param_name, parameter_conversion
)
declare_parameter = DeclareRuntimeParameter(
code_gen_variable, description, read_only
code_gen_variable, description, read_only, validations
)
declare_parameter.add_set_runtime_parameter(declare_parameter_set)
update_parameter = UpdateRuntimeParameter(param_name, parameter_conversion)
else:
declare_parameter = DeclareParameter(
code_gen_variable, description, read_only
code_gen_variable, description, read_only, validations
)
declare_parameter_set = SetParameter(param_name, parameter_conversion)
update_parameter = UpdateParameter(param_name, parameter_conversion)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
admittance_controller:
stiffness: {
type: double_array,
description: "specifies stiffness values for x, y, z, rx, ry, and rz used in the admittance calculation",
validation: {
element_bounds: [ 0.0001, 100000.0 ]
}
}
dankness: {
type: int_array,
description: "specifies stiffness values for x, y, z, rx, ry, and rz used in the admittance calculation",
validation: {
element_bounds: [ 1, 100 ]
}
}

mass: {
type: double_array,
description: "specifies mass values for x, y, z, rx, ry, and rz used in the admittance calculation",
validation: {
fixed_size<>: 6,
element_bounds<>: [ 0.0001, 1000000.0 ]
}
}

one_number: {
type: int,
default_value: 14540,
read_only: true,
validation: {
bounds<>: [ 1024, 65535 ]
}
}

p: {
type: double,
default_value: 1.0,
description: "proportional gain term",
validation: {
lower_bounds<>: [ 0 ],
}
}

p2: {
type: double,
default_value: 1.0,
description: "proportional gain term updated",
validation: {
gt_eq: [ 0.0001 ],
}
}

under_ten: {
type: double,
default_value: 1.0,
description: "should be a number less than 10",
validation: {
upper_bounds<>: [ 10 ],
}
}
lt_eq_fifteen: {
type: int,
default_value: 1,
description: "should be a number less than or equal to 15",
validation: {
lt_eq<>: [ 15 ],
}
}
gt_fifteen: {
type: int,
default_value: 16,
description: "should be a number greater than 15",
validation: {
gt<>: [ 15 ],
}
}

# general settings
enable_parameter_update_without_reactivation: {
type: bool,
default_value: true,
description: "if enabled, read_only parameters will be dynamically updated in the control loop"
}
use_feedforward_commanded_input: {
type: bool,
default_value: false,
description: "if enabled, the velocity commanded to the admittance controller is added to its calculated admittance velocity"
}

0 comments on commit cea78d7

Please sign in to comment.