Copter: enabled CAM_TRIGG_DIST parameter
This commit is contained in:
parent
a5586ec394
commit
3e82f644ea
@ -1373,6 +1373,10 @@ static void update_GPS(void)
|
|||||||
ground_start_count = 10;
|
ground_start_count = 10;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if CAMERA == ENABLED
|
||||||
|
camera.update_location(current_loc);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for loss of gps
|
// check for loss of gps
|
||||||
|
Loading…
Reference in New Issue
Block a user