Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move AHRS functions out of AP_AHRS_DCM.cpp #25016

Merged
merged 2 commits into from
Sep 19, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 56 additions & 0 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2640,6 +2640,62 @@ bool AP_AHRS::_get_origin(Location &ret) const
return false;
}

bool AP_AHRS::set_home(const Location &loc)
{
WITH_SEMAPHORE(_rsem);
// check location is valid
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
return false;
}
if (!loc.check_latlng()) {
return false;
}
// home must always be global frame at the moment as .alt is
// accessed directly by the vehicles and they may not be rigorous
// in checking the frame type.
Location tmp = loc;
if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) {
return false;
}

#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
if (!_home_is_set) {
// record home is set
AP::logger().Write_Event(LogEvent::SET_HOME);
}
#endif

_home = tmp;
_home_is_set = true;

Log_Write_Home_And_Origin();

// send new home and ekf origin to GCS
GCS_SEND_MESSAGE(MSG_HOME);
GCS_SEND_MESSAGE(MSG_ORIGIN);

AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
pd.home_lat = loc.lat;
pd.home_lon = loc.lng;
pd.home_alt_cm = loc.alt;

return true;
}

/* if this was a watchdog reset then get home from backup registers */
void AP_AHRS::load_watchdog_home()
{
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) {
_home.lat = pd.home_lat;
_home.lng = pd.home_lon;
_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");
}
}

// get_hgt_ctrl_limit - get maximum height to be observed by the control loops in metres and a validity flag
// this is used to limit height during optical flow navigation
// it will return false when no limiting is required
Expand Down
58 changes: 0 additions & 58 deletions libraries/AP_AHRS/AP_AHRS_DCM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,22 +51,6 @@ AP_AHRS_DCM::reset_gyro_drift(void)
_omega_I_sum_time = 0;
}


/* if this was a watchdog reset then get home from backup registers */
void AP_AHRS::load_watchdog_home()
{
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
if (hal.util->was_watchdog_reset() && (pd.home_lat != 0 || pd.home_lon != 0)) {
_home.lat = pd.home_lat;
_home.lng = pd.home_lon;
_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");
}
}


// run a full DCM update round
void
AP_AHRS_DCM::update()
Expand Down Expand Up @@ -1119,48 +1103,6 @@ bool AP_AHRS_DCM::get_unconstrained_airspeed_estimate(uint8_t airspeed_index, fl
return false;
}

bool AP_AHRS::set_home(const Location &loc)
{
WITH_SEMAPHORE(_rsem);
// check location is valid
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
return false;
}
if (!loc.check_latlng()) {
return false;
}
// home must always be global frame at the moment as .alt is
// accessed directly by the vehicles and they may not be rigorous
// in checking the frame type.
Location tmp = loc;
if (!tmp.change_alt_frame(Location::AltFrame::ABSOLUTE)) {
return false;
}

#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
if (!_home_is_set) {
// record home is set
AP::logger().Write_Event(LogEvent::SET_HOME);
}
#endif

_home = tmp;
_home_is_set = true;

Log_Write_Home_And_Origin();

// send new home and ekf origin to GCS
GCS_SEND_MESSAGE(MSG_HOME);
GCS_SEND_MESSAGE(MSG_ORIGIN);

AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
pd.home_lat = loc.lat;
pd.home_lon = loc.lng;
pd.home_alt_cm = loc.alt;

return true;
}

/*
check if the AHRS subsystem is healthy
*/
Expand Down