AP_Notify: add set_flight_mode_str method

This allows the vehicle code to set a short string for the flight mode
This commit is contained in:
Randy Mackay 2017-01-20 19:13:37 +09:00 committed by Lucas De Marchi
parent acff67c718
commit e085ae1ec8
3 changed files with 19 additions and 75 deletions

View File

@ -160,7 +160,8 @@ void AP_Notify::init(bool enable_external_leds)
memset(&AP_Notify::flags, 0, sizeof(AP_Notify::flags));
memset(&AP_Notify::events, 0, sizeof(AP_Notify::events));
// clear text buffer
// clear flight mode string and text buffer
memset(_flight_mode_str, 0, sizeof(_flight_mode_str));
memset(_send_text, 0, sizeof(_send_text));
AP_Notify::flags.external_leds = enable_external_leds;
@ -198,6 +199,13 @@ void AP_Notify::handle_play_tune(mavlink_message_t *msg)
}
}
// set flight mode string
void AP_Notify::set_flight_mode_str(const char *str)
{
strncpy(_flight_mode_str, str, 4);
_flight_mode_str[sizeof(_flight_mode_str)-1] = 0;
}
void AP_Notify::send_text(const char *str)
{
strncpy(_send_text, str, sizeof(_send_text));

View File

@ -120,6 +120,10 @@ public:
bool buzzer_enabled() const { return _buzzer_enable; }
// set flight mode string
void set_flight_mode_str(const char *str);
const char* get_flight_mode_str() const { return _flight_mode_str; }
// send text to display
void send_text(const char *str);
const char* get_text() const { return _send_text; }
@ -135,6 +139,7 @@ private:
AP_Int8 _display_type;
char _send_text[NOTIFY_TEXT_BUFFER_SIZE];
char _flight_mode_str[5];
static NotifyDevice* _devices[];
};

View File

@ -284,78 +284,6 @@ static const uint8_t _font[] = {
0x00, 0x00, 0x00, 0x00, 0x00
};
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
static const char * _modename[] = {
"STAB", // STABILIZE = 0, // manual airframe angle with manual throttle
"ACRO", // ACRO = 1, // manual body-frame angular rate with manual throttle
"ALTH", // ALT_HOLD = 2, // manual airframe angle with automatic throttle
"AUTO", // AUTO = 3, // fully automatic waypoint control using mission commands
"GUID", // GUIDED = 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
"LOIT", // LOITER = 5, // automatic horizontal acceleration with automatic throttle
"RTL ", // RTL = 6, // automatic return to launching point
"CIRC", // CIRCLE = 7, // automatic circular flight with automatic throttle
"----", //8 no mode for copter
"LAND", // LAND = 9, // automatic landing with horizontal position control
"----", //10 no mode for copter
"DRIF", // DRIFT = 11, // semi-automous position, yaw and throttle control
"----", //12 no mode for copter
"SPRT", // SPORT = 13, // manual earth-frame angular rate control with manual throttle
"FLIP", // FLIP = 14, // automatically flip the vehicle on the roll axis
"ATUN", // AUTOTUNE = 15, // automatically tune the vehicle's roll and pitch gains
"PHLD", // POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
"BRAK", // BRAKE = 17, // full-brake using inertial/GPS system, no pilot input
"THRW", // THROW = 18, // throw to launch mode using inertial/GPS system, no pilot input
"AVOI", // AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
"GNGP" // GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude
};
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
static const char * _modename[] = {
"MANU", // = 0,
"CIRC", // = 1,
"STAB", // = 2,
"TRAN", // = 3,
"ACRO", // = 4,
"FBWA", // = 5,
"FBWB", // = 6,
"CRUS", // = 7,
"ATUN", // = 8,
"----", //9 no mode for plane
"AUTO", // = 10,
"RTL ", // = 11,
"LOIT", // = 12,
"----", //13 no mode for plane
"----", //14 no mode for plane
"GUID", // = 15,
"INIT", // = 16,
"QSTB", // = 17,
"QHVR", // = 18,
"QLIT", // = 19,
"QLND", // = 20,
"QRTL" // = 21
};
#else //rover
static const char * _modename[] = {
"MANU",
"----",
"LERN",
"STER",
"HOLD",
"----",
"----",
"----",
"----",
"----",
"AUTO",
"RTL",
"----",
"----",
"----",
"GUID",
"INIT"
};
#endif
bool Display::init(void)
{
// exit immediately if already initialised
@ -547,11 +475,14 @@ void Display::update_battery(uint8_t r)
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT1: %4.2fV", (double)AP_Notify::flags.battery_voltage) ;
draw_text(COLUMN(0), ROW(r), msg);
}
void Display::update_mode(uint8_t r)
{
char msg [DISPLAY_MESSAGE_SIZE];
snprintf(msg, DISPLAY_MESSAGE_SIZE, "Mode: %s", _modename[AP_Notify::flags.flight_mode]) ;
draw_text(COLUMN(0), ROW(r), msg);
if (pNotify->get_flight_mode_str()) {
snprintf(msg, DISPLAY_MESSAGE_SIZE, "Mode: %s", pNotify->get_flight_mode_str()) ;
draw_text(COLUMN(0), ROW(r), msg);
}
}
void Display::update_text(uint8_t r)