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

Remove erratic logging of first home position into CMD log #22546

Merged
merged 3 commits into from
Jan 3, 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
16 changes: 0 additions & 16 deletions ArduCopter/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ bool Copter::set_home_to_current_location(bool lock) {
}

// set_home - sets ahrs home (used for RTL) to specified location
// initialises inertial nav and compass on first call
// returns true if home location set successfully
bool Copter::set_home(const Location& loc, bool lock)
{
Expand All @@ -69,26 +68,11 @@ bool Copter::set_home(const Location& loc, bool lock)
return false;
}

const bool home_was_set = ahrs.home_is_set();

// set ahrs home (used for RTL)
if (!ahrs.set_home(loc)) {
return false;
}

// init inav and compass declination
if (!home_was_set) {
#if MODE_AUTO_ENABLED == ENABLED
// log new home position which mission library will pull from ahrs
if (should_log(MASK_LOG_CMD)) {
AP_Mission::Mission_Command temp_cmd;
if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) {
logger.Write_Mission_Cmd(mode_auto.mission, temp_cmd);
}
}
#endif
}

// lock home position
if (lock) {
ahrs.lock_home();
Expand Down
14 changes: 0 additions & 14 deletions ArduSub/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,6 @@ bool Sub::set_home_to_current_location(bool lock)
}

// set_home - sets ahrs home (used for RTL) to specified location
// initialises inertial nav and compass on first call
// returns true if home location set successfully
bool Sub::set_home(const Location& loc, bool lock)
{
Expand All @@ -61,24 +60,11 @@ bool Sub::set_home(const Location& loc, bool lock)
return false;
}

const bool home_was_set = ahrs.home_is_set();

// set ahrs home (used for RTL)
if (!ahrs.set_home(loc)) {
return false;
}

// init inav and compass declination
if (!home_was_set) {
// log new home position which mission library will pull from ahrs
if (should_log(MASK_LOG_CMD)) {
AP_Mission::Mission_Command temp_cmd;
if (mission.read_cmd_from_storage(0, temp_cmd)) {
logger.Write_Mission_Cmd(mission, temp_cmd);
}
}
}

// lock home position
if (lock) {
ahrs.lock_home();
Expand Down
12 changes: 0 additions & 12 deletions Rover/commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,23 +19,11 @@ bool Rover::set_home_to_current_location(bool lock)
// returns true if home location set successfully
bool Rover::set_home(const Location& loc, bool lock)
{
const bool home_was_set = ahrs.home_is_set();

// set ahrs home
if (!ahrs.set_home(loc)) {
return false;
}

if (!home_was_set) {
// log new home position which mission library will pull from ahrs
if (should_log(MASK_LOG_CMD)) {
AP_Mission::Mission_Command temp_cmd;
if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) {
logger.Write_Mission_Cmd(mode_auto.mission, temp_cmd);
}
}
}

// lock home position
if (lock) {
ahrs.lock_home();
Expand Down