mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: privatize AHRS logging
This commit is contained in:
parent
9daa3bbdaa
commit
cc1e395854
|
@ -206,7 +206,7 @@ void Plane::update_logging1(void)
|
||||||
logger.Write_IMU();
|
logger.Write_IMU();
|
||||||
|
|
||||||
if (should_log(MASK_LOG_ATTITUDE_MED))
|
if (should_log(MASK_LOG_ATTITUDE_MED))
|
||||||
logger.Write_AOA_SSA(ahrs);
|
ahrs.Write_AOA_SSA();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -18,9 +18,9 @@ void Plane::Log_Write_Attitude(void)
|
||||||
// Get them from the quaternion instead:
|
// Get them from the quaternion instead:
|
||||||
quadplane.attitude_control->get_attitude_target_quat().to_euler(targets.x, targets.y, targets.z);
|
quadplane.attitude_control->get_attitude_target_quat().to_euler(targets.x, targets.y, targets.z);
|
||||||
targets *= degrees(100.0f);
|
targets *= degrees(100.0f);
|
||||||
logger.Write_AttitudeView(*quadplane.ahrs_view, targets);
|
quadplane.ahrs_view->Write_AttitudeView(targets);
|
||||||
} else {
|
} else {
|
||||||
logger.Write_Attitude(targets);
|
ahrs.Write_Attitude(targets);
|
||||||
}
|
}
|
||||||
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
||||||
// log quadplane PIDs separately from fixed wing PIDs
|
// log quadplane PIDs separately from fixed wing PIDs
|
||||||
|
@ -37,12 +37,12 @@ void Plane::Log_Write_Attitude(void)
|
||||||
|
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
AP::ahrs_navekf().Log_Write();
|
AP::ahrs_navekf().Log_Write();
|
||||||
logger.Write_AHRS2();
|
ahrs.Write_AHRS2();
|
||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
sitl.Log_Write_SIMSTATE();
|
sitl.Log_Write_SIMSTATE();
|
||||||
#endif
|
#endif
|
||||||
logger.Write_POS();
|
ahrs.Write_POS();
|
||||||
}
|
}
|
||||||
|
|
||||||
// do fast logging for plane
|
// do fast logging for plane
|
||||||
|
@ -376,14 +376,6 @@ const struct LogStructure Plane::log_structure[] = {
|
||||||
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
|
{ LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning),
|
||||||
"QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" },
|
"QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" },
|
||||||
|
|
||||||
// @LoggerMessage: AOA
|
|
||||||
// @Description: Angle of attack and Side Slip Angle values
|
|
||||||
// @Field: TimeUS: Time since system startup
|
|
||||||
// @Field: AOA: Angle of Attack calculated from airspeed, wind vector,velocity vector
|
|
||||||
// @Field: SSA: Side Slip Angle calculated from airspeed, wind vector,velocity vector
|
|
||||||
{ LOG_AOA_SSA_MSG, sizeof(log_AOA_SSA),
|
|
||||||
"AOA", "Qff", "TimeUS,AOA,SSA", "sdd", "F00" },
|
|
||||||
|
|
||||||
// @LoggerMessage: PIQR,PIQP,PIQY,PIQA
|
// @LoggerMessage: PIQR,PIQP,PIQY,PIQA
|
||||||
// @Description: QuadPlane Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Z
|
// @Description: QuadPlane Proportional/Integral/Derivative gain values for Roll/Pitch/Yaw/Z
|
||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
|
|
|
@ -2206,7 +2206,7 @@ void QuadPlane::motors_output(bool run_rate_controller)
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
|
|
||||||
// log RATE at main loop rate
|
// log RATE at main loop rate
|
||||||
plane.logger.Write_Rate(ahrs_view, *motors, *attitude_control, *pos_control);
|
ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control);
|
||||||
|
|
||||||
// log QTUN at 25 Hz
|
// log QTUN at 25 Hz
|
||||||
if (now - last_qtun_log_ms > 40) {
|
if (now - last_qtun_log_ms > 40) {
|
||||||
|
|
Loading…
Reference in New Issue