mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Optical flow - updated standard frame rate to 2000hz and increased resolution to 1600cpi
This commit is contained in:
parent
13caa24515
commit
cd21c5905b
@ -92,6 +92,8 @@ static void init_optflow()
|
|||||||
SendDebug("\nFailed to Init OptFlow ");
|
SendDebug("\nFailed to Init OptFlow ");
|
||||||
}
|
}
|
||||||
optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft
|
optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft
|
||||||
|
optflow.set_frame_rate(2000); // set minimum update rate (which should lead to maximum low light performance
|
||||||
|
optflow.set_resolution(OPTFLOW_RESOLUTION); // set optical flow sensor's resolution
|
||||||
optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view
|
optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view
|
||||||
// setup timed read of sensor
|
// setup timed read of sensor
|
||||||
//timer_scheduler.register_process(&AP_OpticalFlow::read);
|
//timer_scheduler.register_process(&AP_OpticalFlow::read);
|
||||||
|
Loading…
Reference in New Issue
Block a user