File tree Expand file tree Collapse file tree 4 files changed +8
-9
lines changed
control/autoware_joy_controller
include/autoware/joy_controller Expand file tree Collapse file tree 4 files changed +8
-9
lines changed Original file line number Diff line number Diff line change 33
33
#include < tier4_external_api_msgs/srv/engage.hpp>
34
34
#include < tier4_external_api_msgs/srv/set_emergency.hpp>
35
35
36
- #include < algorithm>
37
36
#include < memory>
38
37
#include < string>
39
38
@@ -110,7 +109,6 @@ class AutowareJoyControllerNode : public rclcpp::Node
110
109
autoware_control_msgs::msg::Control prev_control_command_;
111
110
tier4_external_api_msgs::msg::ControlCommand prev_external_control_command_;
112
111
GearShiftType prev_shift_ = tier4_external_api_msgs::msg::GearShift::NONE;
113
- TurnSignalType prev_turn_signal_ = tier4_external_api_msgs::msg::TurnSignal::NONE;
114
112
GateModeType prev_gate_mode_ = tier4_control_msgs::msg::GateMode::AUTO;
115
113
116
114
// Timer
Original file line number Diff line number Diff line change 17
17
18
18
#include " autoware/joy_controller/joy_converter/joy_converter_base.hpp"
19
19
20
+ #include < cstdlib>
21
+
20
22
namespace autoware ::joy_controller
21
23
{
22
24
class G29JoyConverter : public JoyConverterBase
@@ -27,7 +29,7 @@ class G29JoyConverter : public JoyConverterBase
27
29
float accel () const
28
30
{
29
31
constexpr float eps = 0.0000001 ;
30
- if (std::fabs (AccelPedal ()) < eps) {
32
+ if (std::abs (AccelPedal ()) < eps) {
31
33
return 0 .0f ;
32
34
}
33
35
return (AccelPedal () + 1 .0f ) / 2 ;
@@ -36,7 +38,7 @@ class G29JoyConverter : public JoyConverterBase
36
38
float brake () const
37
39
{
38
40
constexpr float eps = 0.0000001 ;
39
- if (std::fabs (BrakePedal ()) < eps) {
41
+ if (std::abs (BrakePedal ()) < eps) {
40
42
return 0 .0f ;
41
43
}
42
44
return (BrakePedal () + 1 .0f ) / 2 ;
Original file line number Diff line number Diff line change 17
17
18
18
#include < sensor_msgs/msg/joy.hpp>
19
19
20
- #include < algorithm>
21
-
22
20
namespace autoware ::joy_controller
23
21
{
24
22
class JoyConverterBase
@@ -49,6 +47,8 @@ class JoyConverterBase
49
47
50
48
virtual bool vehicle_engage () const = 0;
51
49
virtual bool vehicle_disengage () const = 0;
50
+
51
+ virtual ~JoyConverterBase () = default ;
52
52
};
53
53
} // namespace autoware::joy_controller
54
54
Original file line number Diff line number Diff line change 23
23
#include < algorithm>
24
24
#include < memory>
25
25
#include < string>
26
- #include < utility>
27
26
28
27
namespace
29
28
{
@@ -404,8 +403,8 @@ void AutowareJoyControllerNode::sendEmergencyRequest(bool emergency)
404
403
request->emergency = emergency;
405
404
406
405
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) {
409
408
auto response = result.get ();
410
409
if (tier4_api_utils::is_success (response->status )) {
411
410
RCLCPP_INFO (get_logger (), " service succeeded" );
You can’t perform that action at this time.
0 commit comments