Browse Source

Copter: remove optical flow init failure message

the sensor only becomes healthy once it has received data which will
take a few seconds after initialisation meaning this failure message
will always be displayed even when the sensor is fine.
master
Randy Mackay 10 years ago
parent
commit
6e623bce28
  1. 6
      ArduCopter/sensors.pde

6
ArduCopter/sensors.pde

@ -86,12 +86,8 @@ static void init_optflow() @@ -86,12 +86,8 @@ static void init_optflow()
return;
}
// initialise sensor and display error on failure
// initialise optical flow sensor
optflow.init();
if (!optflow.healthy()) {
cliSerial->print_P(PSTR("Failed to Init OptFlow\n"));
Log_Write_Error(ERROR_SUBSYSTEM_OPTFLOW,ERROR_CODE_FAILED_TO_INITIALISE);
}
#endif // OPTFLOW == ENABLED
}

Loading…
Cancel
Save