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

refactor(tier4_state_rviz_plugin): apply clang-tidy #1589

Merged
Merged
37 changes: 18 additions & 19 deletions common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,8 +287,10 @@ void AutowareStatePanel::onClickVelocityLimit()

void AutowareStatePanel::onClickAutowareEngage()
{
auto req = std::make_shared<tier4_external_api_msgs::srv::Engage::Request>();
req->engage = current_engage_ ? false : true;
using tier4_external_api_msgs::srv::Engage;

auto req = std::make_shared<Engage::Request>();
req->engage = !current_engage_;

RCLCPP_INFO(raw_node_->get_logger(), "client request");

Expand All @@ -297,30 +299,27 @@ void AutowareStatePanel::onClickAutowareEngage()
return;
}

client_engage_->async_send_request(
req, [this](rclcpp::Client<tier4_external_api_msgs::srv::Engage>::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<Engage>::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<tier4_external_api_msgs::srv::SetEmergency::Request>();
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<SetEmergency::Request>();
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<tier4_external_api_msgs::srv::SetEmergency>::SharedFuture
result) {
auto response = result.get();
if (response->status.code == tier4_external_api_msgs::msg::ResponseStatus::SUCCESS) {
request, [this](rclcpp::Client<SetEmergency>::SharedFuture result) {
const auto & response = result.get();
if (response->status.code == ResponseStatus::SUCCESS) {
RCLCPP_INFO(raw_node_->get_logger(), "service succeeded");
} else {
RCLCPP_WARN(
Expand Down
6 changes: 3 additions & 3 deletions common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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
Expand Down