Skip to content

Commit e7049ab

Browse files
Fix control_filters tests (#261)
* Make tests fail fast * Use common test_fixture and don't start a separate thread * Remove the executor
1 parent 806dd64 commit e7049ab

7 files changed

+46
-164
lines changed

CMakeLists.txt

+3
Original file line numberDiff line numberDiff line change
@@ -165,16 +165,19 @@ if(BUILD_TESTING)
165165
)
166166
target_link_libraries(test_low_pass_filter low_pass_filter low_pass_filter_parameters)
167167
ament_target_dependencies(test_low_pass_filter ${CONTROL_FILTERS_INCLUDE_DEPENDS})
168+
set_tests_properties(test_low_pass_filter PROPERTIES TIMEOUT 2)
168169

169170
ament_add_gmock(test_load_low_pass_filter test/control_filters/test_load_low_pass_filter.cpp)
170171
target_link_libraries(test_load_low_pass_filter low_pass_filter low_pass_filter_parameters)
171172
ament_target_dependencies(test_load_low_pass_filter ${CONTROL_FILTERS_INCLUDE_DEPENDS})
172173

174+
# rate_limiter
173175
add_rostest_with_parameters_gmock(test_rate_limiter test/control_filters/test_rate_limiter.cpp
174176
${CMAKE_CURRENT_SOURCE_DIR}/test/control_filters/test_rate_limiter_parameters.yaml
175177
)
176178
target_link_libraries(test_rate_limiter rate_limiter rate_limiter_parameters)
177179
ament_target_dependencies(test_rate_limiter ${CONTROL_FILTERS_INCLUDE_DEPENDS})
180+
set_tests_properties(test_rate_limiter PROPERTIES TIMEOUT 2)
178181

179182
ament_add_gmock(test_load_rate_limiter test/control_filters/test_load_rate_limiter.cpp)
180183
target_link_libraries(test_load_rate_limiter rate_limiter rate_limiter_parameters)

test/control_filters/test_exponential_filter.cpp

+8-3
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,14 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "test_exponential_filter.hpp"
15+
#include "test_filter_util.hpp"
1616

17-
TEST_F(ExponentialFilterTest, TestExponentialFilterThrowsUnconfigured)
17+
#include <memory>
18+
#include "gmock/gmock.h"
19+
20+
#include "control_filters/exponential_filter.hpp"
21+
22+
TEST_F(FilterTest, TestExponentialFilterThrowsUnconfigured)
1823
{
1924
std::shared_ptr<filters::FilterBase<double>> filter_ =
2025
std::make_shared<control_filters::ExponentialFilter<double>>();
@@ -23,7 +28,7 @@ TEST_F(ExponentialFilterTest, TestExponentialFilterThrowsUnconfigured)
2328
}
2429

2530

