mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControl: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
29f1953ad7
commit
2359ffc7da
|
@ -1160,6 +1160,7 @@ void AC_PosControl::standby_xyz_reset()
|
|||
init_ekf_xy_reset();
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// write PSC and/or PSCZ logs
|
||||
void AC_PosControl::write_log()
|
||||
{
|
||||
|
@ -1180,6 +1181,7 @@ void AC_PosControl::write_log()
|
|||
-_accel_desired.z, -get_accel_target_cmss().z, -get_z_accel_cmss());
|
||||
}
|
||||
}
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
||||
/// crosstrack_error - returns horizontal error to the closest point to the current track
|
||||
float AC_PosControl::crosstrack_error() const
|
||||
|
|
|
@ -37,6 +37,7 @@ void AC_AttitudeControl::control_monitor_update(void)
|
|||
control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw);
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
/*
|
||||
log a CTRL message
|
||||
*/
|
||||
|
@ -59,6 +60,7 @@ void AC_AttitudeControl::control_monitor_log(void) const
|
|||
(double)safe_sqrt(_control_monitor.rms_yaw));
|
||||
|
||||
}
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
||||
/*
|
||||
return current controller RMS filter value for roll
|
||||
|
|
Loading…
Reference in New Issue