Skip to content

Commit

Permalink
Add tests
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 1, 2024
1 parent 0eda373 commit b4cfba4
Show file tree
Hide file tree
Showing 4 changed files with 172 additions and 0 deletions.
6 changes: 6 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,12 @@ if(BUILD_TESTING)
target_link_libraries(test_load_low_pass_filter low_pass_filter low_pass_filter_parameters)
ament_target_dependencies(test_load_low_pass_filter ${CONTROL_FILTERS_INCLUDE_DEPENDS})

add_rostest_with_parameters_gmock(test_rate_limiter test/control_filters/test_rate_limiter.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/control_filters/test_rate_limiter_parameters.yaml
)
target_link_libraries(test_rate_limiter rate_limiter rate_limiter_parameters)
ament_target_dependencies(test_rate_limiter ${CONTROL_FILTERS_INCLUDE_DEPENDS})

ament_add_gmock(test_load_rate_limiter test/control_filters/test_load_rate_limiter.cpp)
target_link_libraries(test_load_rate_limiter rate_limiter rate_limiter_parameters)
ament_target_dependencies(test_load_rate_limiter ${CONTROL_FILTERS_INCLUDE_DEPENDS})
Expand Down
87 changes: 87 additions & 0 deletions test/control_filters/test_rate_limiter.cpp
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;
}
62 changes: 62 additions & 0 deletions test/control_filters/test_rate_limiter.hpp
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_
17 changes: 17 additions & 0 deletions test/control_filters/test_rate_limiter_parameters.yaml
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

0 comments on commit b4cfba4

Please sign in to comment.