26-
TEST_F(ExponentialFilterTest, TestExponentialFilterComputation)
31+
TEST_F(FilterTest, TestExponentialFilterComputation)
2732
{
2833
// parameters should match the test yaml file
2934
double alpha = 0.7;

test/control_filters/test_exponential_filter.hpp

-62
This file was deleted.

test/control_filters/test_low_pass_filter.hpp test/control_filters/test_filter_util.hpp

+7-24
Original file line numberDiff line numberDiff line change
@@ -12,52 +12,35 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef CONTROL_FILTERS__TEST_LOW_PASS_FILTER_HPP_
16-
#define CONTROL_FILTERS__TEST_LOW_PASS_FILTER_HPP_
15+
#ifndef CONTROL_FILTERS__TEST_FILTER_UTIL_HPP_
16+
#define CONTROL_FILTERS__TEST_FILTER_UTIL_HPP_
1717

1818
#include <memory>
19-
#include <thread>
2019
#include "gmock/gmock.h"
2120

22-
#include "control_filters/low_pass_filter.hpp"
23-
#include "geometry_msgs/msg/wrench_stamped.hpp"
24-
#include "rclcpp/rclcpp.hpp"
21+
#include "rclcpp/node.hpp"
22+
#include "rclcpp/logger.hpp"
2523

26-
namespace
27-
{
28-
static const rclcpp::Logger LOGGER = rclcpp::get_logger("test_low_pass_filter");
29-
} // namespace
30-
31-
class LowPassFilterTest : public ::testing::Test
24+
class FilterTest : public ::testing::Test
3225
{
3326
public:
3427
void SetUp() override
3528
{
3629
auto testname = ::testing::UnitTest::GetInstance()->current_test_info()->name();
3730
node_ = std::make_shared<rclcpp::Node>(testname);
38-
executor_->add_node(node_);
39-
executor_thread_ = std::thread([this]() { executor_->spin(); });
4031
}
4132

42-
LowPassFilterTest()
33+
FilterTest()
4334
{
44-
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
4535
}
4636

4737
void TearDown() override
4838
{
49-
executor_->cancel();
50-
if (executor_thread_.joinable())
51-
{
52-
executor_thread_.join();
53-
}
5439
node_.reset();
5540
}
5641

5742
protected:
5843
rclcpp::Node::SharedPtr node_;
59-
rclcpp::Executor::SharedPtr executor_;
60-
std::thread executor_thread_;
6144
};
6245

63-
#endif // CONTROL_FILTERS__TEST_LOW_PASS_FILTER_HPP_
46+
#endif // CONTROL_FILTERS__TEST_FILTER_UTIL_HPP_

test/control_filters/test_low_pass_filter.cpp

+15-7
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,16 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "test_low_pass_filter.hpp"
15+
#include "test_filter_util.hpp"
1616

17-
TEST_F(LowPassFilterTest, TestLowPassWrenchFilterAllParameters)
17+
#include <memory>
18+
#include "gmock/gmock.h"
19+
20+
#include "geometry_msgs/msg/wrench_stamped.hpp"
21+
22+
#include "control_filters/low_pass_filter.hpp"
23+
24+
TEST_F(FilterTest, TestLowPassWrenchFilterAllParameters)
1825
{
1926
std::shared_ptr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> filter_ =
2027
std::make_shared<control_filters::LowPassFilter<geometry_msgs::msg::WrenchStamped>>();
@@ -26,12 +33,13 @@ TEST_F(LowPassFilterTest, TestLowPassWrenchFilterAllParameters)
2633
// change a parameter
2734
node_->set_parameter(rclcpp::Parameter("sampling_frequency", 500.0));
2835
// accept second call to configure with valid parameters to already configured filter
36+
// will give a warning "Filter %s already being reconfigured"
2937
ASSERT_TRUE(filter_->configure("", "TestLowPassFilter",
3038
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
3139
}
3240

3341

34-
TEST_F(LowPassFilterTest, TestLowPassWrenchFilterMissingParameter)
42+
TEST_F(FilterTest, TestLowPassWrenchFilterMissingParameter)
3543
{
3644
std::shared_ptr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> filter_ =
3745
std::make_shared<control_filters::LowPassFilter<geometry_msgs::msg::WrenchStamped>>();
@@ -41,7 +49,7 @@ TEST_F(LowPassFilterTest, TestLowPassWrenchFilterMissingParameter)
4149
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
4250
}
4351

44-
TEST_F(LowPassFilterTest, TestLowPassWrenchFilterInvalidThenFixedParameter)
52+
TEST_F(FilterTest, TestLowPassWrenchFilterInvalidThenFixedParameter)
4553
{
4654
std::shared_ptr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> filter_ =
4755
std::make_shared<control_filters::LowPassFilter<geometry_msgs::msg::WrenchStamped>>();
@@ -57,23 +65,23 @@ TEST_F(LowPassFilterTest, TestLowPassWrenchFilterInvalidThenFixedParameter)
5765
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
5866
}
5967

60-
TEST_F(LowPassFilterTest, TestLowPassFilterThrowsUnconfigured)
68+
TEST_F(FilterTest, TestLowPassFilterThrowsUnconfigured)
6169
{
6270
std::shared_ptr<filters::FilterBase<double>> filter_ =
6371
std::make_shared<control_filters::LowPassFilter<double>>();
6472
double in, out;
6573
ASSERT_THROW(filter_->update(in, out), std::runtime_error);
6674
}
6775

68-
TEST_F(LowPassFilterTest, TestLowPassWrenchFilterThrowsUnconfigured)
76+
TEST_F(FilterTest, TestLowPassWrenchFilterThrowsUnconfigured)
6977
{
7078
std::shared_ptr<filters::FilterBase<geometry_msgs::msg::WrenchStamped>> filter_ =
7179
std::make_shared<control_filters::LowPassFilter<geometry_msgs::msg::WrenchStamped>>();
7280
geometry_msgs::msg::WrenchStamped in, out;
7381
ASSERT_THROW(filter_->update(in, out), std::runtime_error);
7482
}
7583

76-
TEST_F(LowPassFilterTest, TestLowPassWrenchFilterComputation)
84+
TEST_F(FilterTest, TestLowPassWrenchFilterComputation)
7785
{
7886
// parameters should match the test yaml file
7987
double sampling_freq = 1000.0;

test/control_filters/test_rate_limiter.cpp

+13-6
Original file line numberDiff line numberDiff line change
@@ -12,9 +12,15 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "test_rate_limiter.hpp"
15+
#include "test_filter_util.hpp"
1616

17-
TEST_F(RateLimiterTest, TestRateLimiterAllParameters)
17+
#include <memory>
18+
#include <thread>
19+
#include "gmock/gmock.h"
20+
21+
#include "control_filters/rate_limiter.hpp"
22+
23+
TEST_F(FilterTest, TestRateLimiterAllParameters)
1824
{
1925
std::shared_ptr<filters::FilterBase<double>> filter_ =
2026
std::make_shared<control_filters::RateLimiter<double>>();
@@ -26,12 +32,13 @@ TEST_F(RateLimiterTest, TestRateLimiterAllParameters)
2632
// change a parameter
2733
node_->set_parameter(rclcpp::Parameter("sampling_interval", 0.5));
2834
// accept second call to configure with valid parameters to already configured filter
35+
// will give a warning "Filter %s already being reconfigured"
2936
ASSERT_TRUE(filter_->configure("", "TestRateLimiter",
3037
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
3138
}
3239

3340

34-
TEST_F(RateLimiterTest, TestRateLimiterMissingParameter)
41+
TEST_F(FilterTest, TestRateLimiterMissingParameter)
3542
{
3643
std::shared_ptr<filters::FilterBase<double>> filter_ =
3744
std::make_shared<control_filters::RateLimiter<double>>();
@@ -41,7 +48,7 @@ TEST_F(RateLimiterTest, TestRateLimiterMissingParameter)
4148
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
4249
}
4350

44-
TEST_F(RateLimiterTest, TestRateLimiterInvalidThenFixedParameter)
51+
TEST_F(FilterTest, TestRateLimiterInvalidThenFixedParameter)
4552
{
4653
std::shared_ptr<filters::FilterBase<double>> filter_ =
4754
std::make_shared<control_filters::RateLimiter<double>>();
@@ -57,15 +64,15 @@ TEST_F(RateLimiterTest, TestRateLimiterInvalidThenFixedParameter)
5764
node_->get_node_logging_interface(), node_->get_node_parameters_interface()));
5865
}
5966

60-
TEST_F(RateLimiterTest, TestRateLimiterThrowsUnconfigured)
67+
TEST_F(FilterTest, TestRateLimiterThrowsUnconfigured)
6168
{
6269
std::shared_ptr<filters::FilterBase<double>> filter_ =
6370
std::make_shared<control_filters::RateLimiter<double>>();
6471
double in, out;
6572
ASSERT_THROW(filter_->update(in, out), std::runtime_error);
6673
}
6774

68-
TEST_F(RateLimiterTest, TestRateLimiterCompute)
75+
TEST_F(FilterTest, TestRateLimiterCompute)
6976
{
7077
std::shared_ptr<filters::FilterBase<double>> filter_ =
7178
std::make_shared<control_filters::RateLimiter<double>>();

test/control_filters/test_rate_limiter.hpp

-62
This file was deleted.

0 commit comments

Comments
 (0)