mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: log quadplane transision state
This commit is contained in:
parent
f972d3dc2f
commit
6621b69836
@ -375,8 +375,9 @@ const struct LogStructure Plane::log_structure[] = {
|
||||
// @Field: CRt: climb rate
|
||||
// @Field: TMix: transition throttle mix value
|
||||
// @Field: Sscl: speed scalar for tailsitter control surfaces
|
||||
// @Field: Trans: Transistion state
|
||||
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
|
||||
"QTUN", "Qffffffeccff", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl", "s----mmmnn--", "F----00000-0" },
|
||||
"QTUN", "QffffffeccffB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trans", "s----mmmnn---", "F----00000-0-" },
|
||||
|
||||
// @LoggerMessage: AOA
|
||||
// @Description: Angle of attack and Side Slip Angle values
|
||||
|
@ -2941,6 +2941,7 @@ void QuadPlane::Log_Write_QControl_Tuning()
|
||||
climb_rate : int16_t(inertial_nav.get_velocity_z()),
|
||||
throttle_mix : attitude_control->get_throttle_mix(),
|
||||
speed_scaler : last_spd_scaler,
|
||||
transition_state : static_cast<uint8_t>(transition_state)
|
||||
};
|
||||
plane.logger.WriteBlock(&pkt, sizeof(pkt));
|
||||
|
||||
|
@ -159,6 +159,7 @@ public:
|
||||
int16_t climb_rate;
|
||||
float throttle_mix;
|
||||
float speed_scaler;
|
||||
uint8_t transition_state;
|
||||
};
|
||||
|
||||
MAV_TYPE get_mav_type(void) const;
|
||||
|
Loading…
Reference in New Issue
Block a user