Tracker: update severity values

This commit is contained in:
squilter 2015-08-11 16:05:47 -07:00 committed by Randy Mackay
parent b4cf0ce2bb
commit f1d9b3570c
4 changed files with 9 additions and 9 deletions

View File

@ -588,7 +588,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
uint8_t result = MAV_RESULT_UNSUPPORTED; uint8_t result = MAV_RESULT_UNSUPPORTED;
// do command // do command
send_text_P(SEVERITY_LOW,PSTR("command received: ")); send_text_P(MAV_SEVERITY_WARNING,PSTR("command received: "));
switch(packet.command) { switch(packet.command) {
@ -798,7 +798,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// check if this is the HOME wp // check if this is the HOME wp
if (packet.seq == 0) { if (packet.seq == 0) {
tracker.set_home(tell_command); // New home in EEPROM tracker.set_home(tell_command); // New home in EEPROM
send_text_P(SEVERITY_LOW,PSTR("new HOME received")); send_text_P(MAV_SEVERITY_WARNING,PSTR("new HOME received"));
waypoint_receiving = false; waypoint_receiving = false;
} }
@ -890,7 +890,7 @@ void Tracker::mavlink_delay_cb()
} }
if (tnow - last_5s > 5000) { if (tnow - last_5s > 5000) {
last_5s = tnow; last_5s = tnow;
gcs_send_text_P(SEVERITY_LOW, PSTR("Initialising APM...")); gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Initialising APM..."));
} }
in_mavlink_delay = false; in_mavlink_delay = false;
} }
@ -931,7 +931,7 @@ void Tracker::gcs_update(void)
} }
} }
void Tracker::gcs_send_text_P(gcs_severity severity, const prog_char_t *str) void Tracker::gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str)
{ {
for (uint8_t i=0; i<num_gcs; i++) { for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) { if (gcs[i].initialised) {
@ -951,7 +951,7 @@ void Tracker::gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
void Tracker::gcs_send_text_fmt(const prog_char_t *fmt, ...) void Tracker::gcs_send_text_fmt(const prog_char_t *fmt, ...)
{ {
va_list arg_list; va_list arg_list;
gcs[0].pending_status.severity = (uint8_t)SEVERITY_LOW; gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING;
va_start(arg_list, fmt); va_start(arg_list, fmt);
hal.util->vsnprintf_P((char *)gcs[0].pending_status.text, hal.util->vsnprintf_P((char *)gcs[0].pending_status.text,
sizeof(gcs[0].pending_status.text), fmt, arg_list); sizeof(gcs[0].pending_status.text), fmt, arg_list);

View File

@ -202,7 +202,7 @@ private:
void gcs_send_message(enum ap_message id); void gcs_send_message(enum ap_message id);
void gcs_data_stream_send(void); void gcs_data_stream_send(void);
void gcs_update(void); void gcs_update(void);
void gcs_send_text_P(gcs_severity severity, const prog_char_t *str); void gcs_send_text_P(MAV_SEVERITY severity, const prog_char_t *str);
void gcs_retry_deferred(void); void gcs_retry_deferred(void);
void load_parameters(void); void load_parameters(void);
void update_auto(void); void update_auto(void);

View File

@ -4,9 +4,9 @@
void Tracker::init_barometer(void) void Tracker::init_barometer(void)
{ {
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer")); gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Calibrating barometer"));
barometer.calibrate(); barometer.calibrate();
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete")); gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("barometer calibration complete"));
} }
// read the barometer and return the updated altitude in meters // read the barometer and return the updated altitude in meters

View File

@ -104,7 +104,7 @@ void Tracker::init_tracker()
init_capabilities(); init_capabilities();
gcs_send_text_P(SEVERITY_LOW,PSTR("\nReady to track.")); gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("\nReady to track."));
hal.scheduler->delay(1000); // Why???? hal.scheduler->delay(1000); // Why????
set_mode(AUTO); // tracking set_mode(AUTO); // tracking