2015-12-07 13:03:18 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*
|
|
|
|
* Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
|
|
|
|
*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2015-12-07 13:03:18 -04:00
|
|
|
#include <inttypes.h>
|
2012-08-20 15:37:46 -03:00
|
|
|
|
|
|
|
#include "AP_HAL_Namespace.h"
|
2015-12-07 13:03:18 -04:00
|
|
|
#include "SPIDevice.h"
|
|
|
|
#include "utility/OwnPtr.h"
|
2012-08-20 15:37:46 -03:00
|
|
|
|
2015-12-07 13:03:18 -04:00
|
|
|
namespace AP_HAL {
|
2012-11-28 21:57:20 -04:00
|
|
|
|
2015-12-07 13:03:18 -04:00
|
|
|
class SPIDeviceManager {
|
2012-11-28 21:57:20 -04:00
|
|
|
public:
|
2015-12-02 11:37:22 -04:00
|
|
|
virtual void init() = 0;
|
2015-12-07 13:03:18 -04:00
|
|
|
virtual SPIDeviceDriver* device(enum SPIDeviceType, uint8_t index = 0) = 0;
|
|
|
|
virtual OwnPtr<SPIDevice> get_device(const char *name)
|
|
|
|
{
|
|
|
|
return nullptr;
|
|
|
|
}
|
2012-11-28 21:57:20 -04:00
|
|
|
};
|
|
|
|
|
2012-08-30 20:25:35 -03:00
|
|
|
/**
|
2012-11-28 21:57:20 -04:00
|
|
|
* We still need an abstraction for performing bulk
|
2012-08-30 20:25:35 -03:00
|
|
|
* transfers to be portable to other platforms.
|
|
|
|
*/
|
|
|
|
|
2015-12-07 13:03:18 -04:00
|
|
|
class SPIDeviceDriver {
|
2012-08-20 15:37:46 -03:00
|
|
|
public:
|
2012-11-28 21:57:20 -04:00
|
|
|
virtual void init() = 0;
|
2015-12-07 13:03:18 -04:00
|
|
|
virtual Semaphore* get_semaphore() = 0;
|
2015-08-19 12:31:27 -03:00
|
|
|
virtual bool transaction(const uint8_t *tx, uint8_t *rx, uint16_t len) = 0;
|
2012-12-17 21:06:51 -04:00
|
|
|
|
2012-11-28 21:57:20 -04:00
|
|
|
virtual void cs_assert() = 0;
|
|
|
|
virtual void cs_release() = 0;
|
2012-08-30 20:25:35 -03:00
|
|
|
virtual uint8_t transfer (uint8_t data) = 0;
|
2013-01-12 07:10:00 -04:00
|
|
|
virtual void transfer (const uint8_t *data, uint16_t len) = 0;
|
2013-10-11 04:00:23 -03:00
|
|
|
|
|
|
|
/**
|
|
|
|
optional set_bus_speed() interface. This can be used by drivers
|
|
|
|
to request higher speed for sensor registers once the sensor is
|
|
|
|
initialised. This is used by the MPU6000 driver which can
|
|
|
|
handle 20MHz for sensor register reads, but only 1MHz for other
|
|
|
|
registers.
|
|
|
|
*/
|
|
|
|
enum bus_speed {
|
|
|
|
SPI_SPEED_LOW, SPI_SPEED_HIGH
|
|
|
|
};
|
|
|
|
|
|
|
|
virtual void set_bus_speed(enum bus_speed speed) {}
|
2012-08-20 15:37:46 -03:00
|
|
|
};
|
|
|
|
|
2015-12-07 13:03:18 -04:00
|
|
|
}
|