From a9d81db67b0ccfed554953717a18fe595acd7962 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 13 Dec 2024 16:07:38 +0900 Subject: [PATCH] Update some member functions of `FieldOperatorApplication` to be non-virtual Signed-off-by: yamacir-kit --- .../concealer/field_operator_application.hpp | 13 ++++----- ...ator_application_for_autoware_universe.hpp | 17 +---------- .../concealer/service_with_validation.hpp | 3 +- .../src/field_operator_application.cpp | 4 ++- ...ator_application_for_autoware_universe.cpp | 28 ------------------- 5 files changed, 11 insertions(+), 54 deletions(-) diff --git a/external/concealer/include/concealer/field_operator_application.hpp b/external/concealer/include/concealer/field_operator_application.hpp index 4eae6602839..73723d838d9 100644 --- a/external/concealer/include/concealer/field_operator_application.hpp +++ b/external/concealer/include/concealer/field_operator_application.hpp @@ -145,7 +145,7 @@ struct FieldOperatorApplication : public rclcpp::Node, SubscriberWrapper getMrmState; SubscriberWrapper getPathWithLaneId; SubscriberWrapper getTrajectory; - SubscriberWrapper getTurnIndicatorsCommandImpl; + SubscriberWrapper getTurnIndicatorsCommand; ServiceWithValidation requestClearRoute; ServiceWithValidation requestCooperateCommands; @@ -202,13 +202,13 @@ struct FieldOperatorApplication : public rclcpp::Node, virtual auto clearRoute() -> void = 0; - virtual auto getAutowareStateName() const -> std::string = 0; + auto getAutowareStateName() const { return autoware_state; } - virtual auto getMinimumRiskManeuverBehaviorName() const -> std::string = 0; + auto getMinimumRiskManeuverBehaviorName() const { return minimum_risk_maneuver_behavior; } - virtual auto getMinimumRiskManeuverStateName() const -> std::string = 0; + auto getMinimumRiskManeuverStateName() const { return minimum_risk_maneuver_state; } - virtual auto getEmergencyStateName() const -> std::string = 0; + auto getEmergencyStateName() const { return minimum_risk_maneuver_state; } virtual auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray = 0; @@ -216,9 +216,6 @@ struct FieldOperatorApplication : public rclcpp::Node, virtual auto requestAutoModeForCooperation(const std::string &, bool) -> void = 0; - virtual auto getTurnIndicatorsCommand() const - -> autoware_vehicle_msgs::msg::TurnIndicatorsCommand = 0; - virtual auto rethrow() const noexcept(false) -> void; virtual auto sendCooperateCommand(const std::string &, const std::string &) -> void = 0; diff --git a/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp b/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp index 1d4cc1bdc04..08332cfbd80 100644 --- a/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp +++ b/external/concealer/include/concealer/field_operator_application_for_autoware_universe.hpp @@ -22,11 +22,7 @@ namespace concealer template <> struct FieldOperatorApplicationFor : public FieldOperatorApplication { - template - CONCEALER_PUBLIC explicit FieldOperatorApplicationFor(Ts &&... xs) - : FieldOperatorApplication(std::forward(xs)...) - { - } + using FieldOperatorApplication::FieldOperatorApplication; auto engage() -> void override; @@ -34,19 +30,8 @@ struct FieldOperatorApplicationFor : public FieldOperatorAppli auto engaged() const -> bool override; - auto getAutowareStateName() const -> std::string override; - auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray override; - auto getTurnIndicatorsCommand() const - -> autoware_vehicle_msgs::msg::TurnIndicatorsCommand override; - - auto getEmergencyStateName() const -> std::string override; - - auto getMinimumRiskManeuverBehaviorName() const -> std::string override; - - auto getMinimumRiskManeuverStateName() const -> std::string override; - auto initialize(const geometry_msgs::msg::Pose &) -> void override; auto plan(const std::vector &) -> void override; diff --git a/external/concealer/include/concealer/service_with_validation.hpp b/external/concealer/include/concealer/service_with_validation.hpp index 1b01488224e..256cf30f062 100644 --- a/external/concealer/include/concealer/service_with_validation.hpp +++ b/external/concealer/include/concealer/service_with_validation.hpp @@ -73,7 +73,8 @@ class ServiceWithValidation { public: template - explicit TimeoutError(Ts &&... xs) : common::scenario_simulator_exception::Error(std::forward(xs)...) + explicit TimeoutError(Ts &&... xs) + : common::scenario_simulator_exception::Error(std::forward(xs)...) { } }; diff --git a/external/concealer/src/field_operator_application.cpp b/external/concealer/src/field_operator_application.cpp index 71af9a2ae8a..3d17e961456 100644 --- a/external/concealer/src/field_operator_application.cpp +++ b/external/concealer/src/field_operator_application.cpp @@ -43,6 +43,7 @@ auto toAutowareStateString(std::uint8_t state) -> char const * #undef CASE } +// clang-format off FieldOperatorApplication::FieldOperatorApplication(const pid_t pid) : rclcpp::Node("concealer_user", "simulation", rclcpp::NodeOptions().use_global_arguments(false)), process_id(pid), @@ -113,7 +114,7 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid) }), getPathWithLaneId("/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id", rclcpp::QoS(1), *this), getTrajectory("/api/iv_msgs/planning/scenario_planning/trajectory", rclcpp::QoS(1), *this), - getTurnIndicatorsCommandImpl("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this), + getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this), requestClearRoute("/api/routing/clear_route", *this), requestCooperateCommands("/api/external/set/rtc_commands", *this), requestEngage("/api/external/set/engage", *this), @@ -125,6 +126,7 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid) requestEnableAutowareControl("/api/operation_mode/enable_autoware_control", *this) { } +// clang-format on FieldOperatorApplication::~FieldOperatorApplication() { diff --git a/external/concealer/src/field_operator_application_for_autoware_universe.cpp b/external/concealer/src/field_operator_application_for_autoware_universe.cpp index ae5707fc62f..13a4404b1d6 100644 --- a/external/concealer/src/field_operator_application_for_autoware_universe.cpp +++ b/external/concealer/src/field_operator_application_for_autoware_universe.cpp @@ -350,34 +350,6 @@ auto FieldOperatorApplicationFor::getWaypoints() const return waypoints; } -auto FieldOperatorApplicationFor::getTurnIndicatorsCommand() const - -> autoware_vehicle_msgs::msg::TurnIndicatorsCommand -{ - return getTurnIndicatorsCommandImpl(); -} - -auto FieldOperatorApplicationFor::getAutowareStateName() const -> std::string -{ - return autoware_state; -} - -auto FieldOperatorApplicationFor::getEmergencyStateName() const -> std::string -{ - return minimum_risk_maneuver_state; -} - -auto FieldOperatorApplicationFor::getMinimumRiskManeuverBehaviorName() const - -> std::string -{ - return minimum_risk_maneuver_behavior; -} - -auto FieldOperatorApplicationFor::getMinimumRiskManeuverStateName() const - -> std::string -{ - return minimum_risk_maneuver_state; -} - auto FieldOperatorApplicationFor::setVelocityLimit(double velocity_limit) -> void { task_queue.delay([this, velocity_limit]() {