diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp index 585ea34a9120d..635f57299f798 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -287,8 +287,10 @@ void AutowareStatePanel::onClickVelocityLimit() void AutowareStatePanel::onClickAutowareEngage() { - auto req = std::make_shared(); - req->engage = current_engage_ ? false : true; + using tier4_external_api_msgs::srv::Engage; + + auto req = std::make_shared(); + req->engage = !current_engage_; RCLCPP_INFO(raw_node_->get_logger(), "client request"); @@ -297,30 +299,27 @@ void AutowareStatePanel::onClickAutowareEngage() return; } - client_engage_->async_send_request( - req, [this](rclcpp::Client::SharedFuture result) { - RCLCPP_INFO( - raw_node_->get_logger(), "Status: %d, %s", result.get()->status.code, - result.get()->status.message.c_str()); - }); + client_engage_->async_send_request(req, [this](rclcpp::Client::SharedFuture result) { + RCLCPP_INFO( + raw_node_->get_logger(), "Status: %d, %s", result.get()->status.code, + result.get()->status.message.c_str()); + }); } void AutowareStatePanel::onClickEmergencyButton() { - auto request = std::make_shared(); - if (current_emergency_) { - request->emergency = false; - } else { - request->emergency = true; - } + using tier4_external_api_msgs::msg::ResponseStatus; + using tier4_external_api_msgs::srv::SetEmergency; + + auto request = std::make_shared(); + request->emergency = !current_emergency_; + RCLCPP_INFO(raw_node_->get_logger(), request->emergency ? "Set Emergency" : "Clear Emergency"); client_emergency_stop_->async_send_request( - request, - [this]([[maybe_unused]] rclcpp::Client::SharedFuture - result) { - auto response = result.get(); - if (response->status.code == tier4_external_api_msgs::msg::ResponseStatus::SUCCESS) { + request, [this](rclcpp::Client::SharedFuture result) { + const auto & response = result.get(); + if (response->status.code == ResponseStatus::SUCCESS) { RCLCPP_INFO(raw_node_->get_logger(), "service succeeded"); } else { RCLCPP_WARN( diff --git a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp index 1833d75e422ae..8c889b7280ceb 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -44,7 +44,7 @@ class AutowareStatePanel : public rviz_common::Panel explicit AutowareStatePanel(QWidget * parent = nullptr); void onInitialize() override; -public Q_SLOTS: +public Q_SLOTS: // NOLINT for Qt void onClickAutowareEngage(); void onClickVelocityLimit(); void onClickGateMode(); @@ -89,8 +89,8 @@ public Q_SLOTS: QSpinBox * pub_velocity_limit_input_; QPushButton * emergency_button_ptr_; - bool current_engage_; - bool current_emergency_; + bool current_engage_{false}; + bool current_emergency_{false}; }; } // namespace rviz_plugins