Skip to content

Commit f09b24a

Browse files
yhisakitby-udel
authored andcommitted
fix(autoware_joy_controller): add virtual destructor to autoware_joy_controller (autowarefoundation#7760)
Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
1 parent a17c5cf commit f09b24a

File tree

4 files changed

+8
-9
lines changed

4 files changed

+8
-9
lines changed

control/autoware_joy_controller/include/autoware/joy_controller/joy_controller.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,6 @@
3333
#include <tier4_external_api_msgs/srv/engage.hpp>
3434
#include <tier4_external_api_msgs/srv/set_emergency.hpp>
3535

36-
#include <algorithm>
3736
#include <memory>
3837
#include <string>
3938

@@ -110,7 +109,6 @@ class AutowareJoyControllerNode : public rclcpp::Node
110109
autoware_control_msgs::msg::Control prev_control_command_;
111110
tier4_external_api_msgs::msg::ControlCommand prev_external_control_command_;
112111
GearShiftType prev_shift_ = tier4_external_api_msgs::msg::GearShift::NONE;
113-
TurnSignalType prev_turn_signal_ = tier4_external_api_msgs::msg::TurnSignal::NONE;
114112
GateModeType prev_gate_mode_ = tier4_control_msgs::msg::GateMode::AUTO;
115113

116114
// Timer

control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/g29_joy_converter.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717

1818
#include "autoware/joy_controller/joy_converter/joy_converter_base.hpp"
1919

20+
#include <cstdlib>
21+
2022
namespace autoware::joy_controller
2123
{
2224
class G29JoyConverter : public JoyConverterBase
@@ -27,7 +29,7 @@ class G29JoyConverter : public JoyConverterBase
2729
float accel() const
2830
{
2931
constexpr float eps = 0.0000001;
30-
if (std::fabs(AccelPedal()) < eps) {
32+
if (std::abs(AccelPedal()) < eps) {
3133
return 0.0f;
3234
}
3335
return (AccelPedal() + 1.0f) / 2;
@@ -36,7 +38,7 @@ class G29JoyConverter : public JoyConverterBase
3638
float brake() const
3739
{
3840
constexpr float eps = 0.0000001;
39-
if (std::fabs(BrakePedal()) < eps) {
41+
if (std::abs(BrakePedal()) < eps) {
4042
return 0.0f;
4143
}
4244
return (BrakePedal() + 1.0f) / 2;

control/autoware_joy_controller/include/autoware/joy_controller/joy_converter/joy_converter_base.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,6 @@
1717

1818
#include <sensor_msgs/msg/joy.hpp>
1919

20-
#include <algorithm>
21-
2220
namespace autoware::joy_controller
2321
{
2422
class JoyConverterBase
@@ -49,6 +47,8 @@ class JoyConverterBase
4947

5048
virtual bool vehicle_engage() const = 0;
5149
virtual bool vehicle_disengage() const = 0;
50+
51+
virtual ~JoyConverterBase() = default;
5252
};
5353
} // namespace autoware::joy_controller
5454

control/autoware_joy_controller/src/joy_controller_node.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,6 @@
2323
#include <algorithm>
2424
#include <memory>
2525
#include <string>
26-
#include <utility>
2726

2827
namespace
2928
{
@@ -404,8 +403,8 @@ void AutowareJoyControllerNode::sendEmergencyRequest(bool emergency)
404403
request->emergency = emergency;
405404

406405
client_emergency_stop_->async_send_request(
407-
request, [this, emergency](
408-
rclcpp::Client<tier4_external_api_msgs::srv::SetEmergency>::SharedFuture result) {
406+
request,
407+
[this](rclcpp::Client<tier4_external_api_msgs::srv::SetEmergency>::SharedFuture result) {
409408
auto response = result.get();
410409
if (tier4_api_utils::is_success(response->status)) {
411410
RCLCPP_INFO(get_logger(), "service succeeded");

0 commit comments

Comments
 (0)