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