ArduCopter: added spi_semaphore to stop conflicts between dataflash and optical flow sensor on APM1

This commit is contained in:
rmackay9 2012-10-18 17:04:44 +09:00
parent 2428cc647c
commit 9392c8cae2
2 changed files with 6 additions and 5 deletions

View File

@ -171,11 +171,12 @@ APM_RC_APM1 APM_RC;
////////////////////////////////////////////////////////////////////////////////
// Dataflash
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
AP_Semaphore spi_semaphore;
AP_Semaphore spi3_semaphore;
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
DataFlash_APM2 DataFlash(&spi3_semaphore);
#else
DataFlash_APM1 DataFlash;
DataFlash_APM1 DataFlash(&spi_semaphore);
#endif
@ -227,9 +228,9 @@ AP_Compass_HMC5843 compass;
#ifdef OPTFLOW_ENABLED
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
AP_OpticalFlow_ADNS3080 optflow(&spi3_semaphore,OPTFLOW_CS_PIN);
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
#else
AP_OpticalFlow_ADNS3080 optflow(NULL,OPTFLOW_CS_PIN);
AP_OpticalFlow_ADNS3080 optflow(OPTFLOW_CS_PIN);
#endif
#else
AP_OpticalFlow optflow;

View File

@ -51,7 +51,7 @@ static void init_compass()
static void init_optflow()
{
#ifdef OPTFLOW_ENABLED
if( optflow.init(false, &timer_scheduler) == false ) {
if( optflow.init(false, &timer_scheduler, &spi_semaphore, &spi3_semaphore) == false ) {
g.optflow_enabled = false;
SendDebug("\nFailed to Init OptFlow ");
}