|
|
|
@ -105,7 +105,7 @@ struct PACKED log_Control_Tuning {
@@ -105,7 +105,7 @@ struct PACKED log_Control_Tuning {
|
|
|
|
|
float throttle_hover; |
|
|
|
|
float desired_alt; |
|
|
|
|
float inav_alt; |
|
|
|
|
int32_t baro_alt; |
|
|
|
|
float baro_alt; |
|
|
|
|
int16_t desired_rangefinder_alt; |
|
|
|
|
int16_t rangefinder_alt; |
|
|
|
|
float terr_alt; |
|
|
|
@ -131,7 +131,7 @@ void Sub::Log_Write_Control_Tuning()
@@ -131,7 +131,7 @@ void Sub::Log_Write_Control_Tuning()
|
|
|
|
|
throttle_hover : motors.get_throttle_hover(), |
|
|
|
|
desired_alt : pos_control.get_alt_target() / 100.0f, |
|
|
|
|
inav_alt : inertial_nav.get_altitude() / 100.0f, |
|
|
|
|
baro_alt : baro_alt, |
|
|
|
|
baro_alt : barometer.get_altitude(), |
|
|
|
|
desired_rangefinder_alt : (int16_t)target_rangefinder_alt, |
|
|
|
|
rangefinder_alt : rangefinder_state.alt_cm, |
|
|
|
|
terr_alt : terr_alt, |
|
|
|
@ -434,7 +434,7 @@ const struct LogStructure Sub::log_structure[] = {
@@ -434,7 +434,7 @@ const struct LogStructure Sub::log_structure[] = {
|
|
|
|
|
{ LOG_NAV_TUNING_MSG, sizeof(log_Nav_Tuning),
|
|
|
|
|
"NTUN", "Qffffffffff", "TimeUS,DPosX,DPosY,PosX,PosY,DVelX,DVelY,VelX,VelY,DAccX,DAccY" }, |
|
|
|
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), |
|
|
|
|
"CTUN", "Qffffffeccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt" }, |
|
|
|
|
"CTUN", "Qfffffffccfhh", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt" }, |
|
|
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
|
|
|
|
"PM", "QHHIhBHII", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop,Mem" }, |
|
|
|
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt), |
|
|
|
|