-
Notifications
You must be signed in to change notification settings - Fork 99
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
0eda373
commit b4cfba4
Showing
4 changed files
with
172 additions
and
0 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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,87 @@ | ||
// Copyright 2024 AIT - Austrian Institute of Technology GmbH | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include "test_rate_limiter.hpp" | ||
|
||
TEST_F(RateLimiterTest, TestRateLimiterAllParameters) | ||
{ | ||
std::shared_ptr<filters::FilterBase<double>> filter_ = | ||
std::make_shared<control_filters::RateLimiter<double>>(); | ||
|
||
// should allow configuration and find parameters in sensor_filter_chain param namespace | ||
ASSERT_TRUE(filter_->configure("", "TestRateLimiter", | ||
node_->get_node_logging_interface(), node_->get_node_parameters_interface())); | ||
|
||
// change a parameter | ||
node_->set_parameter(rclcpp::Parameter("sampling_interval", 0.5)); | ||
// accept second call to configure with valid parameters to already configured filter | ||
ASSERT_TRUE(filter_->configure("", "TestRateLimiter", | ||
node_->get_node_logging_interface(), node_->get_node_parameters_interface())); | ||
} | ||
|
||
|
||
TEST_F(RateLimiterTest, TestRateLimiterMissingParameter) | ||
{ | ||
std::shared_ptr<filters::FilterBase<double>> filter_ = | ||
std::make_shared<control_filters::RateLimiter<double>>(); | ||
|
||
// should deny configuration as sampling frequency is missing | ||
ASSERT_FALSE(filter_->configure("", "TestRateLimiter", | ||
node_->get_node_logging_interface(), node_->get_node_parameters_interface())); | ||
} | ||
|
||
TEST_F(RateLimiterTest, TestRateLimiterInvalidThenFixedParameter) | ||
{ | ||
std::shared_ptr<filters::FilterBase<double>> filter_ = | ||
std::make_shared<control_filters::RateLimiter<double>>(); | ||
|
||
// should deny configuration as sampling frequency is invalid | ||
ASSERT_FALSE(filter_->configure("", "TestRateLimiter", | ||
node_->get_node_logging_interface(), node_->get_node_parameters_interface())); | ||
|
||
// fix the param | ||
node_->set_parameter(rclcpp::Parameter("sampling_interval", 1.0)); | ||
// should allow configuration and pass second call to unconfigured filter | ||
ASSERT_TRUE(filter_->configure("", "TestRateLimiter", | ||
node_->get_node_logging_interface(), node_->get_node_parameters_interface())); | ||
} | ||
|
||
TEST_F(RateLimiterTest, TestRateLimiterThrowsUnconfigured) | ||
{ | ||
std::shared_ptr<filters::FilterBase<double>> filter_ = | ||
std::make_shared<control_filters::RateLimiter<double>>(); | ||
double in, out; | ||
ASSERT_THROW(filter_->update(in, out), std::runtime_error); | ||
} | ||
|
||
TEST_F(RateLimiterTest, TestRateLimiterCompute) | ||
{ | ||
std::shared_ptr<filters::FilterBase<double>> filter_ = | ||
std::make_shared<control_filters::RateLimiter<double>>(); | ||
|
||
ASSERT_TRUE(filter_->configure("", "TestRateLimiter", | ||
node_->get_node_logging_interface(), node_->get_node_parameters_interface())); | ||
|
||
double in, out; | ||
ASSERT_NO_THROW(filter_->update(in, out)); | ||
} | ||
|
||
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,62 @@ | ||
// Copyright 2024 AIT - Austrian Institute of Technology GmbH | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#ifndef CONTROL_FILTERS__TEST_RATE_LIMITER_HPP_ | ||
#define CONTROL_FILTERS__TEST_RATE_LIMITER_HPP_ | ||
|
||
#include <memory> | ||
#include <thread> | ||
#include "gmock/gmock.h" | ||
|
||
#include "control_filters/rate_limiter.hpp" | ||
#include "rclcpp/rclcpp.hpp" | ||
|
||
namespace | ||
{ | ||
static const rclcpp::Logger LOGGER = rclcpp::get_logger("test_rate_limiter"); | ||
} // namespace | ||
|
||
class RateLimiterTest : public ::testing::Test | ||
{ | ||
public: | ||
void SetUp() override | ||
{ | ||
auto testname = ::testing::UnitTest::GetInstance()->current_test_info()->name(); | ||
node_ = std::make_shared<rclcpp::Node>(testname); | ||
executor_->add_node(node_); | ||
executor_thread_ = std::thread([this]() { executor_->spin(); }); | ||
} | ||
|
||
RateLimiterTest() | ||
{ | ||
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>(); | ||
} | ||
|
||
void TearDown() override | ||
{ | ||
executor_->cancel(); | ||
if (executor_thread_.joinable()) | ||
{ | ||
executor_thread_.join(); | ||
} | ||
node_.reset(); | ||
} | ||
|
||
protected: | ||
rclcpp::Node::SharedPtr node_; | ||
rclcpp::Executor::SharedPtr executor_; | ||
std::thread executor_thread_; | ||
}; | ||
|
||
#endif // CONTROL_FILTERS__TEST_RATE_LIMITER_HPP_ |
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,17 @@ | ||
TestRateLimiterMissingParameter: | ||
ros__parameters: {} | ||
|
||
TestRateLimiterAllParameters: | ||
ros__parameters: | ||
sampling_interval: 1.0 | ||
|
||
TestRateLimiterInvalidThenFixedParameter: | ||
ros__parameters: {} | ||
|
||
TestRateLimiterThrowsUnconfigured: | ||
ros__parameters: | ||
sampling_interval: 1.0 | ||
|
||
TestRateLimiterCompute: | ||
ros__parameters: | ||
sampling_interval: 1.0 |