Skip to content

Commit

Permalink
fix(autoware_joy_controller): add virtual destructor to autoware_joy_…
Browse files Browse the repository at this point in the history
…controller (#7760)

Signed-off-by: Y.Hisaki <[email protected]>
  • Loading branch information
yhisaki authored Jul 1, 2024
1 parent 445bc34 commit 17d24ae
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@
#include <tier4_external_api_msgs/srv/engage.hpp>
#include <tier4_external_api_msgs/srv/set_emergency.hpp>

#include <algorithm>
#include <memory>
#include <string>

Expand Down Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

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

#include <cstdlib>

namespace autoware::joy_controller
{
class G29JoyConverter : public JoyConverterBase
Expand All @@ -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;
Expand All @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@

#include <sensor_msgs/msg/joy.hpp>

#include <algorithm>

namespace autoware::joy_controller
{
class JoyConverterBase
Expand Down Expand Up @@ -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

Expand Down
5 changes: 2 additions & 3 deletions control/autoware_joy_controller/src/joy_controller_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
#include <algorithm>
#include <memory>
#include <string>
#include <utility>

namespace
{
Expand Down Expand Up @@ -404,8 +403,8 @@ void AutowareJoyControllerNode::sendEmergencyRequest(bool emergency)
request->emergency = emergency;

client_emergency_stop_->async_send_request(
request, [this, emergency](
rclcpp::Client<tier4_external_api_msgs::srv::SetEmergency>::SharedFuture result) {
request,
[this](rclcpp::Client<tier4_external_api_msgs::srv::SetEmergency>::SharedFuture result) {
auto response = result.get();
if (tier4_api_utils::is_success(response->status)) {
RCLCPP_INFO(get_logger(), "service succeeded");
Expand Down

0 comments on commit 17d24ae

Please sign in to comment.