Rover: Make the definition name a class type

This commit is contained in:
muramura 2024-06-19 22:13:47 +09:00 committed by Peter Barker
parent c05441b959
commit 76c43f1f82
2 changed files with 15 additions and 15 deletions

View File

@ -80,11 +80,11 @@ enum fs_ekf_action {
#define DISTANCE_HOME_MINCHANGE 0.5f // minimum distance to adjust home location #define DISTANCE_HOME_MINCHANGE 0.5f // minimum distance to adjust home location
enum pilot_steer_type_t { enum class PilotSteerType : uint8_t {
PILOT_STEER_TYPE_DEFAULT = 0, DEFAULT = 0,
PILOT_STEER_TYPE_TWO_PADDLES = 1, TWO_PADDLES = 1,
PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING = 2, DIR_REVERSED_WHEN_REVERSING = 2,
PILOT_STEER_TYPE_DIR_UNCHANGED_WHEN_REVERSING = 3, DIR_UNCHANGED_WHEN_REVERSING = 3,
}; };
// frame class enum used for FRAME_CLASS parameter // frame class enum used for FRAME_CLASS parameter

View File

@ -67,10 +67,10 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) const
} }
// apply RC skid steer mixing // apply RC skid steer mixing
switch ((enum pilot_steer_type_t)g.pilot_steer_type.get()) switch ((PilotSteerType)g.pilot_steer_type.get())
{ {
case PILOT_STEER_TYPE_DEFAULT: case PilotSteerType::DEFAULT:
case PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING: case PilotSteerType::DIR_REVERSED_WHEN_REVERSING:
default: { default: {
// by default regular and skid-steering vehicles reverse their rotation direction when backing up // by default regular and skid-steering vehicles reverse their rotation direction when backing up
throttle_out = rover.channel_throttle->get_control_in(); throttle_out = rover.channel_throttle->get_control_in();
@ -79,7 +79,7 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) const
break; break;
} }
case PILOT_STEER_TYPE_TWO_PADDLES: { case PilotSteerType::TWO_PADDLES: {
// convert the two radio_in values from skid steering values // convert the two radio_in values from skid steering values
// left paddle from steering input channel, right paddle from throttle input channel // left paddle from steering input channel, right paddle from throttle input channel
// steering = left-paddle - right-paddle // steering = left-paddle - right-paddle
@ -92,7 +92,7 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) const
break; break;
} }
case PILOT_STEER_TYPE_DIR_UNCHANGED_WHEN_REVERSING: { case PilotSteerType::DIR_UNCHANGED_WHEN_REVERSING: {
throttle_out = rover.channel_throttle->get_control_in(); throttle_out = rover.channel_throttle->get_control_in();
steering_out = rover.channel_steer->get_control_in(); steering_out = rover.channel_steer->get_control_in();
break; break;
@ -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 // 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); 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)) && if ((is_negative(throttle_out) != is_negative(throttle_out_limited)) &&
((g.pilot_steer_type == PILOT_STEER_TYPE_DEFAULT) || ((PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DEFAULT) ||
(g.pilot_steer_type == PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING))) { (PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DIR_REVERSED_WHEN_REVERSING))) {
steering_out *= -1; steering_out *= -1;
} }
throttle_out = throttle_out_limited; 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 // 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); 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)) && if ((is_negative(speed_out) != is_negative(speed_out_limited)) &&
((g.pilot_steer_type == PILOT_STEER_TYPE_DEFAULT) || ((PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DEFAULT) ||
(g.pilot_steer_type == PILOT_STEER_TYPE_DIR_REVERSED_WHEN_REVERSING))) { (PilotSteerType(g.pilot_steer_type.get()) == PilotSteerType::DIR_REVERSED_WHEN_REVERSING))) {
steering_out *= -1; steering_out *= -1;
} }
speed_out = speed_out_limited; 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); float desired_throttle = constrain_float(rover.channel_throttle->norm_input_dz(), -1.0f, 1.0f);
// handle two paddle input // handle two paddle input
if ((enum pilot_steer_type_t)g.pilot_steer_type.get() == PILOT_STEER_TYPE_TWO_PADDLES) { if ((PilotSteerType)g.pilot_steer_type.get() == PilotSteerType::TWO_PADDLES) {
const float left_paddle = desired_steering; const float left_paddle = desired_steering;
const float right_paddle = desired_throttle; const float right_paddle = desired_throttle;
desired_steering = (left_paddle - right_paddle) * 0.5f; desired_steering = (left_paddle - right_paddle) * 0.5f;