forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathtest_wait_for_message.cpp
More file actions
74 lines (58 loc) · 2.01 KB
/
test_wait_for_message.cpp
File metadata and controls
74 lines (58 loc) · 2.01 KB
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
// Copyright 2021 Open Source Robotics Foundation, 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.
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <vector>
#include "rclcpp/node.hpp"
#include "rclcpp/wait_for_message.hpp"
#include "test_msgs/msg/strings.hpp"
#include "test_msgs/message_fixtures.hpp"
using namespace std::chrono_literals;
TEST(TestUtilities, wait_for_message) {
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("wait_for_message_node");
using MsgT = test_msgs::msg::Strings;
auto pub = node->create_publisher<MsgT>("wait_for_message_topic", 10);
MsgT out;
auto received = false;
auto wait = std::async(
[&]() {
auto ret = rclcpp::wait_for_message(out, node, "wait_for_message_topic", 5s);
EXPECT_TRUE(ret);
received = true;
});
for (auto i = 0u; i < 10 && received == false; ++i) {
pub->publish(*get_messages_strings()[0]);
std::this_thread::sleep_for(1s);
}
ASSERT_TRUE(received);
EXPECT_EQ(out, *get_messages_strings()[0]);
rclcpp::shutdown();
}
TEST(TestUtilities, wait_for_message_indefinitely) {
rclcpp::init(0, nullptr);
auto node = std::make_shared<rclcpp::Node>("wait_for_message_node2");
using MsgT = test_msgs::msg::Strings;
MsgT out;
auto received = false;
auto wait = std::async(
[&]() {
auto ret = rclcpp::wait_for_message(out, node, "wait_for_message_topic" /*, -1 */);
EXPECT_TRUE(ret);
received = true;
});
rclcpp::shutdown();
ASSERT_FALSE(received);
}