Skip to content

Commit

Permalink
chore: requested changes
Browse files Browse the repository at this point in the history
Signed-off-by: Janosch Machowinski <J.Machowinski@cellumation.com>
  • Loading branch information
Janosch Machowinski authored and Janosch Machowinski committed Apr 10, 2024
1 parent 3b7d541 commit e4a9842
Showing 1 changed file with 3 additions and 11 deletions.
14 changes: 3 additions & 11 deletions rosbag2_transport/src/rosbag2_transport/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,6 @@ class RecorderImpl
rclcpp::Service<rosbag2_interfaces::srv::Resume>::SharedPtr srv_resume_;
rclcpp::Service<rosbag2_interfaces::srv::Snapshot>::SharedPtr srv_snapshot_;
rclcpp::Service<rosbag2_interfaces::srv::SplitBagfile>::SharedPtr srv_split_bagfile_;
bool rmw_has_time_stamping_support_ = true;

std::mutex start_stop_transition_mutex_;
std::mutex discovery_mutex_;
Expand Down Expand Up @@ -179,15 +178,6 @@ RecorderImpl::RecorderImpl(
"The /clock topic needs to be discovered to record with sim time.");
}

#if defined _WIN32
// ConnvextDDS on Windows does currently not support time stamping, therefore we disable the feature
if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") !=
std::string::npos)
{
rmw_has_time_stamping_support_ = false;
}
#endif

std::string key_str = enum_key_code_to_str(Recorder::kPauseResumeToggleKey);
toggle_paused_key_callback_handle_ =
keyboard_handler_->add_key_press_callback(
Expand Down Expand Up @@ -572,7 +562,9 @@ RecorderImpl::create_subscription(
const std::string & topic_name, const std::string & topic_type, const rclcpp::QoS & qos)
{
#ifdef _WIN32
if (!rmw_has_time_stamping_support_) {
if (std::string(rmw_get_implementation_identifier()).find("rmw_connextdds") !=
std::string::npos)
{
return node->create_generic_subscription(
topic_name,
topic_type,
Expand Down

0 comments on commit e4a9842

Please sign in to comment.