Rover: make Mode::Number enum class

This commit is contained in:
Pierre Kancir 2023-09-21 17:47:41 +02:00 committed by Peter Barker
parent 3a11a1cf0d
commit 911a467e37
6 changed files with 35 additions and 29 deletions

View File

@ -53,7 +53,7 @@ MAV_MODE GCS_MAVLINK_Rover::base_mode() const
uint32_t GCS_Rover::custom_mode() const uint32_t GCS_Rover::custom_mode() const
{ {
return rover.control_mode->mode_number(); return (uint32_t)rover.control_mode->mode_number();
} }
MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const

View File

@ -241,7 +241,7 @@ void Rover::Log_Write_RC(void)
void Rover::Log_Write_Vehicle_Startup_Messages() void Rover::Log_Write_Vehicle_Startup_Messages()
{ {
// only 200(?) bytes are guaranteed by AP_Logger // only 200(?) bytes are guaranteed by AP_Logger
logger.Write_Mode(control_mode->mode_number(), control_mode_reason); logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason);
ahrs.Log_Write_Home_And_Origin(); ahrs.Log_Write_Home_And_Origin();
gps.Write_AP_Logger_Log_Startup_messages(); gps.Write_AP_Logger_Log_Startup_messages();
} }

View File

@ -29,7 +29,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. // @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.
// @CopyValuesFrom: MODE1 // @CopyValuesFrom: MODE1
// @User: Advanced // @User: Advanced
GSCALAR(initial_mode, "INITIAL_MODE", Mode::Number::MANUAL), GSCALAR(initial_mode, "INITIAL_MODE", (int8_t)Mode::Number::MANUAL),
// @Param: SYSID_THISMAV // @Param: SYSID_THISMAV
// @DisplayName: MAVLink system ID of this vehicle // @DisplayName: MAVLink system ID of this vehicle
@ -174,38 +174,38 @@ const AP_Param::Info Rover::var_info[] = {
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided // @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided
// @User: Standard // @User: Standard
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049) // @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
GSCALAR(mode1, "MODE1", Mode::Number::MANUAL), GSCALAR(mode1, "MODE1", (int8_t)Mode::Number::MANUAL),
// @Param: MODE2 // @Param: MODE2
// @DisplayName: Mode2 // @DisplayName: Mode2
// @Description: Driving mode for switch position 2 (1231 to 1360) // @Description: Driving mode for switch position 2 (1231 to 1360)
// @CopyValuesFrom: MODE1 // @CopyValuesFrom: MODE1
// @User: Standard // @User: Standard
GSCALAR(mode2, "MODE2", Mode::Number::MANUAL), GSCALAR(mode2, "MODE2", (int8_t)Mode::Number::MANUAL),
// @Param: MODE3 // @Param: MODE3
// @CopyFieldsFrom: MODE1 // @CopyFieldsFrom: MODE1
// @DisplayName: Mode3 // @DisplayName: Mode3
// @Description: Driving mode for switch position 3 (1361 to 1490) // @Description: Driving mode for switch position 3 (1361 to 1490)
GSCALAR(mode3, "MODE3", Mode::Number::MANUAL), GSCALAR(mode3, "MODE3", (int8_t)Mode::Number::MANUAL),
// @Param: MODE4 // @Param: MODE4
// @CopyFieldsFrom: MODE1 // @CopyFieldsFrom: MODE1
// @DisplayName: Mode4 // @DisplayName: Mode4
// @Description: Driving mode for switch position 4 (1491 to 1620) // @Description: Driving mode for switch position 4 (1491 to 1620)
GSCALAR(mode4, "MODE4", Mode::Number::MANUAL), GSCALAR(mode4, "MODE4", (int8_t)Mode::Number::MANUAL),
// @Param: MODE5 // @Param: MODE5
// @CopyFieldsFrom: MODE1 // @CopyFieldsFrom: MODE1
// @DisplayName: Mode5 // @DisplayName: Mode5
// @Description: Driving mode for switch position 5 (1621 to 1749) // @Description: Driving mode for switch position 5 (1621 to 1749)
GSCALAR(mode5, "MODE5", Mode::Number::MANUAL), GSCALAR(mode5, "MODE5", (int8_t)Mode::Number::MANUAL),
// @Param: MODE6 // @Param: MODE6
// @CopyFieldsFrom: MODE1 // @CopyFieldsFrom: MODE1
// @DisplayName: Mode6 // @DisplayName: Mode6
// @Description: Driving mode for switch position 6 (1750 to 2049) // @Description: Driving mode for switch position 6 (1750 to 2049)
GSCALAR(mode6, "MODE6", Mode::Number::MANUAL), GSCALAR(mode6, "MODE6", (int8_t)Mode::Number::MANUAL),
// variables not in the g class which contain EEPROM saved variables // variables not in the g class which contain EEPROM saved variables

