Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

make ROS 2 smoke tests less flaky #260

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
36 changes: 24 additions & 12 deletions ros2_foxglove_bridge/tests/smoke_test.cpp
Expand Up @@ -166,6 +166,7 @@ TEST(SmokeTest, testSubscription) {

auto node = rclcpp::Node::make_shared("tester");
rclcpp::QoS qos = rclcpp::QoS{rclcpp::KeepLast(1lu)};
qos.reliable();
qos.transient_local();
auto pub = node->create_publisher<std_msgs::msg::String>(topic_name, qos);
pub->publish(rosMsg);
Expand Down Expand Up @@ -202,6 +203,7 @@ TEST(SmokeTest, testSubscriptionParallel) {

auto node = rclcpp::Node::make_shared("tester");
rclcpp::QoS qos = rclcpp::QoS{rclcpp::KeepLast(1lu)};
qos.reliable();
qos.transient_local();
auto pub = node->create_publisher<std_msgs::msg::String>(topic_name, qos);
pub->publish(rosMsg);
Expand Down Expand Up @@ -258,12 +260,17 @@ TEST(SmokeTest, testPublishing) {
executor.add_node(node);

// Set up the client, advertise and publish the binary message
foxglove::Client<websocketpp::config::asio_client> wsClient;
ASSERT_EQ(std::future_status::ready, wsClient.connect(URI).wait_for(DEFAULT_TIMEOUT));
wsClient.advertise({advertisement});
std::this_thread::sleep_for(ONE_SECOND);
wsClient.publish(advertisement.channelId, HELLO_WORLD_BINARY, sizeof(HELLO_WORLD_BINARY));
wsClient.unadvertise({advertisement.channelId});
auto client = std::make_shared<foxglove::Client<websocketpp::config::asio_client>>();
ASSERT_EQ(std::future_status::ready, client->connect(URI).wait_for(ONE_SECOND));
client->advertise({advertisement});

// Wait until the advertisement got advertised as channel by the server
auto channelFuture = foxglove::waitForChannel(client, advertisement.topic);
ASSERT_EQ(std::future_status::ready, channelFuture.wait_for(ONE_SECOND));

// Publish the message and unadvertise again
client->publish(advertisement.channelId, HELLO_WORLD_BINARY, sizeof(HELLO_WORLD_BINARY));
client->unadvertise({advertisement.channelId});

// Ensure that we have received the correct message via our ROS subscriber
const auto ret = executor.spin_until_future_complete(msgFuture, ONE_SECOND);
Expand All @@ -290,12 +297,17 @@ TEST_F(ExistingPublisherTest, testPublishingWithExistingPublisher) {
executor.add_node(node);

// Set up the client, advertise and publish the binary message
foxglove::Client<websocketpp::config::asio_client> wsClient;
ASSERT_EQ(std::future_status::ready, wsClient.connect(URI).wait_for(DEFAULT_TIMEOUT));
wsClient.advertise({advertisement});
std::this_thread::sleep_for(ONE_SECOND);
wsClient.publish(advertisement.channelId, HELLO_WORLD_BINARY, sizeof(HELLO_WORLD_BINARY));
wsClient.unadvertise({advertisement.channelId});
auto client = std::make_shared<foxglove::Client<websocketpp::config::asio_client>>();
ASSERT_EQ(std::future_status::ready, client->connect(URI).wait_for(ONE_SECOND));
client->advertise({advertisement});

// Wait until the advertisement got advertised as channel by the server
auto channelFuture = foxglove::waitForChannel(client, advertisement.topic);
ASSERT_EQ(std::future_status::ready, channelFuture.wait_for(ONE_SECOND));

// Publish the message and unadvertise again
client->publish(advertisement.channelId, HELLO_WORLD_BINARY, sizeof(HELLO_WORLD_BINARY));
client->unadvertise({advertisement.channelId});

// Ensure that we have received the correct message via our ROS subscriber
const auto ret = executor.spin_until_future_complete(msgFuture, ONE_SECOND);
Expand Down