diff --git a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp b/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp index dde3f10e9b554..c2ed9f0b4bc1b 100644 --- a/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp +++ b/common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp @@ -21,6 +21,8 @@ #include #include +#include + namespace rviz_plugins { BagTimeManagerPanel::BagTimeManagerPanel(QWidget * parent) : rviz_common::Panel(parent) @@ -66,12 +68,17 @@ BagTimeManagerPanel::BagTimeManagerPanel(QWidget * parent) : rviz_common::Panel( void BagTimeManagerPanel::onInitialize() { raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); - client_pause_ = - raw_node_->create_client("/rosbag2_player/pause", rmw_qos_profile_services_default); - client_resume_ = - raw_node_->create_client("/rosbag2_player/resume", rmw_qos_profile_services_default); - client_set_rate_ = - raw_node_->create_client("/rosbag2_player/set_rate", rmw_qos_profile_services_default); + +// APIs taking rclcpp::QoS objects are only available in ROS 2 Iron and higher +#if RCLCPP_VERSION_MAJOR >= 18 + const auto qos_default = rclcpp::ServicesQoS(); +#else + const auto qos_default = rmw_qos_profile_services_default; +#endif + + client_pause_ = raw_node_->create_client("/rosbag2_player/pause", qos_default); + client_resume_ = raw_node_->create_client("/rosbag2_player/resume", qos_default); + client_set_rate_ = raw_node_->create_client("/rosbag2_player/set_rate", qos_default); } void BagTimeManagerPanel::onPauseClicked()