mirror of https://github.com/ArduPilot/ardupilot
DataFlash: modified to use AP_Semaphore for SPI3 bus when required.
Also fixed test sketch which seemed broken.
This commit is contained in:
parent
9ef95d59ba
commit
d754804135
|
@ -37,8 +37,7 @@ extern "C" {
|
|||
#include <inttypes.h>
|
||||
#include <avr/interrupt.h>
|
||||
}
|
||||
//#include <FastSerial.h>
|
||||
//#include <AP_Common.h>
|
||||
#include <FastSerial.h>
|
||||
|
||||
#if defined(ARDUINO) && ARDUINO >= 100
|
||||
#include "Arduino.h"
|
||||
|
@ -46,6 +45,7 @@ extern "C" {
|
|||
#include "WConstants.h"
|
||||
#endif
|
||||
|
||||
#include <AP_Semaphore.h> // for removing conflict with optical flow sensor on SPI3 bus
|
||||
#include "DataFlash_APM2.h"
|
||||
/*
|
||||
* #define ENABLE_FASTSERIAL_DEBUG
|
||||
|
@ -93,6 +93,13 @@ extern "C" {
|
|||
// *** INTERNAL FUNCTIONS ***
|
||||
unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
||||
{
|
||||
unsigned char retval;
|
||||
|
||||
// get spi3 semaphore if required. if failed to get semaphore then just quietly fail
|
||||
if( !AP_Semaphore_spi3.get(this) ) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Wait for empty transmit buffer */
|
||||
while ( !( UCSR3A & (1<<UDRE3)) ) ;
|
||||
/* Put data into buffer, sends the data */
|
||||
|
@ -100,7 +107,12 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
|||
/* Wait for data to be received */
|
||||
while ( !(UCSR3A & (1<<RXC3)) ) ;
|
||||
/* Get and return received data from buffer */
|
||||
return UDR3;
|
||||
retval = UDR3;
|
||||
|
||||
// release spi3 semaphore
|
||||
AP_Semaphore_spi3.release(this);
|
||||
|
||||
return retval;
|
||||
}
|
||||
|
||||
// disable device
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#ifndef __DATAFLASH_APM2_H__
|
||||
#define __DATAFLASH_APM2_H__
|
||||
|
||||
#include <AP_Semaphore.h> // for removing conflict with dataflash on SPI3 bus
|
||||
#include "DataFlash.h"
|
||||
|
||||
class DataFlash_APM2 : public DataFlash_Class
|
||||
|
|
|
@ -4,9 +4,23 @@
|
|||
*/
|
||||
|
||||
// Libraries
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <SPI.h> // Arduino SPI lib
|
||||
#include <AP_Semaphore.h> // for removing conflict with dataflash on SPI3 bus
|
||||
#include <DataFlash.h>
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Serial ports
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
// Note that FastSerial port buffers are allocated at ::begin time,
|
||||
// so there is not much of a penalty to defining ports that we don't
|
||||
// use.
|
||||
//
|
||||
FastSerialPort0(Serial); // FTDI/console
|
||||
|
||||
#define HEAD_BYTE1 0xA3
|
||||
#define HEAD_BYTE2 0x95
|
||||
|
||||
|
|
Loading…
Reference in New Issue