Plane: eliminate GCS_MAVLINK::send_statustext_all

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

View File

@ -540,7 +540,7 @@ void Plane::handle_auto_mode(void)
// this could happen if AP_Landing::restart_landing_sequence() returns false which would only happen if:
// restart_landing_sequence() is called when not executing a NAV_LAND or there is no previous nav point
set_mode(RTL, MODE_REASON_MISSION_END);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Aircraft in auto without a running mission");
gcs().send_text(MAV_SEVERITY_INFO, "Aircraft in auto without a running mission");
return;
}

View File

@ -90,7 +90,7 @@ MAV_COLLISION_ACTION AP_Avoidance_Plane::handle_avoidance(const AP_Avoidance::Ob
}
if (failsafe_state_change) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_ALERT, "Avoid: Performing action: %d", actual_action);
gcs().send_text(MAV_SEVERITY_ALERT, "Avoid: Performing action: %d", actual_action);
}
// return with action taken
@ -102,7 +102,7 @@ void AP_Avoidance_Plane::handle_recovery(uint8_t recovery_action)
// check we are coming out of failsafe
if (plane.failsafe.adsb) {
plane.failsafe.adsb = false;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Avoid: Resuming with action: %d", recovery_action);
gcs().send_text(MAV_SEVERITY_INFO, "Avoid: Resuming with action: %d", recovery_action);
// restore flight mode if requested and user has not changed mode since
if (plane.control_mode_reason == MODE_REASON_AVOIDANCE) {

View File

@ -488,7 +488,7 @@ bool QuadPlane::setup(void)
if (hal.util->available_memory() <
4096 + sizeof(*motors) + sizeof(*attitude_control) + sizeof(*pos_control) + sizeof(*wp_nav)) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Not enough memory for quadplane");
gcs().send_text(MAV_SEVERITY_INFO, "Not enough memory for quadplane");
goto failed;
}
@ -609,14 +609,14 @@ bool QuadPlane::setup(void)
setup_defaults();
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "QuadPlane initialised");
gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane initialised");
initialised = true;
return true;
failed:
initialised = false;
enable.set(0);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "QuadPlane setup failed");
gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane setup failed");
return false;
}
@ -627,7 +627,7 @@ void QuadPlane::setup_defaults_table(const struct defaults_struct *table, uint8_
{
for (uint8_t i=0; i<count; i++) {
if (!AP_Param::set_default_by_name(table[i].name, table[i].value)) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "QuadPlane setup failure for %s",
gcs().send_text(MAV_SEVERITY_INFO, "QuadPlane setup failure for %s",
table[i].name);
AP_HAL::panic("quadplane bad default %s", table[i].name);
}
@ -662,7 +662,7 @@ void QuadPlane::run_esc_calibration(void)
return;
}
if (!AP_Notify::flags.esc_calibration) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Starting ESC calibration");
gcs().send_text(MAV_SEVERITY_INFO, "Starting ESC calibration");
}
AP_Notify::flags.esc_calibration = true;
switch (esc_calibration) {
@ -747,7 +747,7 @@ void QuadPlane::run_z_controller(void)
if (now - last_pidz_active_ms > 2000) {
// set alt target to current height on transition. This
// starts the Z controller off with the right values
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)inertial_nav.get_altitude());
gcs().send_text(MAV_SEVERITY_INFO, "Reset alt target to %.1f", (double)inertial_nav.get_altitude());
pos_control->set_alt_target(inertial_nav.get_altitude());
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
@ -792,7 +792,7 @@ void QuadPlane::check_yaw_reset(void)
if (new_ekfYawReset_ms != ekfYawReset_ms) {
attitude_control->shift_ef_yaw_target(degrees(yaw_angle_change_rad) * 100);
ekfYawReset_ms = new_ekfYawReset_ms;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "EKF yaw reset %.2f", (double)degrees(yaw_angle_change_rad));
gcs().send_text(MAV_SEVERITY_INFO, "EKF yaw reset %.2f", (double)degrees(yaw_angle_change_rad));
}
}
@ -1156,7 +1156,7 @@ bool QuadPlane::assistance_needed(float aspeed)
bool ret = (AP_HAL::millis() - angle_error_start_ms) >= 1000U;
if (ret && !in_angle_assist) {
in_angle_assist = true;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Angle assist r=%d p=%d",
gcs().send_text(MAV_SEVERITY_INFO, "Angle assist r=%d p=%d",
(int)(ahrs.roll_sensor/100),
(int)(ahrs.pitch_sensor/100));
}
@ -1195,7 +1195,7 @@ void QuadPlane::update_transition(void)
plane.is_flying())) {
// the quad should provide some assistance to the plane
if (transition_state != TRANSITION_AIRSPEED_WAIT) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Transition started airspeed %.1f", (double)aspeed);
gcs().send_text(MAV_SEVERITY_INFO, "Transition started airspeed %.1f", (double)aspeed);
}
transition_state = TRANSITION_AIRSPEED_WAIT;
transition_start_ms = millis();
@ -1207,7 +1207,7 @@ void QuadPlane::update_transition(void)
if (is_tailsitter()) {
if (transition_state == TRANSITION_ANGLE_WAIT &&
tailsitter_transition_complete()) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Transition done");
gcs().send_text(MAV_SEVERITY_INFO, "Transition done");
transition_state = TRANSITION_DONE;
}
}
@ -1240,14 +1240,14 @@ void QuadPlane::update_transition(void)
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// we hold in hover until the required airspeed is reached
if (transition_start_ms == 0) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Transition airspeed wait");
gcs().send_text(MAV_SEVERITY_INFO, "Transition airspeed wait");
transition_start_ms = millis();
}
if (have_airspeed && aspeed > plane.aparm.airspeed_min && !assisted_flight) {
transition_start_ms = millis();
transition_state = TRANSITION_TIMER;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Transition airspeed reached %.1f", (double)aspeed);
gcs().send_text(MAV_SEVERITY_INFO, "Transition airspeed reached %.1f", (double)aspeed);
}
assisted_flight = true;
hold_hover(assist_climb_rate_cms());
@ -1272,7 +1272,7 @@ void QuadPlane::update_transition(void)
// transition time, but continue to stabilize
if (millis() - transition_start_ms > (unsigned)transition_time_ms) {
transition_state = TRANSITION_DONE;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Transition done");
gcs().send_text(MAV_SEVERITY_INFO, "Transition done");
}
float trans_time_ms = (float)transition_time_ms.get();
float transition_scale = (trans_time_ms - (millis() - transition_start_ms)) / trans_time_ms;
@ -1511,7 +1511,7 @@ bool QuadPlane::init_mode(void)
return false;
}
if (!initialised) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "QuadPlane mode refused");
gcs().send_text(MAV_SEVERITY_CRITICAL, "QuadPlane mode refused");
return false;
}

