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

Improve the reliability of rosbag2 tests #1796

Merged
merged 15 commits into from
Sep 12, 2024
Merged
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 0 additions & 15 deletions rosbag2_test_common/include/rosbag2_test_common/wait_for.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,21 +37,6 @@ bool spin_and_wait_for(Timeout timeout, const Node & node, Condition condition)
return true;
}

template<typename Timeout, typename Condition>
bool wait_until_shutdown(Timeout timeout, Condition condition)
{
using clock = std::chrono::system_clock;
auto start = clock::now();
while (!condition()) {
if ((clock::now() - start) > timeout) {
return false;
}
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
rclcpp::shutdown();
return true;
}

template<typename Condition>
bool wait_until_condition(
Condition condition,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,10 @@

#include <gmock/gmock.h>

#include <atomic>
#include <chrono>
#include <filesystem>
#include <stdexcept>
#include <string>

#include "rosbag2_cpp/info.hpp"
Expand Down Expand Up @@ -81,15 +83,20 @@ class Rosbag2CPPGetServiceInfoTest
template<class T>
void start_async_spin(T node)
{
node_spinner_future_ = std::async(
std::launch::async,
[node, this]() -> void {
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(node);
while (!exit_from_node_spinner_) {
exec.spin_some();
}
});
if (!exit_from_node_spinner_.exchange(false)) {
node_spinner_future_ = std::async(
std::launch::async,
[node, this]() -> void {
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(node);
while (rclcpp::ok() && !exit_from_node_spinner_) {
exec.spin_some(std::chrono::milliseconds(100));
}
exec.remove_node(node);
});
} else {
throw std::runtime_error("Already spinning a node, can't start a new node spin");
}
}

void stop_spinning()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,26 +12,23 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>

#include <atomic>
#include <chrono>
#include <future>
#include <memory>
#include <stdexcept>
#include <string>
#include <vector>
#include <utility>

#include "rclcpp/rclcpp.hpp"

#include "rosbag2_transport/record_options.hpp"
#include "rosbag2_storage/serialized_bag_message.hpp"

#include "rosbag2_test_common/memory_management.hpp"

#include "rosbag2_transport_test_fixture.hpp"

using namespace ::testing; // NOLINT
using namespace rosbag2_transport; // NOLINT
using namespace std::chrono_literals; // NOLINT

#ifndef ROSBAG2_TRANSPORT__RECORD_INTEGRATION_FIXTURE_HPP_
#define ROSBAG2_TRANSPORT__RECORD_INTEGRATION_FIXTURE_HPP_

Expand All @@ -56,13 +53,25 @@ class RecordIntegrationTestFixture : public Rosbag2TransportTestFixture
template<class T>
void start_async_spin(T node)
{
future_ = std::async(
std::launch::async, [node]() -> void {rclcpp::spin(node);});
if (!done_.exchange(false)) {
future_ = std::async(
std::launch::async,
[node, this]() -> void {
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(node);
while (rclcpp::ok() && !done_) {
exec.spin_some(std::chrono::milliseconds(100));
}
exec.remove_node(node);
});
} else {
throw std::runtime_error("Already spinning a node, can't start a new node spin");
}
}

void stop_spinning()
{
rclcpp::shutdown();
done_ = true;
if (future_.valid()) {
future_.wait();
}
Expand All @@ -85,6 +94,7 @@ class RecordIntegrationTestFixture : public Rosbag2TransportTestFixture

MemoryManagement memory_;
std::future<void> future_;
std::atomic_bool done_{false};
};

#endif // ROSBAG2_TRANSPORT__RECORD_INTEGRATION_FIXTURE_HPP_
40 changes: 21 additions & 19 deletions rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,11 +64,11 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 4;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
EXPECT_TRUE(ret) << "failed to capture expected messages in time" <<
"recorded messages = " << recorded_messages.size();
Expand Down Expand Up @@ -126,10 +126,11 @@ TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop)
std::move(writer_), storage_options_, record_options);
recorder->record();

start_async_spin(recorder);

auto & writer = recorder->get_writer_handle();
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

start_async_spin(recorder);
ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str()));
clalancette marked this conversation as resolved.
Show resolved Hide resolved

pub_manager.run_publishers();
Expand All @@ -146,11 +147,11 @@ TEST_F(RecordIntegrationTestFixture, can_record_again_after_stop)

// 4 because we're running recorder->record() and publishers twice
constexpr size_t expected_messages = 4;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
EXPECT_THAT(recorded_messages, SizeIs(expected_messages));
Expand Down Expand Up @@ -197,11 +198,11 @@ TEST_F(RecordIntegrationTestFixture, qos_is_stored_in_metadata)
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 2;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
EXPECT_THAT(recorded_messages, SizeIs(expected_messages));
Expand Down Expand Up @@ -261,11 +262,11 @@ TEST_F(RecordIntegrationTestFixture, records_sensor_data)
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 2;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
auto recorded_topics = mock_writer.get_topics();
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
Expand Down Expand Up @@ -302,11 +303,11 @@ TEST_F(RecordIntegrationTestFixture, receives_latched_messages)
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());

