forked from PickNikRobotics/generate_parameter_library
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Populate Range Constraints in Parameter Descriptors from Validation F…
…unctions (PickNikRobotics#103)
- Loading branch information
1 parent
6e27f5c
commit cea78d7
Showing
8 changed files
with
286 additions
and
6 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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; | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
88 changes: 88 additions & 0 deletions
88
...e_parameter_library_py/generate_parameter_library_py/test/validation_only_parameters.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
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" | ||
} |