Skip to content

Commit

Permalink
Improve sqlite usage and test stability (#31)
Browse files Browse the repository at this point in the history
* GH-64 Rearrange default plugins build to use public headers

Also already links write integration test against the default plugins.

* GH-64 Remove after_write_action

Query the underlying db directly in tests to determine the amount of
recorded messages.

* GH-64 Add convenience getter for single line SQL result

* GH-64 Add visibility macros to enable linking on Windows

* GH-64 Remove second sqlite exception class (it is not needed)

* GH-64 Fix hanging rosbag2_read_integration_test

* GH-64 Always log sqlite return code

* GH-64 Improve opening of sqlite database

- Always open db with threading mode multi-thread. This forbids
  sharing database connections across threads. Db access from multiple
  threads is possible when each thread uses its own connection.
- Open sqlite db accordingly to given io flags. Readonly open works
  only with already existing database.
- Set journal mode pragma to WAL (write ahead log) and synchronous
  pragma to NORMAL. This should yield good write performance.
- Small fix: use *.db3 as db name in tests.

* GH-64 Fix package test dependencies

* GH-64 Fix cppcheck error

* GH-64 Fix asserting typesupport in test (varies on architectures)

* Cleanup

- consistently use const ref of string instead of string for function
  arguments
- simplify package dependencies
- minor formatting

* Make play integration test compile on Mac

* Fix sqlite_wrapper_integration_test
  • Loading branch information
anhosi authored and Karsten1987 committed Sep 13, 2018
1 parent 3b23acc commit 4bfa3c6
Show file tree
Hide file tree
Showing 24 changed files with 283 additions and 159 deletions.
14 changes: 10 additions & 4 deletions rosbag2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ find_package(rcl REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rcutils REQUIRED)
find_package(rosbag2_storage REQUIRED)
find_package(rosidl_generator_c REQUIRED)
find_package(rosidl_generator_cpp REQUIRED)
find_package(std_msgs REQUIRED)

add_library(
Expand Down Expand Up @@ -72,9 +72,9 @@ install(
LIBRARY DESTINATION lib)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(rosbag2_storage_default_plugins REQUIRED)
find_package(test_msgs REQUIRED)
ament_lint_auto_find_test_dependencies()

Expand All @@ -83,15 +83,21 @@ if(BUILD_TESTING)
test/rosbag2/test_memory_management.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET rosbag2_write_integration_test)
target_link_libraries(rosbag2_write_integration_test librosbag2)
target_link_libraries(rosbag2_write_integration_test librosbag2
${rosbag2_storage_default_plugins_LIBRARIES})
target_include_directories(rosbag2_write_integration_test PRIVATE
${rosbag2_storage_default_plugins_INCLUDE_DIRS})
endif()

ament_add_gmock(rosbag2_write_all_integration_test
test/rosbag2/rosbag2_write_all_integration_test.cpp
test/rosbag2/test_memory_management.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET rosbag2_write_all_integration_test)
target_link_libraries(rosbag2_write_all_integration_test librosbag2)
target_link_libraries(rosbag2_write_all_integration_test librosbag2
${rosbag2_storage_default_plugins_LIBRARIES})
target_include_directories(rosbag2_write_all_integration_test PRIVATE
${rosbag2_storage_default_plugins_INCLUDE_DIRS})
endif()

ament_add_gmock(rosbag2_read_integration_test
Expand Down
6 changes: 1 addition & 5 deletions rosbag2/include/rosbag2/rosbag2.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,7 @@ class Rosbag2
* Might be removed later.
*/
ROSBAG2_PUBLIC
void record(
const std::string & file_name,
const std::vector<std::string> & topic_names,
std::function<void(std::string)> after_write_action = nullptr);
void record(const std::string & file_name, const std::vector<std::string> & topic_names);

/**
* Replay all topics in a bagfile.
Expand All @@ -69,7 +66,6 @@ class Rosbag2

std::shared_ptr<rosbag2::GenericSubscription>
create_subscription(
const std::function<void(std::string)> & after_write_action,
std::shared_ptr<rosbag2_storage::storage_interfaces::ReadWriteInterface> storage,
std::shared_ptr<Rosbag2Node> & node,
const std::string & topic_name, const std::string & topic_type) const;
Expand Down
9 changes: 8 additions & 1 deletion rosbag2/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,18 @@
<depend>rclcpp</depend>
<depend>rcutils</depend>
<depend>rosbag2_storage</depend>
<depend>rosidl_generator_c</depend>
<depend>rosidl_generator_cpp</depend>
<depend>std_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_index_cpp</test_depend>
<test_depend>poco_vendor</test_depend>
<test_depend>rcl</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>rosbag2_storage_default_plugins</test_depend>
<test_depend>std_msgs</test_depend>
<test_depend>test_msgs</test_depend>

<export>
Expand Down
13 changes: 3 additions & 10 deletions rosbag2/src/rosbag2/rosbag2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,10 +41,7 @@ namespace rosbag2

const char * ROS_PACKAGE_NAME = "rosbag2";

void Rosbag2::record(
const std::string & file_name,
const std::vector<std::string> & topic_names,
std::function<void(std::string)> after_write_action)
void Rosbag2::record(const std::string & file_name, const std::vector<std::string> & topic_names)
{
rosbag2_storage::StorageFactory factory;
auto storage = factory.open_read_write(file_name, "sqlite3");
Expand All @@ -68,7 +65,7 @@ void Rosbag2::record(
auto topic_type = topic_and_type.second;

std::shared_ptr<GenericSubscription> subscription = create_subscription(
after_write_action, storage, node, topic_name, topic_type);
storage, node, topic_name, topic_type);

if (subscription) {
subscriptions_.push_back(subscription);
Expand All @@ -90,15 +87,14 @@ void Rosbag2::record(

std::shared_ptr<GenericSubscription>
Rosbag2::create_subscription(
const std::function<void(std::string)> & after_write_action,
std::shared_ptr<rosbag2_storage::storage_interfaces::ReadWriteInterface> storage,
std::shared_ptr<Rosbag2Node> & node,
const std::string & topic_name, const std::string & topic_type) const
{
auto subscription = node->create_generic_subscription(
topic_name,
topic_type,
[storage, topic_name, after_write_action](std::shared_ptr<rmw_serialized_message_t> message) {
[storage, topic_name](std::shared_ptr<rmw_serialized_message_t> message) {
auto bag_message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
bag_message->serialized_data = message;
bag_message->topic_name = topic_name;
Expand All @@ -111,9 +107,6 @@ Rosbag2::create_subscription(
bag_message->time_stamp = time_stamp;

storage->write(bag_message);
if (after_write_action) {
after_write_action(topic_name);
}
});
return subscription;
}
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/src/rosbag2/typesupport_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@

#include "Poco/SharedLibrary.h"

#include "rosidl_generator_c/message_type_support_struct.h"
#include "rosidl_generator_cpp/message_type_support_decl.hpp"

namespace rosbag2
{
Expand Down
37 changes: 18 additions & 19 deletions rosbag2/test/rosbag2/rosbag2_read_integration_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,24 +49,24 @@ class RosBag2IntegrationTestFixture : public Rosbag2TestFixture
}

template<typename T>
auto subscribe_messages(
size_t expected_messages_number, const std::string & topic)
auto prepare_subscriber(size_t expected_messages_number, const std::string & topic)
{
auto node = rclcpp::Node::make_shared("node_" + topic);
std::vector<typename T::ConstSharedPtr> messages;
size_t messages_received = 0;

auto messages = std::make_shared<std::vector<typename T::ConstSharedPtr>>();
auto messages_received = std::make_shared<size_t>(0);
auto subscription = node->create_subscription<T>(topic,
[&messages, &messages_received](typename T::ConstSharedPtr message) {
messages.push_back(message);
++messages_received;
[messages, messages_received](typename T::ConstSharedPtr message) {
messages->push_back(message);
++*messages_received;
});
subscriptions_.push_back(subscription);

while (messages_received < expected_messages_number) {
rclcpp::spin_some(node);
}
return messages;
return [messages, messages_received, node, expected_messages_number]() {
while (*messages_received < expected_messages_number) {
rclcpp::spin_some(node);
}
return *messages;
};
}

template<typename MessageT>
Expand All @@ -83,9 +83,8 @@ class RosBag2IntegrationTestFixture : public Rosbag2TestFixture
template<typename MessageT>
auto launch_subscriber(size_t expected_messages_number, const std::string & topic)
{
return std::async(std::launch::async, [this, expected_messages_number, topic] {
return subscribe_messages<MessageT>(expected_messages_number, topic);
});
auto spin_subscriber = prepare_subscriber<MessageT>(expected_messages_number, topic);
return std::async(std::launch::async, spin_subscriber);
}

void wait_for_subscribers(size_t count)
Expand All @@ -110,12 +109,12 @@ TEST_F(RosBag2IntegrationTestFixture, recorded_messages_are_played_for_all_topic
primitive_message2->string_value = "Hello World 2";

auto complex_message1 = get_messages_static_array_primitives()[0];
complex_message1->string_values = {"Complex Hello1", "Complex Hello2", "Complex Hello3"};
complex_message1->bool_values = {true, false, true};
complex_message1->string_values = {{"Complex Hello1", "Complex Hello2", "Complex Hello3"}};
complex_message1->bool_values = {{true, false, true}};

auto complex_message2 = get_messages_static_array_primitives()[0];
complex_message2->string_values = {"Complex Hello4", "Complex Hello5", "Complex Hello6"};
complex_message2->bool_values = {false, false, true};
complex_message2->string_values = {{"Complex Hello4", "Complex Hello5", "Complex Hello6"}};
complex_message2->bool_values = {{false, false, true}};

auto topic_types = std::map<std::string, std::string>{
{"topic1", "test_msgs/Primitives"},
Expand Down
4 changes: 2 additions & 2 deletions rosbag2/test/rosbag2/rosbag2_rosbag_node_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ class RosBag2NodeFixture : public Test
rclcpp::shutdown();
}

void create_publisher(std::string topic)
void create_publisher(const std::string & topic)
{
auto publisher = publisher_node_->create_publisher<std_msgs::msg::String>(topic);
publishers_.push_back(publisher);
Expand All @@ -73,7 +73,7 @@ class RosBag2NodeFixture : public Test
return messages;
}

std::shared_ptr<rcutils_char_array_t> serialize_string_message(std::string message)
std::shared_ptr<rcutils_char_array_t> serialize_string_message(const std::string & message)
{
auto string_message = std::make_shared<std_msgs::msg::String>();
string_message->data = message;
Expand Down
2 changes: 1 addition & 1 deletion rosbag2/test/rosbag2/rosbag2_test_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class Rosbag2TestFixture : public Test
{
public:
Rosbag2TestFixture()
: database_name_(UnitTest::GetInstance()->current_test_info()->name())
: database_name_(std::string(UnitTest::GetInstance()->current_test_info()->name()) + ".db3")
{
std::string system_separator = "/";
#ifdef _WIN32
Expand Down
6 changes: 2 additions & 4 deletions rosbag2/test/rosbag2/rosbag2_typesupport_helpers_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,9 +54,7 @@ TEST(TypesupportHelpersTest, throws_exception_if_library_cannot_be_found) {

TEST(TypesupportHelpersTest, returns_c_type_info_for_valid_library) {
auto string_typesupport = rosbag2::get_typesupport("std_msgs/String");
auto pointcloud_typesupport = rosbag2::get_typesupport("sensor_msgs/PointCloud");

EXPECT_THAT(std::string(string_typesupport->typesupport_identifier), "rosidl_typesupport_cpp");
EXPECT_THAT(
std::string(pointcloud_typesupport->typesupport_identifier), "rosidl_typesupport_cpp");
EXPECT_THAT(std::string(string_typesupport->typesupport_identifier),
ContainsRegex("rosidl_typesupport"));
}
4 changes: 2 additions & 2 deletions rosbag2/test/rosbag2/rosbag2_write_all_integration_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#include "test_memory_management.hpp"

// TODO(Martin-Idel-SI): merge with other write and read tests once signal handling is sorted out
TEST_F(RosBag2IntegrationTestFixture, published_messages_from_multiple_topics_are_recorded)
TEST_F(RosBag2WriteIntegrationTestFixture, published_messages_from_multiple_topics_are_recorded)
{
std::string int_topic = "/int_topic";
auto serialized_int_bag_message = serialize_message<std_msgs::msg::UInt8>(int_topic, 10);
Expand All @@ -41,7 +41,7 @@ TEST_F(RosBag2IntegrationTestFixture, published_messages_from_multiple_topics_ar
start_publishing(serialized_int_bag_message, int_topic, 2);

start_recording_all_topics();
wait_for_publishers();
wait_for_publishers_to_stop();
stop_recording();

auto recorded_messages = get_messages(database_name_);
Expand Down
Loading

0 comments on commit 4bfa3c6

Please sign in to comment.