AP_AHRS: fixed build for SITL periph

This commit is contained in:
Andrew Tridgell 2023-08-18 06:18:05 +10:00 committed by Peter Barker
parent 9706a207b1
commit 5d4bf9fc14
3 changed files with 10 additions and 2 deletions

View File

@ -392,6 +392,7 @@ void AP_AHRS::update(bool skip_ins_update)
// update AOA and SSA
update_AOA_SSA();
#if HAL_GCS_ENABLED
EKFType active = active_EKF_type();
if (active != last_active_ekf_type) {
last_active_ekf_type = active;
@ -423,6 +424,7 @@ void AP_AHRS::update(bool skip_ins_update)
}
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "AHRS: %s active", shortname);
}
#endif // HAL_GCS_ENABLED
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
/*

View File

@ -62,7 +62,7 @@ void AP_AHRS::load_watchdog_home()
_home.set_alt_cm(pd.home_alt_cm, Location::AltFrame::ABSOLUTE);
_home_is_set = true;
_home_locked = true;
gcs().send_text(MAV_SEVERITY_INFO, "Restored watchdog home");
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog home");
}
}
@ -185,7 +185,7 @@ AP_AHRS_DCM::reset(bool recover_eulers)
pitch = pd.pitch_rad;
yaw = pd.yaw_rad;
_dcm_matrix.from_euler(roll, pitch, yaw);
gcs().send_text(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f",
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Restored watchdog attitude %.0f %.0f %.0f",
degrees(roll), degrees(pitch), degrees(yaw));
} else if (recover_eulers && !isnan(roll) && !isnan(pitch) && !isnan(yaw)) {
_dcm_matrix.from_euler(roll, pitch, yaw);
@ -485,10 +485,12 @@ AP_AHRS_DCM::drift_correction_yaw(void)
Compass &compass = AP::compass();
#if COMPASS_CAL_ENABLED
if (compass.is_calibrating()) {
// don't do any yaw correction while calibrating
return;
}
#endif
if (AP_AHRS_DCM::use_compass()) {
/*
@ -1147,9 +1149,11 @@ bool AP_AHRS::set_home(const Location &loc)
Log_Write_Home_And_Origin();
#if HAL_GCS_ENABLED
// send new home and ekf origin to GCS
gcs().send_message(MSG_HOME);
gcs().send_message(MSG_ORIGIN);
#endif
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
pd.home_lat = loc.lat;

View File

@ -181,6 +181,7 @@ bool AP_AHRS_SIM::get_mag_offsets(uint8_t mag_idx, Vector3f &magOffsets) const
void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const
{
#if HAL_GCS_ENABLED
// send status report with everything looking good
const uint16_t flags =
EKF_ATTITUDE | /* Set if EKF's attitude estimate is good. | */
@ -194,6 +195,7 @@ void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const
EKF_PRED_POS_HORIZ_REL | /* Set if EKF's predicted horizontal position (relative) estimate is good. | */
EKF_PRED_POS_HORIZ_ABS; /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */
mavlink_msg_ekf_status_report_send(link.get_chan(), flags, 0, 0, 0, 0, 0, 0);
#endif // HAL_GCS_ENABLED
}
bool AP_AHRS_SIM::get_origin(Location &ret) const