Rover: create an enumeration to hold vehicle mode constants

This gives us type-safety on the mode numbers.  This is advantageous as
some of these symbols exist with different values elsewhere in the code.
This commit is contained in:
Peter Barker 2018-06-06 16:41:17 +10:00 committed by Randy Mackay
parent b32b57ad75
commit 36705af8ff
7 changed files with 38 additions and 38 deletions

View File

@ -1281,7 +1281,7 @@ AP_Mission *GCS_MAVLINK_Rover::get_mission()
bool GCS_MAVLINK_Rover::set_mode(const uint8_t mode)
{
Mode *new_mode = rover.mode_from_mode_num((enum mode)mode);
Mode *new_mode = rover.mode_from_mode_num((enum Mode::Number)mode);
if (new_mode == nullptr) {
return false;
}

View File

@ -35,7 +35,7 @@ const AP_Param::Info Rover::var_info[] = {
// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.
// @Values: 0:MANUAL,1:ACRO,3:STEERING,4:HOLD,5:LOITER,10:AUTO,11:RTL,15:GUIDED
// @User: Advanced
GSCALAR(initial_mode, "INITIAL_MODE", MANUAL),
GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL),
// @Param: SYSID_THIS_MAV
// @DisplayName: MAVLink system ID of this vehicle
@ -236,42 +236,42 @@ const AP_Param::Info Rover::var_info[] = {
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
GSCALAR(mode1, "MODE1", MANUAL),
GSCALAR(mode1, "MODE1", Mode::Number::MANUAL),
// @Param: MODE2
// @DisplayName: Mode2
// @Description: Driving mode for switch position 2 (1231 to 1360)
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard
GSCALAR(mode2, "MODE2", MANUAL),
GSCALAR(mode2, "MODE2", Mode::Number::MANUAL),
// @Param: MODE3
// @DisplayName: Mode3
// @Description: Driving mode for switch position 3 (1361 to 1490)
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard
GSCALAR(mode3, "MODE3", MANUAL),
GSCALAR(mode3, "MODE3", Mode::Number::MANUAL),
// @Param: MODE4
// @DisplayName: Mode4
// @Description: Driving mode for switch position 4 (1491 to 1620)
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard
GSCALAR(mode4, "MODE4", MANUAL),
GSCALAR(mode4, "MODE4", Mode::Number::MANUAL),
// @Param: MODE5
// @DisplayName: Mode5
// @Description: Driving mode for switch position 5 (1621 to 1749)
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard
GSCALAR(mode5, "MODE5", MANUAL),
GSCALAR(mode5, "MODE5", Mode::Number::MANUAL),
// @Param: MODE6
// @DisplayName: Mode6
// @Description: Driving mode for switch position 6 (1750 to 2049)
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard
GSCALAR(mode6, "MODE6", MANUAL),
GSCALAR(mode6, "MODE6", Mode::Number::MANUAL),
// @Param: WP_RADIUS
// @DisplayName: Waypoint radius

View File

@ -434,7 +434,7 @@ private:
void delay(uint32_t ms);
// control_modes.cpp
Mode *mode_from_mode_num(enum mode num);
Mode *mode_from_mode_num(enum Mode::Number num);
void read_control_switch();
uint8_t readSwitch(void);
void reset_control_switch();

View File

@ -2,38 +2,38 @@
static const int16_t CH_7_PWM_TRIGGER = 1800;
Mode *Rover::mode_from_mode_num(const enum mode num)
Mode *Rover::mode_from_mode_num(const enum Mode::Number num)
{
Mode *ret = nullptr;
switch (num) {
case MANUAL:
case Mode::Number::MANUAL:
ret = &mode_manual;
break;
case ACRO:
case Mode::Number::ACRO:
ret = &mode_acro;
break;
case STEERING:
case Mode::Number::STEERING:
ret = &mode_steering;
break;
case HOLD:
case Mode::Number::HOLD:
ret = &mode_hold;
break;
case LOITER:
case Mode::Number::LOITER:
ret = &mode_loiter;
break;
case AUTO:
case Mode::Number::AUTO:
ret = &mode_auto;
break;
case RTL:
case Mode::Number::RTL:
ret = &mode_rtl;
break;
case SMART_RTL:
case Mode::Number::SMART_RTL:
ret = &mode_smartrtl;
break;
case GUIDED:
case Mode::Number::GUIDED:
ret = &mode_guided;
break;
case INITIALISING:
case Mode::Number::INITIALISING:
ret = &mode_initializing;
break;
default:
@ -76,7 +76,7 @@ void Rover::read_control_switch()
return;
}
Mode *new_mode = mode_from_mode_num((enum mode)modes[switchPosition].get());
Mode *new_mode = mode_from_mode_num((enum Mode::Number)modes[switchPosition].get());
if (new_mode != nullptr) {
set_mode(*new_mode, MODE_REASON_TX_COMMAND);
}

View File

@ -34,21 +34,6 @@ enum ch7_option {
#define HIL_MODE_DISABLED 0
#define HIL_MODE_SENSORS 1
// Auto Pilot modes
// ----------------
enum mode {
MANUAL = 0,
ACRO = 1,
STEERING = 3,
HOLD = 4,
LOITER = 5,
AUTO = 10,
RTL = 11,
SMART_RTL = 12,
GUIDED = 15,
INITIALISING = 16
};
// types of failsafe events
#define FAILSAFE_EVENT_THROTTLE (1<<0)
#define FAILSAFE_EVENT_GCS (1<<1)

View File

@ -16,6 +16,21 @@ class Mode
{
public:
// Auto Pilot modes
// ----------------
enum Number {
MANUAL = 0,
ACRO = 1,
STEERING = 3,
HOLD = 4,
LOITER = 5,
AUTO = 10,
RTL = 11,
SMART_RTL = 12,
GUIDED = 15,
INITIALISING = 16
};
// Constructor
Mode();

View File

@ -146,7 +146,7 @@ void Rover::init_ardupilot()
startup_ground();
Mode *initial_mode = mode_from_mode_num((enum mode)g.initial_mode.get());
Mode *initial_mode = mode_from_mode_num((enum Mode::Number)g.initial_mode.get());
if (initial_mode == nullptr) {
initial_mode = &mode_initializing;
}
@ -262,7 +262,7 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
#endif
#if CAMERA == ENABLED
camera.set_is_auto_mode(control_mode->mode_number() == AUTO);
camera.set_is_auto_mode(control_mode->mode_number() == Mode::Number::AUTO);
#endif
old_mode.exit();