mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APM_Control: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
9168a8fc50
commit
f930c38712
@ -247,6 +247,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
|
||||
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (now - last_log_ms >= 40) {
|
||||
// log at 25Hz
|
||||
struct log_ATRP pkt = {
|
||||
@ -269,6 +270,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
last_log_ms = now;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (new_state == state) {
|
||||
if (state == ATState::IDLE &&
|
||||
|
@ -363,6 +363,7 @@ void AR_PosControl::get_srate(float &velocity_srate)
|
||||
velocity_srate = _pid_vel.get_pid_info_x().slew_rate;
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// write PSC logs
|
||||
void AR_PosControl::write_log()
|
||||
{
|
||||
@ -401,6 +402,7 @@ void AR_PosControl::write_log()
|
||||
_accel_target.y * 100.0, // target accel
|
||||
curr_accel_NED.y); // accel
|
||||
}
|
||||
#endif
|
||||
|
||||
/// initialise ekf xy position reset check
|
||||
void AR_PosControl::init_ekf_xy_reset()
|
||||
|
Loading…
Reference in New Issue
Block a user