View File

@ -21,7 +21,7 @@ void Plane::update_soaring() {
case FLY_BY_WIRE_B:
case CRUISE:
if (!g2.soaring_controller.suppress_throttle()) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Soaring: forcing RTL");
gcs().send_text(MAV_SEVERITY_INFO, "Soaring: forcing RTL");
set_mode(RTL, MODE_REASON_SOARING_FBW_B_WITH_MOTOR_RUNNING);
}
break;
@ -48,7 +48,7 @@ void Plane::update_soaring() {
g2.soaring_controller.update_cruising();
if (g2.soaring_controller.check_thermal_criteria()) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Soaring: Thermal detected, entering loiter");
gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Thermal detected, entering loiter");
set_mode(LOITER, MODE_REASON_SOARING_THERMAL_DETECTED);
}
break;
@ -61,14 +61,14 @@ void Plane::update_soaring() {
// Exit as soon as thermal state estimate deteriorates
switch (previous_mode) {
case FLY_BY_WIRE_B:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Soaring: Thermal ended, entering RTL");
gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Thermal ended, entering RTL");
set_mode(RTL, MODE_REASON_SOARING_THERMAL_ESTIMATE_DETERIORATED);
break;
case CRUISE: {
// return to cruise with old ground course
CruiseState cruise = cruise_state;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Soaring: Thermal ended, restoring CRUISE");
gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Thermal ended, restoring CRUISE");
set_mode(CRUISE, MODE_REASON_SOARING_THERMAL_ESTIMATE_DETERIORATED);
cruise_state = cruise;
set_target_altitude_current();
@ -76,7 +76,7 @@ void Plane::update_soaring() {
}
case AUTO:
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Soaring: Thermal ended, restoring AUTO");
gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Thermal ended, restoring AUTO");
set_mode(AUTO, MODE_REASON_SOARING_THERMAL_ESTIMATE_DETERIORATED);
break;