mirror of https://github.com/ArduPilot/ardupilot
Rover: add name4() to Mode and use it for AP_Notify calls
This commit is contained in:
parent
04e9228fa0
commit
45d76bdf25
|
@ -562,7 +562,7 @@ private:
|
|||
void resetPerfData(void);
|
||||
void check_usb_mux(void);
|
||||
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
|
||||
void notify_mode(enum mode new_mode);
|
||||
void notify_mode(const Mode *new_mode);
|
||||
uint8_t check_digital_pin(uint8_t pin);
|
||||
bool should_log(uint32_t mask);
|
||||
void change_arm_state(void);
|
||||
|
|
|
@ -25,6 +25,9 @@ public:
|
|||
// returns a unique number specific to this mode
|
||||
virtual uint32_t mode_number() const = 0;
|
||||
|
||||
// returns short text name (up to 4 bytes)
|
||||
virtual const char *name4() const = 0;
|
||||
|
||||
//
|
||||
// methods that sub classes should override to affect movement of the vehicle in this mode
|
||||
//
|
||||
|
@ -150,6 +153,7 @@ class ModeAcro : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return ACRO; }
|
||||
const char *name4() const override { return "ACRO"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -167,6 +171,7 @@ public:
|
|||
ModeAuto(ModeRTL& mode_rtl);
|
||||
|
||||
uint32_t mode_number() const override { return AUTO; }
|
||||
const char *name4() const override { return "AUTO"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -226,6 +231,7 @@ class ModeGuided : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return GUIDED; }
|
||||
const char *name4() const override { return "GUID"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -269,6 +275,7 @@ class ModeHold : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return HOLD; }
|
||||
const char *name4() const override { return "HOLD"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -283,6 +290,7 @@ class ModeManual : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return MANUAL; }
|
||||
const char *name4() const override { return "MANU"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -301,6 +309,7 @@ class ModeRTL : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return RTL; }
|
||||
const char *name4() const override { return "RTL"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -323,6 +332,7 @@ class ModeSteering : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return STEERING; }
|
||||
const char *name4() const override { return "STER"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override;
|
||||
|
@ -336,6 +346,7 @@ class ModeInitializing : public Mode
|
|||
public:
|
||||
|
||||
uint32_t mode_number() const override { return INITIALISING; }
|
||||
const char *name4() const override { return "INIT"; }
|
||||
|
||||
// methods that affect movement of the vehicle in this mode
|
||||
void update() override { }
|
||||
|
|
|
@ -58,7 +58,7 @@ void Rover::init_ardupilot()
|
|||
// initialise notify system
|
||||
notify.init(false);
|
||||
AP_Notify::flags.failsafe_battery = false;
|
||||
notify_mode((enum mode)control_mode->mode_number());
|
||||
notify_mode(control_mode);
|
||||
|
||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||
|
||||
|
@ -238,7 +238,7 @@ bool Rover::set_mode(Mode &new_mode, mode_reason_t reason)
|
|||
control_mode_reason = reason;
|
||||
DataFlash.Log_Write_Mode(control_mode->mode_number(), control_mode_reason);
|
||||
|
||||
notify_mode((enum mode)control_mode->mode_number());
|
||||
notify_mode(control_mode);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -282,39 +282,10 @@ void Rover::check_usb_mux(void)
|
|||
}
|
||||
|
||||
// update notify with mode change
|
||||
void Rover::notify_mode(enum mode new_mode)
|
||||
void Rover::notify_mode(const Mode *mode)
|
||||
{
|
||||
notify.flags.flight_mode = new_mode;
|
||||
|
||||
switch (new_mode) {
|
||||
case MANUAL:
|
||||
notify.set_flight_mode_str("MANU");
|
||||
break;
|
||||
case ACRO:
|
||||
notify.set_flight_mode_str("ACRO");
|
||||
break;
|
||||
case STEERING:
|
||||
notify.set_flight_mode_str("STER");
|
||||
break;
|
||||
case HOLD:
|
||||
notify.set_flight_mode_str("HOLD");
|
||||
break;
|
||||
case AUTO:
|
||||
notify.set_flight_mode_str("AUTO");
|
||||
break;
|
||||
case RTL:
|
||||
notify.set_flight_mode_str("RTL");
|
||||
break;
|
||||
case GUIDED:
|
||||
notify.set_flight_mode_str("GUID");
|
||||
break;
|
||||
case INITIALISING:
|
||||
notify.set_flight_mode_str("INIT");
|
||||
break;
|
||||
default:
|
||||
notify.set_flight_mode_str("----");
|
||||
break;
|
||||
}
|
||||
notify.flags.flight_mode = mode->mode_number();
|
||||
notify.set_flight_mode_str(mode->name4());
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue