Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(bag_time_manager_rviz_plugin): update create_client API to use rc… #2783

Merged
merged 5 commits into from
Feb 6, 2023
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 13 additions & 6 deletions common/bag_time_manager_rviz_plugin/src/bag_time_manager_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <qt5/QtWidgets/QWidget>
#include <rviz_common/display_context.hpp>

#include <rclcpp/version.h>

namespace rviz_plugins
{
BagTimeManagerPanel::BagTimeManagerPanel(QWidget * parent) : rviz_common::Panel(parent)
Expand Down Expand Up @@ -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<Pause>("/rosbag2_player/pause", rmw_qos_profile_services_default);
client_resume_ =
raw_node_->create_client<Resume>("/rosbag2_player/resume", rmw_qos_profile_services_default);
client_set_rate_ =
raw_node_->create_client<SetRate>("/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
isamu-takagi marked this conversation as resolved.
Show resolved Hide resolved
const auto qos_default = rclcpp::ServicesQoS();
#else
const auto qos_default = rmw_qos_profile_services_default;
#endif

client_pause_ = raw_node_->create_client<Pause>("/rosbag2_player/pause", qos_default);
client_resume_ = raw_node_->create_client<Resume>("/rosbag2_player/resume", qos_default);
client_set_rate_ = raw_node_->create_client<SetRate>("/rosbag2_player/set_rate", qos_default);
}

void BagTimeManagerPanel::onPauseClicked()
Expand Down