Skip to content

Commit

Permalink
Minor cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
Martin-Idel-SI committed Aug 21, 2018
1 parent be8599d commit db5e4fc
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 9 deletions.
1 change: 0 additions & 1 deletion rosbag2/src/rosbag2/rosbag2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
}

Expand Down
3 changes: 1 addition & 2 deletions rosbag2/test/rosbag2/rosbag2_test_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,24 +72,26 @@ std::shared_ptr<rosbag2_storage::SerializedBagMessage> SqliteStorage::read_next(
// TODO(Martin-Idel-SI): improve sqlite_wrapper interface
std::string message;
database_->get_message(message, counter_++);
auto msg = std::make_shared<rosbag2_storage::SerializedBagMessage>();
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<rosbag2_storage::SerializedBagMessage>();
msg->time_stamp = 0;
msg->serialized_data = std::shared_ptr<rcutils_char_array_t>(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;
Expand Down

0 comments on commit db5e4fc

Please sign in to comment.