diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 62037c6958..5b8cbf5a44 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -588,7 +588,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) uint8_t result = MAV_RESULT_UNSUPPORTED; // do command - send_text_P(SEVERITY_LOW,PSTR("command received: ")); + send_text_P(MAV_SEVERITY_WARNING,PSTR("command received: ")); switch(packet.command) { @@ -798,7 +798,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) // check if this is the HOME wp if (packet.seq == 0) { 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; } @@ -890,7 +890,7 @@ void Tracker::mavlink_delay_cb() } if (tnow - last_5s > 5000) { 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; } @@ -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; ivsnprintf_P((char *)gcs[0].pending_status.text, sizeof(gcs[0].pending_status.text), fmt, arg_list); diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 226a927c41..bbac65dbf6 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -202,7 +202,7 @@ private: void gcs_send_message(enum ap_message id); void gcs_data_stream_send(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 load_parameters(void); void update_auto(void); diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 9234033631..b6a76d561c 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -4,9 +4,9 @@ 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(); - 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 diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index faff36e0dc..33f860f23a 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -104,7 +104,7 @@ void Tracker::init_tracker() 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???? set_mode(AUTO); // tracking