View File

@ -378,6 +378,7 @@ private:
bool gcs_mode_enabled(const Mode::Number mode_num) const; bool gcs_mode_enabled(const Mode::Number mode_num) const;
bool set_mode(Mode &new_mode, ModeReason reason); bool set_mode(Mode &new_mode, ModeReason reason);
bool set_mode(const uint8_t new_mode, ModeReason reason) override; bool set_mode(const uint8_t new_mode, ModeReason reason) override;
bool set_mode(Mode::Number new_mode, ModeReason reason);
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); } uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
bool current_mode_requires_mission() const override { bool current_mode_requires_mission() const override {
return control_mode == &mode_auto; return control_mode == &mode_auto;

View File

@ -11,7 +11,7 @@ public:
// Auto Pilot modes // Auto Pilot modes
// ---------------- // ----------------
enum Number : uint8_t { enum class Number : uint8_t {
MANUAL = 0, MANUAL = 0,
ACRO = 1, ACRO = 1,
STEERING = 3, STEERING = 3,
@ -43,7 +43,7 @@ public:
void exit(); void exit();
// returns a unique number specific to this mode // returns a unique number specific to this mode
virtual uint32_t mode_number() const = 0; virtual Number mode_number() const = 0;
// returns short text name (up to 4 bytes) // returns short text name (up to 4 bytes)
virtual const char *name4() const = 0; virtual const char *name4() const = 0;
@ -218,7 +218,7 @@ class ModeAcro : public Mode
{ {
public: public:
uint32_t mode_number() const override { return ACRO; } Number mode_number() const override { return Number::ACRO; }
const char *name4() const override { return "ACRO"; } const char *name4() const override { return "ACRO"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -240,7 +240,7 @@ class ModeAuto : public Mode
{ {
public: public:
uint32_t mode_number() const override { return AUTO; } Number mode_number() const override { return Number::AUTO; }
const char *name4() const override { return "AUTO"; } const char *name4() const override { return "AUTO"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -405,7 +405,7 @@ public:
// Does not allow copies // Does not allow copies
CLASS_NO_COPY(ModeCircle); CLASS_NO_COPY(ModeCircle);
uint32_t mode_number() const override { return CIRCLE; } Number mode_number() const override { return Number::CIRCLE; }
const char *name4() const override { return "CIRC"; } const char *name4() const override { return "CIRC"; }
// initialise with specific center location, radius (in meters) and direction // initialise with specific center location, radius (in meters) and direction
@ -489,7 +489,7 @@ class ModeGuided : public Mode
{ {
public: public:
uint32_t mode_number() const override { return GUIDED; } Number mode_number() const override { return Number::GUIDED; }
const char *name4() const override { return "GUID"; } const char *name4() const override { return "GUID"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -593,7 +593,7 @@ class ModeHold : public Mode
{ {
public: public:
uint32_t mode_number() const override { return HOLD; } Number mode_number() const override { return Number::HOLD; }
const char *name4() const override { return "HOLD"; } const char *name4() const override { return "HOLD"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -611,7 +611,7 @@ class ModeLoiter : public Mode
{ {
public: public:
uint32_t mode_number() const override { return LOITER; } Number mode_number() const override { return Number::LOITER; }
const char *name4() const override { return "LOIT"; } const char *name4() const override { return "LOIT"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -643,7 +643,7 @@ class ModeManual : public Mode
{ {
public: public:
uint32_t mode_number() const override { return MANUAL; } Number mode_number() const override { return Number::MANUAL; }
const char *name4() const override { return "MANU"; } const char *name4() const override { return "MANU"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -667,7 +667,7 @@ class ModeRTL : public Mode
{ {
public: public:
uint32_t mode_number() const override { return RTL; } Number mode_number() const override { return Number::RTL; }
const char *name4() const override { return "RTL"; } const char *name4() const override { return "RTL"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -702,7 +702,7 @@ class ModeSmartRTL : public Mode
{ {
public: public:
uint32_t mode_number() const override { return SMART_RTL; } Number mode_number() const override { return Number::SMART_RTL; }
const char *name4() const override { return "SRTL"; } const char *name4() const override { return "SRTL"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -748,7 +748,7 @@ class ModeSteering : public Mode
{ {
public: public:
uint32_t mode_number() const override { return STEERING; } Number mode_number() const override { return Number::STEERING; }
const char *name4() const override { return "STER"; } const char *name4() const override { return "STER"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -773,7 +773,7 @@ class ModeInitializing : public Mode
{ {
public: public:
uint32_t mode_number() const override { return INITIALISING; } Number mode_number() const override { return Number::INITIALISING; }
const char *name4() const override { return "INIT"; } const char *name4() const override { return "INIT"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -794,7 +794,7 @@ class ModeFollow : public Mode
{ {
public: public:
uint32_t mode_number() const override { return FOLLOW; } Number mode_number() const override { return Number::FOLLOW; }
const char *name4() const override { return "FOLL"; } const char *name4() const override { return "FOLL"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -830,7 +830,7 @@ class ModeSimple : public Mode
{ {
public: public:
uint32_t mode_number() const override { return SIMPLE; } Number mode_number() const override { return Number::SIMPLE; }
const char *name4() const override { return "SMPL"; } const char *name4() const override { return "SMPL"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode
@ -860,7 +860,7 @@ public:
// Does not allow copies // Does not allow copies
CLASS_NO_COPY(ModeDock); CLASS_NO_COPY(ModeDock);
uint32_t mode_number() const override { return DOCK; } Number mode_number() const override { return Number::DOCK; }
const char *name4() const override { return "DOCK"; } const char *name4() const override { return "DOCK"; }
// methods that affect movement of the vehicle in this mode // methods that affect movement of the vehicle in this mode

View File

@ -281,7 +281,7 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
old_mode.exit(); old_mode.exit();
control_mode_reason = reason; control_mode_reason = reason;
logger.Write_Mode(control_mode->mode_number(), control_mode_reason); logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason);
gcs().send_message(MSG_HEARTBEAT); gcs().send_message(MSG_HEARTBEAT);
notify_mode(control_mode); notify_mode(control_mode);
@ -291,9 +291,14 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
bool Rover::set_mode(const uint8_t new_mode, ModeReason reason) bool Rover::set_mode(const uint8_t new_mode, ModeReason reason)
{ {
static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number"); static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number");
Mode *mode = rover.mode_from_mode_num((enum Mode::Number)new_mode); return rover.set_mode(static_cast<Mode::Number>(new_mode), reason);
}
bool Rover::set_mode(Mode::Number new_mode, ModeReason reason)
{
Mode *mode = rover.mode_from_mode_num(new_mode);
if (mode == nullptr) { if (mode == nullptr) {
notify_no_such_mode(new_mode); notify_no_such_mode((uint8_t)new_mode);
return false; return false;
} }
return rover.set_mode(*mode, reason); return rover.set_mode(*mode, reason);
@ -317,7 +322,7 @@ void Rover::startup_INS_ground(void)
void Rover::notify_mode(const Mode *mode) void Rover::notify_mode(const Mode *mode)
{ {
AP_Notify::flags.autopilot_mode = mode->is_autopilot_mode(); AP_Notify::flags.autopilot_mode = mode->is_autopilot_mode();
notify.flags.flight_mode = mode->mode_number(); notify.flags.flight_mode = (uint8_t)mode->mode_number();
notify.set_flight_mode_str(mode->name4()); notify.set_flight_mode_str(mode->name4());
} }