mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
c977a646db
commit
dba80c95d5
|
@ -312,7 +312,7 @@ void AP_Camera::update()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (get_distance(current_loc, _last_location) < _trigg_dist) {
|
if (current_loc.get_distance(_last_location) < _trigg_dist) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue