Browse Source

ArduCopter: only attempt to change settings of optical flow sensor if it has been successfully initialised

master
rmackay9 12 years ago
parent
commit
52177c63f7
  1. 19
      ArduCopter/sensors.pde

19
ArduCopter/sensors.pde

@ -54,17 +54,18 @@ static void init_optflow() @@ -54,17 +54,18 @@ static void init_optflow()
if( optflow.init(false, &timer_scheduler, &spi_semaphore, &spi3_semaphore) == false ) {
g.optflow_enabled = false;
cliSerial->print_P(PSTR("\nFailed to Init OptFlow "));
}
// suspend timer while we set-up SPI communication
timer_scheduler.suspend_timer();
}else{
// suspend timer while we set-up SPI communication
timer_scheduler.suspend_timer();
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_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
// resume timer
timer_scheduler.resume_timer();
// resume timer
timer_scheduler.resume_timer();
}
#endif // OPTFLOW == ENABLED
}

Loading…
Cancel
Save