From 10991589a7e46d50b4dfbe72683f67e60d8941c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 4 Sep 2024 16:33:06 +1000 Subject: [PATCH] Rover: use AP_Enum for pilot_steer_type --- Rover/Parameters.h | 2 +- Rover/mode.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 8a19324bfa..ff8d29c38b 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -257,7 +257,7 @@ public: // Throttle // AP_Int8 throttle_cruise; - AP_Int8 pilot_steer_type; + AP_Enum pilot_steer_type; // failsafe control AP_Int8 fs_action; diff --git a/Rover/mode.cpp b/Rover/mode.cpp index ee1a533e11..ae858691ea 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -123,8 +123,8 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t // check for special case of input and output throttle being in opposite directions float throttle_out_limited = g2.motors.get_slew_limited_throttle(throttle_out, rover.G_Dt); if ((is_negative(throttle_out) != is_negative(throttle_out_limited)) && - ((PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DEFAULT) || - (PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DIR_REVERSED_WHEN_REVERSING))) { + (g.pilot_steer_type == PilotSteerType::DEFAULT || + g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) { steering_out *= -1; } throttle_out = throttle_out_limited; @@ -139,8 +139,8 @@ void Mode::get_pilot_desired_steering_and_speed(float &steering_out, float &spee // check for special case of input and output throttle being in opposite directions float speed_out_limited = g2.attitude_control.get_desired_speed_accel_limited(speed_out, rover.G_Dt); if ((is_negative(speed_out) != is_negative(speed_out_limited)) && - ((PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DEFAULT) || - (PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DIR_REVERSED_WHEN_REVERSING))) { + (g.pilot_steer_type == PilotSteerType::DEFAULT || + g.pilot_steer_type == PilotSteerType::DIR_REVERSED_WHEN_REVERSING)) { steering_out *= -1; } speed_out = speed_out_limited; @@ -167,7 +167,7 @@ void Mode::get_pilot_desired_heading_and_speed(float &heading_out, float &speed_ float desired_throttle = constrain_float(rover.channel_throttle->norm_input_dz(), -1.0f, 1.0f); // handle two paddle input - if ((PilotSteerType)g.pilot_steer_type.get() == PilotSteerType::TWO_PADDLES) { + if (g.pilot_steer_type == PilotSteerType::TWO_PADDLES) { const float left_paddle = desired_steering; const float right_paddle = desired_throttle; desired_steering = (left_paddle - right_paddle) * 0.5f;