Skip to content

Commit

Permalink
Correct errors introduced by rebase
Browse files Browse the repository at this point in the history
Signed-off-by: Geoffrey Biggs <[email protected]>
  • Loading branch information
gbiggs committed Jun 1, 2022
1 parent 97dd138 commit 5a8a0a7
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 18 deletions.
1 change: 0 additions & 1 deletion rosbag2_transport/include/rosbag2_transport/player.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,6 @@ class Player : public rclcpp::Node
rclcpp::Service<rosbag2_interfaces::srv::SetRate>::SharedPtr srv_set_rate_;
rclcpp::Service<rosbag2_interfaces::srv::Play>::SharedPtr srv_play_;
rclcpp::Service<rosbag2_interfaces::srv::PlayNext>::SharedPtr srv_play_next_;
rclcpp::Service<rosbag2_interfaces::srv::PlayFor>::SharedPtr srv_play_for_;
rclcpp::Service<rosbag2_interfaces::srv::Burst>::SharedPtr srv_burst_;
rclcpp::Service<rosbag2_interfaces::srv::Seek>::SharedPtr srv_seek_;

Expand Down
19 changes: 2 additions & 17 deletions rosbag2_transport/src/rosbag2_transport/player.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -479,13 +479,12 @@ void Player::play_messages_from_queue(const rcutils_duration_value_t & play_unti
ready_to_play_from_queue_cv_.notify_all();
}
while (message_ptr != nullptr && rclcpp::ok()) {
rosbag2_storage::SerializedBagMessageSharedPtr message = *message_ptr;
if (play_until_time >= starting_time_ && message->time_stamp > play_until_time) {
if (play_until_time >= starting_time_ && message_ptr->time_stamp > play_until_time) {
break;
}
// Do not move on until sleep_until returns true
// It will always sleep, so this is not a tight busy loop on pause
while (rclcpp::ok() && !clock_->sleep_until(message->time_stamp)) {
while (rclcpp::ok() && !clock_->sleep_until(message_ptr->time_stamp)) {
if (std::atomic_exchange(&cancel_wait_for_next_message_, false)) {
break;
}
Expand Down Expand Up @@ -723,20 +722,6 @@ void Player::create_control_services()
{
response->success = play_next();
});
srv_play_for_ = create_service<rosbag2_interfaces::srv::PlayFor>(
"~/play_for",
[this](
const std::shared_ptr<rmw_request_id_t>/* request_header */,
const std::shared_ptr<rosbag2_interfaces::srv::PlayFor::Request> request,
const std::shared_ptr<rosbag2_interfaces::srv::PlayFor::Response> response)
{
const rcutils_duration_value_t duration =
static_cast<rcutils_duration_value_t>(request->duration.sec) *
static_cast<rcutils_duration_value_t>(1000000000) +
static_cast<rcutils_duration_value_t>(request->duration.nanosec);
play({duration});
response->success = true;
});
srv_burst_ = create_service<rosbag2_interfaces::srv::Burst>(
"~/burst",
[this](
Expand Down

0 comments on commit 5a8a0a7

Please sign in to comment.