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

build(iron): remove rmw_qos_profile_t #3809

Merged
merged 1 commit into from
May 25, 2023
Merged
Show file tree
Hide file tree
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
15 changes: 3 additions & 12 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,8 +21,6 @@
#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 @@ -69,16 +67,9 @@ void BagTimeManagerPanel::onInitialize()
{
raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();

// 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<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);
client_pause_ = raw_node_->create_client<Pause>("/rosbag2_player/pause");
client_resume_ = raw_node_->create_client<Resume>("/rosbag2_player/resume");
client_set_rate_ = raw_node_->create_client<SetRate>("/rosbag2_player/set_rate");
}

void BagTimeManagerPanel::onPauseClicked()
Expand Down
8 changes: 4 additions & 4 deletions common/rtc_manager_rviz_plugin/src/rtc_manager_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -255,14 +255,14 @@ void RTCManagerPanel::onInitialize()
{
raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node();

client_rtc_commands_ = raw_node_->create_client<CooperateCommands>(
"/api/external/set/rtc_commands", rmw_qos_profile_services_default);
client_rtc_commands_ =
raw_node_->create_client<CooperateCommands>("/api/external/set/rtc_commands");

for (size_t i = 0; i < auto_modes_.size(); i++) {
auto & a = auto_modes_.at(i);
// auto mode
a->enable_auto_mode_cli = raw_node_->create_client<AutoMode>(
enable_auto_mode_namespace_ + "/" + a->module_name, rmw_qos_profile_services_default);
a->enable_auto_mode_cli =
raw_node_->create_client<AutoMode>(enable_auto_mode_namespace_ + "/" + a->module_name);
}

sub_rtc_status_ = raw_node_->create_subscription<CooperateStatusArray>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,22 +61,20 @@ void AutowareAutomaticGoalSender::initCommunication(rclcpp::Node * node)
"/api/operation_mode/state", rclcpp::QoS{1}.transient_local(),
std::bind(&AutowareAutomaticGoalSender::onOperationMode, this, std::placeholders::_1));

cli_change_to_autonomous_ = node->create_client<ChangeOperationMode>(
"/api/operation_mode/change_to_autonomous", rmw_qos_profile_services_default);
cli_change_to_autonomous_ =
node->create_client<ChangeOperationMode>("/api/operation_mode/change_to_autonomous");

cli_change_to_stop_ = node->create_client<ChangeOperationMode>(
"/api/operation_mode/change_to_stop", rmw_qos_profile_services_default);
cli_change_to_stop_ =
node->create_client<ChangeOperationMode>("/api/operation_mode/change_to_stop");

// Planning
sub_route_ = node->create_subscription<RouteState>(
"/api/routing/state", rclcpp::QoS{1}.transient_local(),
std::bind(&AutowareAutomaticGoalSender::onRoute, this, std::placeholders::_1));

cli_clear_route_ =
node->create_client<ClearRoute>("/api/routing/clear_route", rmw_qos_profile_services_default);
cli_clear_route_ = node->create_client<ClearRoute>("/api/routing/clear_route");

cli_set_route_ = node->create_client<SetRoutePoints>(
"/api/routing/set_route_points", rmw_qos_profile_services_default);
cli_set_route_ = node->create_client<SetRoutePoints>("/api/routing/set_route_points");
}

// Sub
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,8 +176,7 @@ void ManualController::onInitialize()
sub_gear_ = raw_node_->create_subscription<GearReport>(
"/vehicle/status/gear_status", 10, std::bind(&ManualController::onGear, this, _1));

client_engage_ = raw_node_->create_client<EngageSrv>(
"/api/autoware/set/engage", rmw_qos_profile_services_default);
client_engage_ = raw_node_->create_client<EngageSrv>("/api/autoware/set/engage");

pub_gate_mode_ = raw_node_->create_publisher<GateMode>("/control/gate_mode_cmd", rclcpp::QoS(1));

Expand Down
32 changes: 15 additions & 17 deletions common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -219,31 +219,30 @@ void AutowareStatePanel::onInitialize()
"/api/operation_mode/state", rclcpp::QoS{1}.transient_local(),
std::bind(&AutowareStatePanel::onOperationMode, this, _1));

client_change_to_autonomous_ = raw_node_->create_client<ChangeOperationMode>(
"/api/operation_mode/change_to_autonomous", rmw_qos_profile_services_default);
client_change_to_autonomous_ =
raw_node_->create_client<ChangeOperationMode>("/api/operation_mode/change_to_autonomous");

client_change_to_stop_ = raw_node_->create_client<ChangeOperationMode>(
"/api/operation_mode/change_to_stop", rmw_qos_profile_services_default);
client_change_to_stop_ =
raw_node_->create_client<ChangeOperationMode>("/api/operation_mode/change_to_stop");

client_change_to_local_ = raw_node_->create_client<ChangeOperationMode>(
"/api/operation_mode/change_to_local", rmw_qos_profile_services_default);
client_change_to_local_ =
raw_node_->create_client<ChangeOperationMode>("/api/operation_mode/change_to_local");

