mirror of https://github.com/ArduPilot/ardupilot
Rover: remove logging of first home location into CMD message set
This commit is contained in:
parent
7e3233f8e8
commit
6e563dd834
|
@ -19,23 +19,11 @@ bool Rover::set_home_to_current_location(bool lock)
|
||||||
// returns true if home location set successfully
|
// returns true if home location set successfully
|
||||||
bool Rover::set_home(const Location& loc, bool lock)
|
bool Rover::set_home(const Location& loc, bool lock)
|
||||||
{
|
{
|
||||||
const bool home_was_set = ahrs.home_is_set();
|
|
||||||
|
|
||||||
// set ahrs home
|
// set ahrs home
|
||||||
if (!ahrs.set_home(loc)) {
|
if (!ahrs.set_home(loc)) {
|
||||||
return false;
|
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
|
// lock home position
|
||||||
if (lock) {
|
if (lock) {
|
||||||
ahrs.lock_home();
|
ahrs.lock_home();
|
||||||
|
|
Loading…
Reference in New Issue