uncrustify libraries/AP_Limits/AP_Limit_Geofence.cpp

This commit is contained in:
uncrustify 2012-08-21 19:19:52 -07:00 committed by Pat Hickey
parent 97035fbead
commit 40a4777d31
1 changed files with 99 additions and 99 deletions

View File

@ -101,7 +101,7 @@ bool AP_Limit_Geofence::triggered() {
Vector2l location;
location.x = _current_loc->lat;
location.y = _current_loc->lng;
if (Polygon_outside(location, &_boundary[1], _fence_total-1)) {// trigger if outside
if (Polygon_outside(location, &_boundary[1], _fence_total-1)) { // trigger if outside
// TRIGGER
_triggered = true;
@ -161,7 +161,7 @@ void AP_Limit_Geofence::set_fence_point_with_index(Vector2l &point, uint8_t i)
}
/*
fence boundaries fetch/store
* fence boundaries fetch/store
*/
Vector2l AP_Limit_Geofence::get_fence_point_with_index(uint8_t i)
{