From 57720204fd401a59b5dffd12d5b8958e5ae2a5af Mon Sep 17 00:00:00 2001 From: Hiroki OTA Date: Wed, 17 Aug 2022 15:21:01 +0900 Subject: [PATCH] refactor(tier4_state_rviz_plugin): apply clang-tidy for readability-identifier-naming (#1595) * refactor(tier4_state_rviz_plugin): apply clang-tidy for readability-identifier-naming Signed-off-by: h-ohta * ci(pre-commit): autofix Signed-off-by: h-ohta Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../src/autoware_state_panel.cpp | 39 ++++++++++--------- .../src/autoware_state_panel.hpp | 22 +++++------ 2 files changed, 31 insertions(+), 30 deletions(-) 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 635f57299f798..50fba69281e56 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.cpp @@ -24,7 +24,7 @@ #include #include -inline std::string Bool2String(const bool var) { return var ? "True" : "False"; } +inline std::string bool_to_string(const bool var) { return var ? "True" : "False"; } using std::placeholders::_1; @@ -128,25 +128,26 @@ void AutowareStatePanel::onInitialize() raw_node_ = this->getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); sub_gate_mode_ = raw_node_->create_subscription( - "/control/current_gate_mode", 10, std::bind(&AutowareStatePanel::onGateMode, this, _1)); + "/control/current_gate_mode", 10, std::bind(&AutowareStatePanel::on_gate_mode, this, _1)); sub_selector_mode_ = raw_node_->create_subscription( "/control/external_cmd_selector/current_selector_mode", 10, - std::bind(&AutowareStatePanel::onSelectorMode, this, _1)); + std::bind(&AutowareStatePanel::on_selector_mode, this, _1)); sub_autoware_state_ = raw_node_->create_subscription( - "/autoware/state", 10, std::bind(&AutowareStatePanel::onAutowareState, this, _1)); + "/autoware/state", 10, std::bind(&AutowareStatePanel::on_autoware_state, this, _1)); sub_gear_ = raw_node_->create_subscription( - "/vehicle/status/gear_status", 10, std::bind(&AutowareStatePanel::onShift, this, _1)); + "/vehicle/status/gear_status", 10, std::bind(&AutowareStatePanel::on_shift, this, _1)); sub_engage_ = raw_node_->create_subscription( - "/api/external/get/engage", 10, std::bind(&AutowareStatePanel::onEngageStatus, this, _1)); + "/api/external/get/engage", 10, std::bind(&AutowareStatePanel::on_engage_status, this, _1)); sub_emergency_ = raw_node_->create_subscription( - "/api/autoware/get/emergency", 10, std::bind(&AutowareStatePanel::onEmergencyStatus, this, _1)); + "/api/autoware/get/emergency", 10, + std::bind(&AutowareStatePanel::on_emergency_status, this, _1)); client_engage_ = raw_node_->create_client( "/api/external/set/engage", rmw_qos_profile_services_default); @@ -166,7 +167,7 @@ void AutowareStatePanel::onInitialize() rclcpp::QoS{1}.transient_local()); } -void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) +void AutowareStatePanel::on_gate_mode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg) { switch (msg->data) { case tier4_control_msgs::msg::GateMode::AUTO: @@ -186,7 +187,7 @@ void AutowareStatePanel::onGateMode(const tier4_control_msgs::msg::GateMode::Con } } -void AutowareStatePanel::onSelectorMode( +void AutowareStatePanel::on_selector_mode( const tier4_control_msgs::msg::ExternalCommandSelectorMode::ConstSharedPtr msg) { switch (msg->data) { @@ -212,7 +213,7 @@ void AutowareStatePanel::onSelectorMode( } } -void AutowareStatePanel::onAutowareState( +void AutowareStatePanel::on_autoware_state( const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr msg) { if (msg->state == autoware_auto_system_msgs::msg::AutowareState::INITIALIZING) { @@ -239,7 +240,7 @@ void AutowareStatePanel::onAutowareState( } } -void AutowareStatePanel::onShift( +void AutowareStatePanel::on_shift( const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg) { switch (msg->report) { @@ -258,14 +259,14 @@ void AutowareStatePanel::onShift( } } -void AutowareStatePanel::onEngageStatus( +void AutowareStatePanel::on_engage_status( const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg) { current_engage_ = msg->engage; - engage_status_label_ptr_->setText(QString::fromStdString(Bool2String(current_engage_))); + engage_status_label_ptr_->setText(QString::fromStdString(bool_to_string(current_engage_))); } -void AutowareStatePanel::onEmergencyStatus( +void AutowareStatePanel::on_emergency_status( const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg) { current_emergency_ = msg->emergency; @@ -278,14 +279,14 @@ void AutowareStatePanel::onEmergencyStatus( } } -void AutowareStatePanel::onClickVelocityLimit() +void AutowareStatePanel::on_click_velocity_limit() { auto velocity_limit = std::make_shared(); velocity_limit->max_velocity = pub_velocity_limit_input_->value() / 3.6; pub_velocity_limit_->publish(*velocity_limit); } -void AutowareStatePanel::onClickAutowareEngage() +void AutowareStatePanel::on_click_autoware_engage() { using tier4_external_api_msgs::srv::Engage; @@ -306,7 +307,7 @@ void AutowareStatePanel::onClickAutowareEngage() }); } -void AutowareStatePanel::onClickEmergencyButton() +void AutowareStatePanel::on_click_emergency_button() { using tier4_external_api_msgs::msg::ResponseStatus; using tier4_external_api_msgs::srv::SetEmergency; @@ -327,7 +328,7 @@ void AutowareStatePanel::onClickEmergencyButton() } }); } -void AutowareStatePanel::onClickGateMode() +void AutowareStatePanel::on_click_gate_mode() { const auto data = gate_mode_label_ptr_->text().toStdString() == "AUTO" ? tier4_control_msgs::msg::GateMode::EXTERNAL @@ -337,7 +338,7 @@ void AutowareStatePanel::onClickGateMode() tier4_control_msgs::build().data(data)); } -void AutowareStatePanel::onClickPathChangeApproval() +void AutowareStatePanel::on_click_path_change_approval() { pub_path_change_approval_->publish( tier4_planning_msgs::build() 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 8c889b7280ceb..038f1205cd7d0 100644 --- a/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp +++ b/common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp @@ -45,20 +45,20 @@ class AutowareStatePanel : public rviz_common::Panel void onInitialize() override; public Q_SLOTS: // NOLINT for Qt - void onClickAutowareEngage(); - void onClickVelocityLimit(); - void onClickGateMode(); - void onClickPathChangeApproval(); - void onClickEmergencyButton(); + void on_click_autoware_engage(); + void on_click_velocity_limit(); + void on_click_gate_mode(); + void on_click_path_change_approval(); + void on_click_emergency_button(); protected: - void onGateMode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); - void onSelectorMode( + void on_gate_mode(const tier4_control_msgs::msg::GateMode::ConstSharedPtr msg); + void on_selector_mode( const tier4_control_msgs::msg::ExternalCommandSelectorMode::ConstSharedPtr msg); - void onAutowareState(const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr msg); - void onShift(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg); - void onEmergencyStatus(const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg); - void onEngageStatus(const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg); + void on_autoware_state(const autoware_auto_system_msgs::msg::AutowareState::ConstSharedPtr msg); + void on_shift(const autoware_auto_vehicle_msgs::msg::GearReport::ConstSharedPtr msg); + void on_emergency_status(const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg); + void on_engage_status(const tier4_external_api_msgs::msg::EngageStatus::ConstSharedPtr msg); rclcpp::Node::SharedPtr raw_node_; rclcpp::Subscription::SharedPtr sub_gate_mode_;