mirror of https://github.com/ArduPilot/ardupilot
Copter: init_home checks cmd read success before logging
This commit is contained in:
parent
4c0a31a9dc
commit
cc7b1c4e9c
|
@ -23,8 +23,9 @@ static void init_home()
|
|||
// log new home position which mission library will pull from ahrs
|
||||
if (g.log_bitmask & MASK_LOG_CMD) {
|
||||
AP_Mission::Mission_Command temp_cmd;
|
||||
mission.read_cmd_from_storage(0, temp_cmd);
|
||||
Log_Write_Cmd(temp_cmd);
|
||||
if (mission.read_cmd_from_storage(0, temp_cmd)) {
|
||||
Log_Write_Cmd(temp_cmd);
|
||||
}
|
||||
}
|
||||
|
||||
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
|
||||
|
|
Loading…
Reference in New Issue