mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
added define for optflow
This commit is contained in:
parent
d7af42c925
commit
0491d4feca
@ -744,12 +744,13 @@ static void medium_loop()
|
|||||||
// If we have optFlow enabled we can grab a more accurate speed
|
// If we have optFlow enabled we can grab a more accurate speed
|
||||||
// here and override the speed from the GPS
|
// here and override the speed from the GPS
|
||||||
// ----------------------------------------
|
// ----------------------------------------
|
||||||
|
#ifdef OPTFLOW_ENABLED
|
||||||
if(g.optflow_enabled && current_loc.alt < 500){
|
if(g.optflow_enabled && current_loc.alt < 500){
|
||||||
// optflow wont be enabled on 1280's
|
// optflow wont be enabled on 1280's
|
||||||
x_GPS_speed = optflow.x_cm;
|
x_GPS_speed = optflow.x_cm;
|
||||||
y_GPS_speed = optflow.y_cm;
|
y_GPS_speed = optflow.y_cm;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
// control mode specific updates
|
// control mode specific updates
|
||||||
// -----------------------------
|
// -----------------------------
|
||||||
update_navigation();
|
update_navigation();
|
||||||
|
Loading…
Reference in New Issue
Block a user