client_change_to_remote_ = raw_node_->create_client<ChangeOperationMode>(
"/api/operation_mode/change_to_remote", rmw_qos_profile_services_default);
client_change_to_remote_ =
raw_node_->create_client<ChangeOperationMode>("/api/operation_mode/change_to_remote");

client_enable_autoware_control_ = raw_node_->create_client<ChangeOperationMode>(
"/api/operation_mode/enable_autoware_control", rmw_qos_profile_services_default);
client_enable_autoware_control_ =
raw_node_->create_client<ChangeOperationMode>("/api/operation_mode/enable_autoware_control");

client_enable_direct_control_ = raw_node_->create_client<ChangeOperationMode>(
"/api/operation_mode/disable_autoware_control", rmw_qos_profile_services_default);
client_enable_direct_control_ =
raw_node_->create_client<ChangeOperationMode>("/api/operation_mode/disable_autoware_control");

// Routing
sub_route_ = raw_node_->create_subscription<RouteState>(
"/api/routing/state", rclcpp::QoS{1}.transient_local(),
std::bind(&AutowareStatePanel::onRoute, this, _1));

client_clear_route_ = raw_node_->create_client<ClearRoute>(
"/api/routing/clear_route", rmw_qos_profile_services_default);
client_clear_route_ = raw_node_->create_client<ClearRoute>("/api/routing/clear_route");

// Localization
sub_localization_ = raw_node_->create_subscription<LocalizationInitializationState>(
Expand All @@ -255,8 +254,7 @@ void AutowareStatePanel::onInitialize()
"/api/motion/state", rclcpp::QoS{1}.transient_local(),
std::bind(&AutowareStatePanel::onMotion, this, _1));

client_accept_start_ = raw_node_->create_client<AcceptStart>(
"/api/motion/accept_start", rmw_qos_profile_services_default);
client_accept_start_ = raw_node_->create_client<AcceptStart>("/api/motion/accept_start");

// FailSafe
sub_mrm_ = raw_node_->create_subscription<MRMState>(
Expand All @@ -271,7 +269,7 @@ void AutowareStatePanel::onInitialize()
"/api/autoware/get/emergency", 10, std::bind(&AutowareStatePanel::onEmergencyStatus, this, _1));

client_emergency_stop_ = raw_node_->create_client<tier4_external_api_msgs::srv::SetEmergency>(
"/api/autoware/set/emergency", rmw_qos_profile_services_default);
"/api/autoware/set/emergency");

pub_velocity_limit_ = raw_node_->create_publisher<tier4_planning_msgs::msg::VelocityLimit>(
"/planning/scenario_planning/max_velocity_default", rclcpp::QoS{1}.transient_local());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -511,8 +511,8 @@ AutowareJoyControllerNode::AutowareJoyControllerNode(const rclcpp::NodeOptions &
RCLCPP_INFO(get_logger(), "Waiting for emergency_stop service connection...");
}

client_autoware_engage_ = this->create_client<tier4_external_api_msgs::srv::Engage>(
"service/autoware_engage", rmw_qos_profile_services_default);
client_autoware_engage_ =
this->create_client<tier4_external_api_msgs::srv::Engage>("service/autoware_engage");

// Timer
initTimer(1.0 / update_rate_);
Expand Down
4 changes: 2 additions & 2 deletions localization/ndt_scan_matcher/src/map_update_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ MapUpdateModule::MapUpdateModule(
&MapUpdateModule::service_ndt_align, this, std::placeholders::_1, std::placeholders::_2),
rclcpp::ServicesQoS().get_rmw_qos_profile(), map_callback_group_);

pcd_loader_client_ = node->create_client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>(
"pcd_loader_service", rmw_qos_profile_services_default);
pcd_loader_client_ =
node->create_client<autoware_map_msgs::srv::GetDifferentialPointCloudMap>("pcd_loader_service");
while (!pcd_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) {
RCLCPP_INFO(
logger_,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ RTCAutoModeManagerInterface::RTCAutoModeManagerInterface(
using std::placeholders::_2;

// Service client
enable_cli_ = node->create_client<AutoMode>(
enable_auto_mode_namespace_ + "/internal/" + module_name, rmw_qos_profile_services_default);
enable_cli_ =
node->create_client<AutoMode>(enable_auto_mode_namespace_ + "/internal/" + module_name);

while (!enable_cli_->wait_for_service(1s)) {
if (!rclcpp::ok()) {
Expand Down
3 changes: 1 addition & 2 deletions planning/rtc_replayer/src/rtc_replayer_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,7 @@ RTCReplayerNode::RTCReplayerNode(const rclcpp::NodeOptions & node_options)
{
sub_statuses_ = create_subscription<CooperateStatusArray>(
"/debug/rtc_status", 1, std::bind(&RTCReplayerNode::onCooperateStatus, this, _1));
client_rtc_commands_ = create_client<CooperateCommands>(
"/api/external/set/rtc_commands", rmw_qos_profile_services_default);
client_rtc_commands_ = create_client<CooperateCommands>("/api/external/set/rtc_commands");
}

void RTCReplayerNode::onCooperateStatus(const CooperateStatusArray::ConstSharedPtr msg)
Expand Down