Copter: eliminate GCS_MAVLINK::send_statustext_all

This commit is contained in:
Peter Barker 2017-07-09 13:47:39 +10:00 committed by Francisco Ferreira
parent 69c7402c9c
commit 592729733e
4 changed files with 29 additions and 29 deletions

View File

@ -156,7 +156,7 @@ bool AP_Arming_Copter::fence_checks(bool display_failure)
const char *fail_msg = nullptr;
if (!copter.fence.pre_arm_check(fail_msg)) {
if (display_failure && fail_msg != nullptr) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", fail_msg);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: %s", fail_msg);
}
return false;
}
@ -421,7 +421,7 @@ bool AP_Arming_Copter::pre_arm_gps_checks(bool display_failure)
if (display_failure) {
const char *reason = ahrs.prearm_failure_reason();
if (reason) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
} else {
if (!mode_requires_gps && fence_requires_gps) {
// clarify to user why they need GPS in non-GPS flight mode
@ -545,7 +545,7 @@ bool AP_Arming_Copter::pre_arm_proximity_check(bool display_failure)
// display error if something is within 60cm
if (distance <= 0.6f) {
if (display_failure) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Proximity %d deg, %4.2fm", (int)angle_deg, (double)distance);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Proximity %d deg, %4.2fm", (int)angle_deg, (double)distance);
}
return false;
}
@ -699,7 +699,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
const char *fail_msg = nullptr;
if (!copter.fence.pre_arm_check(fail_msg)) {
if (display_failure && fail_msg != nullptr) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Arm: %s", fail_msg);
gcs().send_text(MAV_SEVERITY_CRITICAL, "Arm: %s", fail_msg);
}
return false;
}

View File

@ -47,18 +47,18 @@ void Copter::set_simple_mode(uint8_t b)
switch (b) {
case 0:
Log_Write_Event(DATA_SET_SIMPLE_OFF);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode off");
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off");
break;
case 1:
Log_Write_Event(DATA_SET_SIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode on");
gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on");
break;
case 2:
default:
// initialise super simple heading
update_super_simple_bearing(true);
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on");
break;
}
ap.simple_mode = b;

View File

@ -298,21 +298,21 @@ const char *Copter::autotune_level_issue_string() const
void Copter::autotune_send_step_string()
{
if (autotune_state.pilot_override) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Paused: Pilot Override Active");
return;
}
switch (autotune_state.step) {
case AUTOTUNE_STEP_WAITING_FOR_LEVEL:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: WFL (%s) (%f > %f)", autotune_level_issue_string(), (double)(autotune_level_problem.current*0.01f), (double)(autotune_level_problem.maximum*0.01f));
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: WFL (%s) (%f > %f)", autotune_level_issue_string(), (double)(autotune_level_problem.current*0.01f), (double)(autotune_level_problem.maximum*0.01f));
return;
case AUTOTUNE_STEP_UPDATE_GAINS:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: UPDATING_GAINS");
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: UPDATING_GAINS");
return;
case AUTOTUNE_STEP_TWITCHING:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: TWITCHING");
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: TWITCHING");
return;
}
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: unknown step");
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: unknown step");
}
const char *Copter::autotune_type_string() const
@ -367,26 +367,26 @@ void Copter::autotune_do_gcs_announcements()
break;
}
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: (%c) %s", axis, autotune_type_string());
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: (%c) %s", axis, autotune_type_string());
autotune_send_step_string();
if (!is_zero(lean_angle)) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: lean=%f target=%f", (double)lean_angle, (double)autotune_target_angle);
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: lean=%f target=%f", (double)lean_angle, (double)autotune_target_angle);
}
if (!is_zero(rotation_rate)) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: rotation=%f target=%f", (double)(rotation_rate*0.01f), (double)(autotune_target_rate*0.01f));
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: rotation=%f target=%f", (double)(rotation_rate*0.01f), (double)(autotune_target_rate*0.01f));
}
switch (autotune_state.tune_type) {
case AUTOTUNE_TYPE_RD_UP:
case AUTOTUNE_TYPE_RD_DOWN:
case AUTOTUNE_TYPE_RP_UP:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: p=%f d=%f", (double)tune_rp, (double)tune_rd);
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f d=%f", (double)tune_rp, (double)tune_rd);
break;
case AUTOTUNE_TYPE_SP_DOWN:
case AUTOTUNE_TYPE_SP_UP:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: p=%f accel=%f", (double)tune_sp, (double)tune_accel);
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: p=%f accel=%f", (double)tune_sp, (double)tune_accel);
break;
}
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: success %u/%u", autotune_counter, AUTOTUNE_SUCCESS_COUNT);
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: success %u/%u", autotune_counter, AUTOTUNE_SUCCESS_COUNT);
autotune_announce_time = now;
}
@ -575,7 +575,7 @@ void Copter::autotune_attitude_control()
// if we have been level for a sufficient amount of time (0.5 seconds) move onto tuning step
if (millis() - autotune_step_start_time >= AUTOTUNE_REQUIRED_LEVEL_TIME_MS) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "AutoTune: Twitch");
gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Twitch");
// initiate variables for next step
autotune_state.step = AUTOTUNE_STEP_TWITCHING;
autotune_step_start_time = millis();

View File

@ -49,21 +49,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
if (plane.aparm.roll_limit_cd < 300) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_ROLL_CD too small (%u)", plane.aparm.roll_limit_cd);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: LIM_ROLL_CD too small (%u)", plane.aparm.roll_limit_cd);
}
ret = false;
}
if (plane.aparm.pitch_limit_max_cd < 300) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_PITCH_MAX too small (%u)", plane.aparm.pitch_limit_max_cd);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: LIM_PITCH_MAX too small (%u)", plane.aparm.pitch_limit_max_cd);
}
ret = false;
}
if (plane.aparm.pitch_limit_min_cd > -300) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: LIM_PITCH_MIN too large (%u)", plane.aparm.pitch_limit_min_cd);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: LIM_PITCH_MIN too large (%u)", plane.aparm.pitch_limit_min_cd);
}
ret = false;
}
@ -73,21 +73,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
plane.g.throttle_fs_value <
plane.channel_throttle->get_radio_max()) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Invalid THR_FS_VALUE for rev throttle");
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Invalid THR_FS_VALUE for rev throttle");
}
ret = false;
}
if (plane.quadplane.available() && plane.scheduler.get_loop_rate_hz() < 100) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: quadplane needs SCHED_LOOP_RATE > 100");
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: quadplane needs SCHED_LOOP_RATE > 100");
}
ret = false;
}
if (plane.control_mode == AUTO && plane.mission.num_commands() <= 1) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: No mission loaded");
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: No mission loaded");
}
ret = false;
}
@ -95,7 +95,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
// check adsb avoidance failsafe
if (plane.failsafe.adsb) {
if (report) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,"PreArm: ADSB threat detected");
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: ADSB threat detected");
}
ret = false;
}
@ -104,7 +104,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
if (plane.last_mixer_crc == -1) {
if (report) {
// if you ever get this error, a reboot is recommended.
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL,"PreArm: Mixer error");
gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: Mixer error");
}
ret = false;
}
@ -127,9 +127,9 @@ bool AP_Arming_Plane::ins_checks(bool report)
if (report) {
const char *reason = ahrs.prearm_failure_reason();
if (reason) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: %s", reason);
} else {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: AHRS not healthy");
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: AHRS not healthy");
}
}
return false;