diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index e5e165460d..45032eee9e 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -865,7 +865,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) { @@ -950,7 +950,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } } else { - send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration")); + send_text_P(MAV_SEVERITY_WARNING, PSTR("Unsupported preflight calibration")); } break; @@ -1076,10 +1076,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { // mark the firmware version in the tlog - send_text_P(SEVERITY_LOW, PSTR(FIRMWARE_STRING)); + send_text_P(MAV_SEVERITY_WARNING, PSTR(FIRMWARE_STRING)); #if defined(PX4_GIT_VERSION) && defined(NUTTX_GIT_VERSION) - send_text_P(SEVERITY_LOW, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION)); + send_text_P(MAV_SEVERITY_WARNING, PSTR("PX4: " PX4_GIT_VERSION " NuttX: " NUTTX_GIT_VERSION)); #endif handle_param_request_list(msg); break; @@ -1301,7 +1301,7 @@ void Rover::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...")); } check_usb_mux(); @@ -1361,7 +1361,7 @@ void Rover::gcs_update(void) } } -void Rover::gcs_send_text_P(gcs_severity severity, const prog_char_t *str) +void Rover::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/APMrover2/Log.cpp b/APMrover2/Log.cpp index 06401b80c8..4d25cbb6fc 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -396,10 +396,10 @@ void Rover::log_init(void) { DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); if (!DataFlash.CardInserted()) { - gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash card inserted")); + gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("No dataflash card inserted")); g.log_bitmask.set(0); } else if (DataFlash.NeedErase()) { - gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS")); + gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("ERASING LOGS")); do_erase_logs(); } if (g.log_bitmask != 0) { diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index ff94c2c011..52fbab409e 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -400,7 +400,7 @@ private: void gcs_send_mission_item_reached_message(uint16_t mission_index); 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 do_erase_logs(void); void Log_Write_Performance(); diff --git a/APMrover2/Steering.cpp b/APMrover2/Steering.cpp index 4c7de23018..bef219ebfc 100644 --- a/APMrover2/Steering.cpp +++ b/APMrover2/Steering.cpp @@ -31,7 +31,7 @@ bool Rover::auto_check_trigger(void) // check for user pressing the auto trigger to off if (auto_triggered && g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 1) { - gcs_send_text_P(SEVERITY_LOW, PSTR("AUTO triggered off")); + gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("AUTO triggered off")); auto_triggered = false; return false; } @@ -49,7 +49,7 @@ bool Rover::auto_check_trigger(void) } if (g.auto_trigger_pin != -1 && check_digital_pin(g.auto_trigger_pin) == 0) { - gcs_send_text_P(SEVERITY_LOW, PSTR("Triggered AUTO with pin")); + gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Triggered AUTO with pin")); auto_triggered = true; return true; } diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index fb4299e335..5532021827 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -30,7 +30,7 @@ void Rover::set_next_WP(const struct Location& loc) // location as the previous waypoint, to prevent immediately // considering the waypoint complete if (location_passed_point(current_loc, prev_WP, next_WP)) { - gcs_send_text_P(SEVERITY_LOW, PSTR("Resetting prev_WP")); + gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("Resetting prev_WP")); prev_WP = current_loc; } @@ -63,7 +63,7 @@ void Rover::init_home() return; } - gcs_send_text_P(SEVERITY_LOW, PSTR("init home")); + gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("init home")); ahrs.set_home(gps.location()); home_is_set = true; diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index dc2a162e7b..6d2a9c8790 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -164,7 +164,7 @@ bool Rover::verify_command(const AP_Mission::Mission_Command& cmd) // this is a command that doesn't require verify return true; } - gcs_send_text_P(SEVERITY_HIGH,PSTR("verify_conditon: Unsupported command")); + gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("verify_conditon: Unsupported command")); return true; } return false; @@ -248,7 +248,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd) bool Rover::verify_RTL() { if (wp_distance <= g.waypoint_radius) { - gcs_send_text_P(SEVERITY_LOW,PSTR("Reached Destination")); + gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("Reached Destination")); rtl_complete = true; return true; } diff --git a/APMrover2/navigation.cpp b/APMrover2/navigation.cpp index 51a3642e86..5994d3a55e 100644 --- a/APMrover2/navigation.cpp +++ b/APMrover2/navigation.cpp @@ -22,7 +22,7 @@ void Rover::navigate() wp_distance = get_distance(current_loc, next_WP); if (wp_distance < 0){ - gcs_send_text_P(SEVERITY_HIGH,PSTR(" WP error - distance < 0")); + gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR(" WP error - distance < 0")); return; } diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index 900503f693..2c8893a1e3 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -4,9 +4,9 @@ void Rover::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")); } void Rover::init_sonar(void) diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index bb5ed7fed8..3d0bb0ffc7 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -229,10 +229,10 @@ void Rover::startup_ground(void) { set_mode(INITIALISING); - gcs_send_text_P(SEVERITY_LOW,PSTR(" GROUND START")); + gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR(" GROUND START")); #if(GROUND_START_DELAY > 0) - gcs_send_text_P(SEVERITY_LOW,PSTR(" With Delay")); + gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR(" With Delay")); delay(GROUND_START_DELAY * 1000); #endif @@ -256,7 +256,7 @@ void Rover::startup_ground(void) ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_dataflash(&DataFlash); - gcs_send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to drive.")); + gcs_send_text_P(MAV_SEVERITY_WARNING,PSTR("\n\n Ready to drive.")); } /* @@ -394,12 +394,12 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, bool on) void Rover::startup_INS_ground(void) { - gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC...")); + gcs_send_text_P(MAV_SEVERITY_ALERT, PSTR("Warming up ADC...")); mavlink_delay(500); // Makes the servos wiggle twice - about to begin INS calibration - HOLD LEVEL AND STILL!! // ----------------------- - gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Beginning INS calibration; do not move vehicle")); + gcs_send_text_P(MAV_SEVERITY_ALERT, PSTR("Beginning INS calibration; do not move vehicle")); mavlink_delay(1000); ahrs.init();