mirror of https://github.com/ArduPilot/ardupilot
Plane: always log tailsitter scalefactor
This commit is contained in:
parent
840f129153
commit
b225ae43ab
|
@ -2943,7 +2943,7 @@ void QuadPlane::Log_Write_QControl_Tuning()
|
|||
target_climb_rate : target_climb_rate_cms,
|
||||
climb_rate : int16_t(inertial_nav.get_velocity_z()),
|
||||
throttle_mix : attitude_control->get_throttle_mix(),
|
||||
speed_scaler : last_spd_scaler,
|
||||
speed_scaler : log_spd_scaler,
|
||||
transition_state : static_cast<uint8_t>(transition_state)
|
||||
};
|
||||
plane.logger.WriteBlock(&pkt, sizeof(pkt));
|
||||
|
|
|
@ -515,7 +515,8 @@ private:
|
|||
} tailsitter;
|
||||
|
||||
// tailsitter speed scaler
|
||||
float last_spd_scaler = 1.0f;
|
||||
float last_spd_scaler = 1.0f; // used to slew rate limiting with TAILSITTER_GSCL_ATT_THR option
|
||||
float log_spd_scaler; // for QTUN log
|
||||
|
||||
// the attitude view of the VTOL attitude controller
|
||||
AP_AHRS_View *ahrs_view;
|
||||
|
|
|
@ -338,6 +338,9 @@ void QuadPlane::tailsitter_speed_scaling(void)
|
|||
}
|
||||
}
|
||||
|
||||
// record for QTUN log
|
||||
log_spd_scaler = spd_scaler;
|
||||
|
||||
const SRV_Channel::Aux_servo_function_t functions[] = {
|
||||
SRV_Channel::Aux_servo_function_t::k_aileron,
|
||||
SRV_Channel::Aux_servo_function_t::k_elevator,
|
||||
|
|
Loading…
Reference in New Issue