forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathtest_fake_test_node.cpp
105 lines (88 loc) · 3.01 KB
/
test_fake_test_node.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
// Copyright 2021 Apex.AI, Inc.
//
// 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.
//
// Co-developed by Tier IV, Inc. and Apex.AI, Inc.
/// \copyright Copyright 2021 Apex.AI, Inc.
/// All rights reserved.
#include <autoware/fake_test_node/fake_test_node.hpp>
#include <std_msgs/msg/bool.hpp>
#include <std_msgs/msg/int32.hpp>
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <vector>
using bool8_t = bool;
using FakeNodeFixture = autoware::fake_test_node::FakeTestNode;
using FakeNodeFixtureParametrized = autoware::fake_test_node::FakeTestNodeParametrized<bool8_t>;
using std_msgs::msg::Bool;
using std_msgs::msg::Int32;
namespace
{
class NodeUnderTest : public rclcpp::Node
{
public:
NodeUnderTest()
: rclcpp::Node{"is_positive_node"},
m_pub{this->create_publisher<Bool>("/output_topic", 10)},
m_sub{this->create_subscription<Int32>("/input_topic", 10, [&](const Int32::SharedPtr msg) {
Bool output;
output.data = msg->data > 0;
m_pub->publish(output);
})}
{
}
private:
rclcpp::Publisher<Bool>::SharedPtr m_pub{};
rclcpp::Subscription<Int32>::SharedPtr m_sub{};
};
template <typename FixtureT>
void run_test(int32_t value_in_message, FixtureT * fixture)
{
Int32 msg{};
msg.data = value_in_message;
const auto node = std::make_shared<NodeUnderTest>();
Bool::SharedPtr last_received_msg{};
auto fake_odom_publisher = fixture->template create_publisher<Int32>("/input_topic");
auto result_odom_subscription = fixture->template create_subscription<Bool>(
"/output_topic", *node,
[&last_received_msg](const Bool::SharedPtr msg) { last_received_msg = msg; });
const auto dt{std::chrono::milliseconds{100LL}};
const auto max_wait_time{std::chrono::seconds{10LL}};
auto time_passed{std::chrono::milliseconds{0LL}};
while (!last_received_msg) {
fake_odom_publisher->publish(msg);
rclcpp::spin_some(node);
rclcpp::spin_some(fixture->get_fake_node());
std::this_thread::sleep_for(dt);
time_passed += dt;
if (time_passed > max_wait_time) {
FAIL() << "Did not receive a message soon enough.";
}
}
EXPECT_EQ(last_received_msg->data, value_in_message > 0);
SUCCEED();
}
} // namespace
/// @test Test that we can use a non-parametrized test.
TEST_F(FakeNodeFixture, Test)
{
run_test(15, this);
}
INSTANTIATE_TEST_SUITE_P(
FakeNodeFixtureTests, FakeNodeFixtureParametrized, ::testing::Values(-5, 0, 42));
/// @test Test that we can use a parametrized test.
TEST_P(FakeNodeFixtureParametrized, Test)
{
run_test(GetParam(), this);
}