|
|
|
@ -398,7 +398,12 @@ void Plane::send_pid_tuning(mavlink_channel_t chan)
@@ -398,7 +398,12 @@ void Plane::send_pid_tuning(mavlink_channel_t chan)
|
|
|
|
|
if ((g.gcs_pid_mask & TUNING_BITS_LAND) && (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND)) { |
|
|
|
|
send_pid_info(chan, landing.get_pid_info(), PID_TUNING_LANDING, degrees(gyro.z)); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
if (g.gcs_pid_mask & TUNING_BITS_ACCZ && quadplane.in_vtol_mode()) { |
|
|
|
|
const Vector3f &accel = ahrs.get_accel_ef(); |
|
|
|
|
pid_info = &quadplane.pos_control->get_accel_z_pid().get_pid_info(); |
|
|
|
|
send_pid_info(chan, pid_info, PID_TUNING_ACCZ, -accel.z); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
uint8_t GCS_MAVLINK_Plane::sysid_my_gcs() const |
|
|
|
|
{ |
|
|
|
|