Skip to content

Commit 19e0b90

Browse files
authored
[kilted] Follow-up on "Fix for multibag replay stagnation (#2158)" (#2182)
* [kilted] Follow-up on "Fix for multibag replay stagnation (#2158)" - Fix for returning a dangling reference from the "Player::get_storage_options()" method - Also deprecate "Player::get_storage_options()" method in favor of the "get_all_storage_options()"" Signed-off-by: Michael Orlov <michael.orlov@apex.ai> * Remove deprecation warning for the get_storage_options() per code review Signed-off-by: Michael Orlov <michael.orlov@apex.ai> --------- Signed-off-by: Michael Orlov <michael.orlov@apex.ai>
1 parent 5434a78 commit 19e0b90

File tree

1 file changed

+8
-3
lines changed

1 file changed

+8
-3
lines changed

rosbag2_transport/src/rosbag2_transport/player.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -241,7 +241,7 @@ class PlayerImpl
241241
size_t get_number_of_registered_on_play_msg_post_callbacks();
242242

243243
/// \brief Getter for the first of the currently stored storage options
244-
/// \return Copy of the first of the currently stored storage options
244+
/// \return Reference to the first of the currently stored storage options
245245
const rosbag2_storage::StorageOptions & get_storage_options();
246246

247247
/// \brief Getter for the currently stored storage options
@@ -435,6 +435,9 @@ class PlayerImpl
435435
return l->send_timestamp > r->send_timestamp;
436436
}
437437
} bag_message_chronological_send_timestamp_comparator;
438+
439+
// Note: The first_storage_options_ is used as a workaround for deprecated get_storage_options()
440+
rosbag2_storage::StorageOptions first_storage_options_;
438441
};
439442

440443
PlayerImpl::BagMessageComparator PlayerImpl::get_bag_message_comparator(const MessageOrder & order)
@@ -2182,10 +2185,12 @@ void PlayerImpl::publish_clock_update(const rclcpp::Time & time)
21822185
const rosbag2_storage::StorageOptions & PlayerImpl::get_storage_options()
21832186
{
21842187
auto all_storage_options = get_all_storage_options();
2185-
if (all_storage_options.size() < 1) {
2188+
if (all_storage_options.empty()) {
21862189
throw std::runtime_error("Storage options not available.");
21872190
}
2188-
return all_storage_options[0];
2191+
first_storage_options_ = all_storage_options[0];
2192+
// Note: Use first_storage_options_ as return value to keep the reference valid
2193+
return first_storage_options_;
21892194
}
21902195

21912196
std::vector<rosbag2_storage::StorageOptions> PlayerImpl::get_all_storage_options()

0 commit comments

Comments
 (0)