Skip to content

Commit 9741bfc

Browse files
authored
Add public API to get player's starting time and playback duration (#2095)
* Bring getters for starting time and duration on rosbag2_transport layer Signed-off-by: Michael Orlov <[email protected]> * Bring getters for starting time and duration on rosbag2_py layer Signed-off-by: Michael Orlov <[email protected]> * Regenerate Python stub files (.pyi) Signed-off-by: Michael Orlov <[email protected]> --------- Signed-off-by: Michael Orlov <[email protected]>
1 parent e140ca4 commit 9741bfc

File tree

7 files changed

+141
-3
lines changed

7 files changed

+141
-3
lines changed

rosbag2_py/rosbag2_py/_transport.pyi

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,8 @@ class Player:
7272
def burst(self, num_messages) -> Any: ...
7373
@staticmethod
7474
def cancel() -> None: ...
75+
def get_playback_duration(self) -> int: ...
76+
def get_starting_time(self) -> int: ...
7577
def is_paused(self) -> bool: ...
7678
def pause(self) -> None: ...
7779
@overload

rosbag2_py/src/rosbag2_py/_transport.cpp

Lines changed: 37 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -311,7 +311,7 @@ class Player
311311
player_->resume();
312312
}
313313

314-
bool is_paused() const
314+
[[nodiscard]] bool is_paused() const
315315
{
316316
if (!player_) {
317317
throw std::runtime_error("Player is not initialized. Please use constructor with "
@@ -320,6 +320,24 @@ class Player
320320
return player_->is_paused();
321321
}
322322

323+
[[nodiscard]] int64_t get_starting_time() const
324+
{
325+
if (!player_) {
326+
throw std::runtime_error("Player is not initialized. Please use constructor with "
327+
"storage and play options.");
328+
}
329+
return player_->get_starting_time();
330+
}
331+
332+
[[nodiscard]] int64_t get_playback_duration() const
333+
{
334+
if (!player_) {
335+
throw std::runtime_error("Player is not initialized. Please use constructor with "
336+
"storage and play options.");
337+
}
338+
return player_->get_playback_duration();
339+
}
340+
323341
bool play_next()
324342
{
325343
if (!player_) {
@@ -1070,6 +1088,24 @@ PYBIND11_MODULE(_transport, m) {
10701088
&rosbag2_py::Player::is_paused,
10711089
"Whether the playback is currently paused.")
10721090

1091+
.def("get_starting_time",
1092+
&rosbag2_py::Player::get_starting_time,
1093+
R"pbdoc(
1094+
Get the starting time of the playback.
1095+
1096+
Returns:
1097+
int: The timestamp of the first message in nanoseconds.
1098+
)pbdoc")
1099+
1100+
.def("get_playback_duration",
1101+
&rosbag2_py::Player::get_playback_duration,
1102+
R"pbdoc(
1103+
Get the total duration of the playback.
1104+
1105+
Returns:
1106+
int: The total duration of the playback in nanoseconds.
1107+
)pbdoc")
1108+
10731109
.def("play_next", &rosbag2_py::Player::play_next,
10741110
R"pbdoc(
10751111
Playing next message from queue when in pause.

rosbag2_py/test/test_transport.py

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -148,6 +148,36 @@ def test_player_api(storage_id):
148148
ctx.shutdown()
149149

150150

151+
@pytest.mark.parametrize('storage_id', TESTED_STORAGE_IDS)
152+
def test_player_get_starting_time(storage_id):
153+
bag_path = str(RESOURCES_PATH / storage_id / 'talker')
154+
assert os.path.exists(bag_path), 'Could not find test bag file: ' + bag_path
155+
156+
storage_options, _ = get_rosbag_options(bag_path, storage_id)
157+
158+
play_options = rosbag2_py.PlayOptions()
159+
play_options.topics_to_filter = ['topic']
160+
161+
player = rosbag2_py.Player(storage_options, play_options, 'info', 'rosbag2_player_test')
162+
starting_time = player.get_starting_time()
163+
assert starting_time is not None, 'Expected a valid starting time'
164+
165+
166+
@pytest.mark.parametrize('storage_id', TESTED_STORAGE_IDS)
167+
def test_player_get_playback_duration(storage_id):
168+
bag_path = str(RESOURCES_PATH / storage_id / 'talker')
169+
assert os.path.exists(bag_path), 'Could not find test bag file: ' + bag_path
170+
171+
storage_options, _ = get_rosbag_options(bag_path, storage_id)
172+
173+
play_options = rosbag2_py.PlayOptions()
174+
play_options.topics_to_filter = ['topic']
175+
176+
player = rosbag2_py.Player(storage_options, play_options, 'info', 'rosbag2_player_test')
177+
playback_duration = player.get_playback_duration()
178+
assert playback_duration is not None, 'Expected a valid starting time'
179+
180+
151181
@pytest.mark.parametrize('storage_id', TESTED_STORAGE_IDS)
152182
def test_recorder_api(tmp_path, storage_id):
153183
bag_path = tmp_path / 'test_recorder_api'

rosbag2_transport/include/rosbag2_transport/player.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -252,6 +252,16 @@ class Player : public rclcpp::Node
252252
ROSBAG2_TRANSPORT_PUBLIC
253253
bool is_paused() const;
254254

255+
/// \brief Getter method for starting time of the playback.
256+
/// \return Returns timestamp of the first message in nanoseconds.
257+
ROSBAG2_TRANSPORT_PUBLIC
258+
rcutils_time_point_value_t get_starting_time() const;
259+
260+
/// \brief Getter method for playback duration
261+
/// \return Returns duration of the playback in nanoseconds.
262+
ROSBAG2_TRANSPORT_PUBLIC
263+
rcutils_duration_value_t get_playback_duration() const;
264+
255265
/// Return current playback rate.
256266
ROSBAG2_TRANSPORT_PUBLIC
257267
double get_rate() const;

rosbag2_transport/src/rosbag2_transport/player.cpp

Lines changed: 32 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,6 +120,14 @@ class PlayerImpl
120120
/// Return whether the playback is currently paused.
121121
bool is_paused() const;
122122

123+
/// \brief Getter method for starting time of the playback.
124+
/// \return Returns timestamp of the first message in nanoseconds.
125+
rcutils_time_point_value_t get_starting_time() const;
126+
127+
/// \brief Getter method for playback duration
128+
/// \return Returns duration of the playback in nanoseconds.
129+
rcutils_duration_value_t get_playback_duration() const;
130+
123131
/// Return current playback rate.
124132
double get_rate() const;
125133

@@ -380,7 +388,8 @@ class PlayerImpl
380388
// Whether we successfully played next
381389
std::atomic_bool play_next_result_{false};
382390

383-
rcutils_time_point_value_t starting_time_;
391+
rcutils_time_point_value_t starting_time_ = 0;
392+
rcutils_duration_value_t playback_duration_ = 0;
384393

385394
// control services
386395
rclcpp::Service<rosbag2_interfaces::srv::Pause>::SharedPtr srv_pause_;
@@ -524,6 +533,8 @@ PlayerImpl::PlayerImpl(
524533
starting_time_ += play_options_.start_offset;
525534
}
526535

536+
playback_duration_ = ending_time - starting_time_;
537+
527538
progress_bar_ = std::make_unique<PlayerProgressBar>(
528539
std::cout, starting_time_, ending_time,
529540
play_options.progress_bar_update_rate,
@@ -782,6 +793,16 @@ bool PlayerImpl::is_paused() const
782793
return clock_->is_paused();
783794
}
784795

796+
rcutils_time_point_value_t PlayerImpl::get_starting_time() const
797+
{
798+
return starting_time_;
799+
}
800+
801+
rcutils_duration_value_t PlayerImpl::get_playback_duration() const
802+
{
803+
return playback_duration_;
804+
}
805+
785806
double PlayerImpl::get_rate() const
786807
{
787808
return clock_->get_rate();
@@ -2274,6 +2295,16 @@ bool Player::is_paused() const
22742295
return pimpl_->is_paused();
22752296
}
22762297

2298+
rcutils_time_point_value_t Player::get_starting_time() const
2299+
{
2300+
return pimpl_->get_starting_time();
2301+
}
2302+
2303+
rcutils_duration_value_t Player::get_playback_duration() const
2304+
{
2305+
return pimpl_->get_playback_duration();
2306+
}
2307+
22772308
double Player::get_rate() const
22782309
{
22792310
return pimpl_->get_rate();

rosbag2_transport/test/rosbag2_transport/mock_sequential_reader.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -142,6 +142,10 @@ class MockSequentialReader : public rosbag2_cpp::reader_interfaces::BaseReaderIn
142142
std::chrono::nanoseconds(messages[0]->recv_timestamp));
143143
metadata_.starting_time = message_timestamp;
144144
}
145+
metadata_.duration = std::chrono::nanoseconds(messages.back()->recv_timestamp -
146+
std::chrono::duration_cast<std::chrono::nanoseconds>(
147+
metadata_.starting_time.time_since_epoch()).count());
148+
145149
messages_ = std::move(messages);
146150
topics_ = std::move(topics);
147151
}

rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp

Lines changed: 26 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,9 +56,12 @@ class PlayerTestFixture : public Rosbag2TransportTestFixture
5656
serialize_test_message("topic1", 0, primitive_message2)
5757
};
5858

59-
messages[0]->recv_timestamp = 100;
59+
messages[0]->send_timestamp = 80;
60+
messages[0]->recv_timestamp = 90;
6061
messages[1]->recv_timestamp = messages[0]->recv_timestamp +
6162
message_time_difference.nanoseconds();
63+
messages[1]->send_timestamp = messages[0]->send_timestamp +
64+
message_time_difference.nanoseconds();
6265

6366
prepared_mock_reader = std::make_unique<MockSequentialReader>();
6467
prepared_mock_reader->prepare(messages, topics_and_types);
@@ -78,6 +81,28 @@ class PlayerTestFixture : public Rosbag2TransportTestFixture
7881
std::unique_ptr<rosbag2_cpp::Reader> reader;
7982
};
8083

84+
TEST_F(PlayerTestFixture, get_starting_time_returns_correct_value)
85+
{
86+
auto player = std::make_shared<rosbag2_transport::Player>(
87+
std::move(reader), storage_options_, play_options_);
88+
89+
rcutils_time_point_value_t starting_time = player->get_starting_time();
90+
// The starting time is the time of the first message in the bag
91+
EXPECT_EQ(starting_time, messages[0]->recv_timestamp);
92+
}
93+
94+
TEST_F(PlayerTestFixture, get_playback_duration_returns_correct_value)
95+
{
96+
auto player = std::make_shared<rosbag2_transport::Player>(
97+
std::move(reader), storage_options_, play_options_);
98+
99+
auto playback_duration = player->get_playback_duration();
100+
// The playback duration is the time difference between the first and last message in the bag
101+
rcutils_duration_value_t expected_duration =
102+
messages.back()->recv_timestamp - messages[0]->recv_timestamp;
103+
EXPECT_EQ(playback_duration, expected_duration);
104+
}
105+
81106
TEST_F(PlayerTestFixture, playing_respects_relative_timing_of_stored_messages)
82107
{
83108
auto player = std::make_shared<rosbag2_transport::Player>(

0 commit comments

Comments
 (0)