mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_OpticalFlow_ADNS3080: has private AP_Semaphore* _semaphore
Semaphore can be null, handled correctly if it is. Rather than check for which SPI bus the sensor is using, just check whether semaphore is not null before using it. More general and flexible.
This commit is contained in:
parent
6fc0d22671
commit
26ba391cd4
@ -41,7 +41,8 @@ union NumericIntType
|
||||
};
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_OpticalFlow_ADNS3080::AP_OpticalFlow_ADNS3080(int16_t cs_pin, int16_t reset_pin) :
|
||||
AP_OpticalFlow_ADNS3080::AP_OpticalFlow_ADNS3080(AP_Semaphore* semaphore, int16_t cs_pin, int16_t reset_pin) :
|
||||
_semaphore(semaphore),
|
||||
_cs_pin(cs_pin),
|
||||
_reset_pin(reset_pin),
|
||||
_spi_bus(ADNS3080_SPI_UNKNOWN)
|
||||
@ -181,10 +182,10 @@ AP_OpticalFlow_ADNS3080::read_register(byte address)
|
||||
uint8_t result = 0;
|
||||
uint8_t junk = 0;
|
||||
|
||||
// get spi3 semaphore if required
|
||||
if( _spi_bus == ADNS3080_SPIBUS_3 ) {
|
||||
// get spi semaphore if required
|
||||
if( _semaphore != NULL) {
|
||||
// if failed to get semaphore then just quietly fail
|
||||
if( !AP_Semaphore_spi3.get(this) ) {
|
||||
if( !_semaphore->get(this) ) {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
@ -209,9 +210,9 @@ AP_OpticalFlow_ADNS3080::read_register(byte address)
|
||||
|
||||
restore_spi_settings();
|
||||
|
||||
// get spi3 semaphore if required
|
||||
if( _spi_bus == ADNS3080_SPIBUS_3 ) {
|
||||
AP_Semaphore_spi3.release(this);
|
||||
// get spi semaphore if required
|
||||
if( _semaphore != NULL) {
|
||||
_semaphore->release(this);
|
||||
}
|
||||
|
||||
return result;
|
||||
@ -223,10 +224,10 @@ AP_OpticalFlow_ADNS3080::write_register(byte address, byte value)
|
||||
{
|
||||
byte junk = 0;
|
||||
|
||||
// get spi3 semaphore if required
|
||||
if( _spi_bus == ADNS3080_SPIBUS_3 ) {
|
||||
// get spi semaphore if required
|
||||
if( _semaphore != NULL) {
|
||||
// if failed to get semaphore then just quietly fail
|
||||
if( !AP_Semaphore_spi3.get(this) ) {
|
||||
if( !_semaphore->get(this) ) {
|
||||
Serial.println("Optflow: failed to get spi3 semaphore!");
|
||||
return;
|
||||
}
|
||||
@ -253,8 +254,8 @@ AP_OpticalFlow_ADNS3080::write_register(byte address, byte value)
|
||||
restore_spi_settings();
|
||||
|
||||
// get spi3 semaphore if required
|
||||
if( _spi_bus == ADNS3080_SPIBUS_3 ) {
|
||||
AP_Semaphore_spi3.release(this);
|
||||
if( _semaphore != NULL) {
|
||||
_semaphore->release(this);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1,6 +1,7 @@
|
||||
#ifndef AP_OPTICALFLOW_ADNS3080_H
|
||||
#define AP_OPTICALFLOW_ADNS3080_H
|
||||
#ifndef __AP_OPTICALFLOW_ADNS3080_H__
|
||||
#define __AP_OPTICALFLOW_ADNS3080_H__
|
||||
|
||||
#include <AP_Semaphore.h>
|
||||
#include "AP_OpticalFlow.h"
|
||||
|
||||
// default pin settings
|
||||
@ -82,7 +83,7 @@
|
||||
class AP_OpticalFlow_ADNS3080 : public AP_OpticalFlow
|
||||
{
|
||||
public:
|
||||
AP_OpticalFlow_ADNS3080(int16_t cs_pin = ADNS3080_CHIP_SELECT, int16_t reset_pin = ADNS3080_RESET);
|
||||
AP_OpticalFlow_ADNS3080(AP_Semaphore* semaphore, int16_t cs_pin = ADNS3080_CHIP_SELECT, int16_t reset_pin = ADNS3080_RESET);
|
||||
bool init(bool initCommAPI, AP_PeriodicProcess *scheduler); // parameter controls whether I2C/SPI interface is initialised (set to false if other devices are on the I2C/SPI bus and have already initialised the interface)
|
||||
uint8_t read_register(uint8_t address);
|
||||
void write_register(uint8_t address, uint8_t value);
|
||||
@ -138,6 +139,7 @@ private:
|
||||
bool _motion; // true if there has been motion
|
||||
bool _overflow; // true if the x or y data buffers overflowed
|
||||
uint8_t _spi_bus; // 0 = unknown, 1 = using SPI, 3 = using SPI3
|
||||
AP_Semaphore* _semaphore;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user