5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 23:48:31 -04:00

Tracker: text message severity uniformization

Continuing the uniformization, now for AntennaTracker
This commit is contained in:
lvale 2015-11-04 00:57:18 +00:00 committed by Randy Mackay
parent a64689600f
commit e7efaa45c5
5 changed files with 11 additions and 11 deletions

View File

@ -599,7 +599,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(MAV_SEVERITY_WARNING,"command received: "); send_text(MAV_SEVERITY_INFO,"command received: ");
switch(packet.command) { switch(packet.command) {
@ -827,7 +827,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(MAV_SEVERITY_WARNING,"new HOME received"); send_text(MAV_SEVERITY_INFO,"new HOME received");
waypoint_receiving = false; waypoint_receiving = false;
} }
@ -916,7 +916,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(MAV_SEVERITY_WARNING, "Initialising APM..."); gcs_send_text(MAV_SEVERITY_INFO, "Initialising APM...");
} }
in_mavlink_delay = false; in_mavlink_delay = false;
} }
@ -974,10 +974,10 @@ void Tracker::gcs_send_text(MAV_SEVERITY severity, const char *str)
* only one fits in the queue, so if you send more than one before the * only one fits in the queue, so if you send more than one before the
* last one gets into the serial buffer then the old one will be lost * last one gets into the serial buffer then the old one will be lost
*/ */
void Tracker::gcs_send_text_fmt(const char *fmt, ...) void Tracker::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
{ {
va_list arg_list; va_list arg_list;
gcs[0].pending_status.severity = (uint8_t)MAV_SEVERITY_WARNING; gcs[0].pending_status.severity = (uint8_t)severity;
va_start(arg_list, fmt); va_start(arg_list, fmt);
hal.util->vsnprintf((char *)gcs[0].pending_status.text, hal.util->vsnprintf((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

@ -243,7 +243,7 @@ private:
void tracking_update_pressure(const mavlink_scaled_pressure_t &msg); void tracking_update_pressure(const mavlink_scaled_pressure_t &msg);
void tracking_manual_control(const mavlink_manual_control_t &msg); void tracking_manual_control(const mavlink_manual_control_t &msg);
void update_armed_disarmed(); void update_armed_disarmed();
void gcs_send_text_fmt(const char *fmt, ...); void gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...);
void init_capabilities(void); void init_capabilities(void);
void compass_cal_update(); void compass_cal_update();

View File

@ -4,9 +4,9 @@
void Tracker::init_barometer(void) void Tracker::init_barometer(void)
{ {
gcs_send_text(MAV_SEVERITY_WARNING, "Calibrating barometer"); gcs_send_text(MAV_SEVERITY_INFO, "Calibrating barometer");
barometer.calibrate(); barometer.calibrate();
gcs_send_text(MAV_SEVERITY_WARNING, "barometer calibration complete"); gcs_send_text(MAV_SEVERITY_INFO, "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

@ -248,7 +248,7 @@ void Tracker::update_yaw_position_servo(float yaw)
} }
if (new_slew_dir != slew_dir) { if (new_slew_dir != slew_dir) {
tracker.gcs_send_text_fmt("SLEW: %d/%d err=%ld servo=%ld ez=%.3f", tracker.gcs_send_text_fmt(MAV_SEVERITY_WARNING, "SLEW: %d/%d err=%ld servo=%ld ez=%.3f",
(int)slew_dir, (int)new_slew_dir, (int)slew_dir, (int)new_slew_dir,
(long)angle_err, (long)angle_err,
(long)channel_yaw.servo_out, (long)channel_yaw.servo_out,

View File

@ -94,7 +94,7 @@ void Tracker::init_tracker()
if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 180.0f) { if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 180.0f) {
current_loc.lat = g.start_latitude * 1.0e7f; current_loc.lat = g.start_latitude * 1.0e7f;
current_loc.lng = g.start_longitude * 1.0e7f; current_loc.lng = g.start_longitude * 1.0e7f;
gcs_send_text(MAV_SEVERITY_WARNING, "ignoring invalid START_LATITUDE or START_LONGITUDE parameter"); gcs_send_text(MAV_SEVERITY_NOTICE, "ignoring invalid START_LATITUDE or START_LONGITUDE parameter");
} }
// see if EEPROM has a default location as well // see if EEPROM has a default location as well
@ -104,7 +104,7 @@ void Tracker::init_tracker()
init_capabilities(); init_capabilities();
gcs_send_text(MAV_SEVERITY_WARNING,"\nReady to track."); gcs_send_text(MAV_SEVERITY_INFO,"\nReady to track.");
hal.scheduler->delay(1000); // Why???? hal.scheduler->delay(1000); // Why????
set_mode(AUTO); // tracking set_mode(AUTO); // tracking