size_t expected_messages = num_latched_messages;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[&mock_writer, &expected_messages]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
auto recorded_topics = mock_writer.get_topics();
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
Expand Down Expand Up @@ -436,14 +437,15 @@ TEST_F(RecordIntegrationTestFixture, write_split_callback_is_called)

rosbag2_test_common::PublicationManager pub_manager;
pub_manager.setup_publisher(string_topic, string_message, expected_messages);

ASSERT_TRUE(pub_manager.wait_for_matched(string_topic.c_str()));
pub_manager.run_publishers();

auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[&mock_writer, &expected_messages]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
EXPECT_THAT(recorded_messages, SizeIs(expected_messages));
Expand Down
39 changes: 27 additions & 12 deletions rosbag2_transport/test/rosbag2_transport/test_record_all.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@

#include "rosbag2_transport/recorder.hpp"

#include "mock_recorder.hpp"
#include "record_integration_fixture.hpp"

using namespace std::chrono_literals; // NOLINT
Expand Down Expand Up @@ -66,11 +67,11 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_topics_are
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 4;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
auto recorded_messages = mock_writer.get_messages();
EXPECT_EQ(recorded_messages.size(), expected_messages);
Expand Down Expand Up @@ -98,7 +99,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a

rosbag2_transport::RecordOptions record_options =
{false, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms};
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();

Expand All @@ -107,20 +108,27 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_multiple_services_a
ASSERT_TRUE(client_manager_1->wait_for_service_to_be_ready());
ASSERT_TRUE(client_manager_2->wait_for_service_to_be_ready());

// At this point, we expect that the services /test_service_1 and /test_service_2, along with
// the event topics /test_service_1/_service_event and /test_service_2/_service_event are
// available to be recorded. However, wait_for_service_to_be_ready() only checks the services,
// not the event topics, so ask the recorder to make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/test_service_1/_service_event"));
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/test_service_2/_service_event"));
MichaelOrlov marked this conversation as resolved.
Show resolved Hide resolved

// By default, only client introspection is enabled.
// For one request, service event topic get 2 messages.
// For one request, service event topic gets 2 messages.
ASSERT_TRUE(client_manager_1->send_request());
ASSERT_TRUE(client_manager_2->send_request());

auto & writer = recorder->get_writer_handle();
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 4;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
auto recorded_messages = mock_writer.get_messages();
EXPECT_EQ(recorded_messages.size(), expected_messages);
Expand All @@ -140,7 +148,7 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a

rosbag2_transport::RecordOptions record_options =
{true, true, false, {}, {}, {}, {"/rosout"}, {}, {}, "rmw_format", 100ms};
auto recorder = std::make_shared<rosbag2_transport::Recorder>(
auto recorder = std::make_shared<MockRecorder>(
std::move(writer_), storage_options_, record_options);
recorder->record();

Expand All @@ -150,6 +158,13 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a

ASSERT_TRUE(client_manager_1->wait_for_service_to_be_ready());

// At this point, we expect that the service /test_service_1, along with the topic /string_topic,
// along with the event topic /test_service_1, along with the split topic /events/write_split are
// available to be recorded. However, wait_for_matched() and wait_for_service_to_be_ready() only
// check on the service and the topic, not the event or the split topic, so ask the recorder to
// make sure it has successfully subscribed to all.
ASSERT_TRUE(recorder->wait_for_topic_to_be_discovered("/test_service/_service_event"));

pub_manager.run_publishers();

// By default, only client introspection is enabled.
Expand All @@ -160,11 +175,11 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_topic_and_service_a
auto & mock_writer = dynamic_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 3;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
EXPECT_TRUE(ret) << "failed to capture expected messages in time";
auto recorded_messages = mock_writer.get_messages();
EXPECT_EQ(recorded_messages.size(), expected_messages);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,11 +69,11 @@ TEST_F(RecordIntegrationTestFixture, published_messages_from_two_topics_ignore_l
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 2;
auto ret = rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(5),
auto ret = rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() >= expected_messages;
});
},
std::chrono::seconds(5));
auto recorded_messages = mock_writer.get_messages();
// We may receive additional messages from rosout, it doesn't matter,
// as long as we have received at least as many total messages as we expect
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"
#include "rosbag2_test_common/publication_manager.hpp"
#include "rosbag2_test_common/wait_for.hpp"
#include "record_integration_fixture.hpp"

using namespace std::chrono_literals; // NOLINT
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,11 +54,11 @@ TEST_F(RecordIntegrationTestFixture, record_all_without_discovery_ignores_later_
static_cast<MockSequentialWriter &>(writer.get_implementation_handle());

constexpr size_t expected_messages = 0;
rosbag2_test_common::wait_until_shutdown(
std::chrono::seconds(2),
rosbag2_test_common::wait_until_condition(
[ =, &mock_writer]() {
return mock_writer.get_messages().size() > expected_messages;
});
},
std::chrono::seconds(2));
// We can't EXPECT anything here, since there may be some messages from rosout

auto recorded_topics = mock_writer.get_topics();
Expand Down
Loading
Loading