From db5e4fc4d8ea42300bb319c08588236b62a97a54 Mon Sep 17 00:00:00 2001 From: Martin Idel Date: Tue, 21 Aug 2018 13:22:36 +0200 Subject: [PATCH] Minor cleanup --- rosbag2/src/rosbag2/rosbag2.cpp | 1 - rosbag2/test/rosbag2/rosbag2_test_fixture.hpp | 3 +-- .../sqlite/sqlite_storage.cpp | 14 ++++++++------ 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/rosbag2/src/rosbag2/rosbag2.cpp b/rosbag2/src/rosbag2/rosbag2.cpp index 81205994ba..2abc6c2e48 100644 --- a/rosbag2/src/rosbag2/rosbag2.cpp +++ b/rosbag2/src/rosbag2/rosbag2.cpp @@ -81,7 +81,6 @@ void Rosbag2::play(const std::string & file_name, const std::string & topic_name std::this_thread::sleep_for(std::chrono::milliseconds(500)); publisher->publish(string_message); } - rclcpp::spin_some(node); } } diff --git a/rosbag2/test/rosbag2/rosbag2_test_fixture.hpp b/rosbag2/test/rosbag2/rosbag2_test_fixture.hpp index eb7056a2d2..4737d9b5a7 100644 --- a/rosbag2/test/rosbag2/rosbag2_test_fixture.hpp +++ b/rosbag2/test/rosbag2/rosbag2_test_fixture.hpp @@ -99,8 +99,7 @@ class Rosbag2TestFixture : public Test if (storage) { while (storage->has_next()) { - auto message = storage->read_next(); - table_msgs.emplace_back(message); + table_msgs.push_back(storage->read_next()); } } return table_msgs; diff --git a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp index fe7c8f173c..c2f96088a2 100644 --- a/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp +++ b/rosbag2_storage_default_plugins/src/rosbag2_storage_default_plugins/sqlite/sqlite_storage.cpp @@ -72,24 +72,26 @@ std::shared_ptr SqliteStorage::read_next( // TODO(Martin-Idel-SI): improve sqlite_wrapper interface std::string message; database_->get_message(message, counter_++); - auto msg = std::make_shared(); auto payload = new rcutils_char_array_t; *payload = rcutils_get_zero_initialized_char_array(); - payload->allocator = rcutils_get_default_allocator(); - auto ret = rcutils_char_array_resize(payload, strlen(message.c_str()) + 1); + auto allocator = new rcutils_allocator_t; + *allocator = rcutils_get_default_allocator(); + auto ret = rcutils_char_array_init(payload, strlen(message.c_str()) + 1, allocator); if (ret != RCUTILS_RET_OK) { - RCUTILS_LOG_ERROR_NAMED("rosbag2_storage_default_plugins", - " Failed to destroy serialized bag message"); + throw std::runtime_error(std::string(" Failed to allocate serialized bag message ") + + rcutils_get_error_string_safe()); } memcpy(payload->buffer, message.c_str(), strlen(message.c_str()) + 1); + auto msg = std::make_shared(); + msg->time_stamp = 0; msg->serialized_data = std::shared_ptr(payload, [](rcutils_char_array_t * msg) { auto error = rcutils_char_array_fini(msg); delete msg; if (error != RCUTILS_RET_OK) { RCUTILS_LOG_ERROR_NAMED("rosbag2_storage_default_plugins", - " Failed to destroy serialized bag message"); + " Failed to destroy serialized bag message %s", rcutils_get_error_string_safe()); } }); return msg;