From 17d24ae7070dc3082b3d6aec2de6c2c06fa3afd3 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 1 Jul 2024 14:13:52 +0900 Subject: [PATCH] fix(autoware_joy_controller): add virtual destructor to autoware_joy_controller (#7760) Signed-off-by: Y.Hisaki --- .../include/autoware/joy_controller/joy_controller.hpp | 2 -- .../joy_controller/joy_converter/g29_joy_converter.hpp | 6 ++++-- .../joy_controller/joy_converter/joy_converter_base.hpp | 4 ++-- control/autoware_joy_controller/src/joy_controller_node.cpp | 5 ++--- 4 files changed, 8 insertions(+), 9 deletions(-) diff --git a/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp b/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp index fd2d89f446dbb..a4dcbc841696e 100644 --- a/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp +++ b/control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp @@ -33,7 +33,6 @@ #include #include -#include #include #include @@ -110,7 +109,6 @@ class AutowareJoyControllerNode : public rclcpp::Node autoware_control_msgs::msg::Control prev_control_command_; tier4_external_api_msgs::msg::ControlCommand prev_external_control_command_; GearShiftType prev_shift_ = tier4_external_api_msgs::msg::GearShift::NONE; - TurnSignalType prev_turn_signal_ = tier4_external_api_msgs::msg::TurnSignal::NONE; GateModeType prev_gate_mode_ = tier4_control_msgs::msg::GateMode::AUTO; // Timer diff --git a/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/g29_joy_converter.hpp b/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/g29_joy_converter.hpp index ea253e86305b7..28c424e7d6452 100644 --- a/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/g29_joy_converter.hpp +++ b/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/g29_joy_converter.hpp @@ -17,6 +17,8 @@ #include "autoware/joy_controller/joy_converter/joy_converter_base.hpp" +#include + namespace autoware::joy_controller { class G29JoyConverter : public JoyConverterBase @@ -27,7 +29,7 @@ class G29JoyConverter : public JoyConverterBase float accel() const { constexpr float eps = 0.0000001; - if (std::fabs(AccelPedal()) < eps) { + if (std::abs(AccelPedal()) < eps) { return 0.0f; } return (AccelPedal() + 1.0f) / 2; @@ -36,7 +38,7 @@ class G29JoyConverter : public JoyConverterBase float brake() const { constexpr float eps = 0.0000001; - if (std::fabs(BrakePedal()) < eps) { + if (std::abs(BrakePedal()) < eps) { return 0.0f; } return (BrakePedal() + 1.0f) / 2; diff --git a/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/joy_converter_base.hpp b/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/joy_converter_base.hpp index fa6081721511c..6deae0445bf0b 100644 --- a/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/joy_converter_base.hpp +++ b/control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/joy_converter_base.hpp @@ -17,8 +17,6 @@ #include -#include - namespace autoware::joy_controller { class JoyConverterBase @@ -49,6 +47,8 @@ class JoyConverterBase virtual bool vehicle_engage() const = 0; virtual bool vehicle_disengage() const = 0; + + virtual ~JoyConverterBase() = default; }; } // namespace autoware::joy_controller diff --git a/control/autoware_joy_controller/src/joy_controller_node.cpp b/control/autoware_joy_controller/src/joy_controller_node.cpp index cab15c93d753f..378109eacc574 100644 --- a/control/autoware_joy_controller/src/joy_controller_node.cpp +++ b/control/autoware_joy_controller/src/joy_controller_node.cpp @@ -23,7 +23,6 @@ #include #include #include -#include namespace { @@ -404,8 +403,8 @@ void AutowareJoyControllerNode::sendEmergencyRequest(bool emergency) request->emergency = emergency; client_emergency_stop_->async_send_request( - request, [this, emergency]( - rclcpp::Client::SharedFuture result) { + request, + [this](rclcpp::Client::SharedFuture result) { auto response = result.get(); if (tier4_api_utils::is_success(response->status)) { RCLCPP_INFO(get_logger(), "service succeeded");