mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Camera: Correct trigger behaviour when cmd is switched off then on again
This commit is contained in:
parent
d813ee27de
commit
c97cc71382
@ -343,6 +343,8 @@ void AP_Camera::update()
|
||||
}
|
||||
|
||||
if (is_zero(_trigg_dist)) {
|
||||
_last_location.lat = 0;
|
||||
_last_location.lng = 0;
|
||||
return;
|
||||
}
|
||||
if (_last_location.lat == 0 && _last_location.lng == 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user