mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 15:08:28 -04:00
61ef653181
The way this code is structured is a little bit different from the SPIDriver implementation: - We only open the bus once, no matter how many devices we have in it - There's a single transfer() method which uses half-duplex mode instead of full duplex. The reason is that for all cases in the codebase we are using half-duplex transfers using the full-duplex API, i.e. a single SPI msg with both tx and rx buffers. This is cumbersome because the buffers need to be of the same size and the receive buffer using an offset of the same length as the actux data being written. This means the high level APIs need to copy buffers around. If later we have uses for a real full duplex case it's just a matter of adding another transfer_fullduplex() method or something like this. - The methods are implemented in the SPIDevice class instead of having proxy methods to SPIDeviceManager as is the case of SPIDriver Also from now on we refer to the SPIDriver objects as "descriptors" because they have the parameters of each device in the SPIDeviceManager::devices[] table. When SPIDeviceDriver is completely replaced we can rename them to SPIDeviceProperties.
75 lines
2.0 KiB
C++
75 lines
2.0 KiB
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
/*
|
|
* Copyright (C) 2015 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
|
|
|
|
#include <inttypes.h>
|
|
|
|
#include <AP_HAL/HAL.h>
|
|
#include <AP_HAL/SPIDevice.h>
|
|
|
|
#include "SPIDriver.h"
|
|
|
|
namespace Linux {
|
|
|
|
class SPIBus;
|
|
|
|
class SPIDevice : public AP_HAL::SPIDevice {
|
|
public:
|
|
SPIDevice(SPIBus &bus, SPIDeviceDriver &device_desc);
|
|
|
|
virtual ~SPIDevice();
|
|
|
|
/* AP_HAL::SPIDevice implementation */
|
|
|
|
/* See AP_HAL::Device::set_speed() */
|
|
bool set_speed(AP_HAL::Device::Speed speed) override;
|
|
|
|
/* See AP_HAL::Device::transfer() */
|
|
bool transfer(const uint8_t *send, uint32_t send_len,
|
|
uint8_t *recv, uint32_t recv_len) override;
|
|
|
|
/* See AP_HAL::Device::get_semaphore() */
|
|
AP_HAL::Semaphore *get_semaphore() override;
|
|
|
|
/* See AP_HAL::Device::register_periodic_callback() */
|
|
AP_HAL::Device::PeriodicHandle *register_periodic_callback(
|
|
uint32_t period_usec, AP_HAL::MemberProc) override
|
|
{
|
|
return nullptr;
|
|
}
|
|
|
|
/* See AP_HAL::Device::get_fd() */
|
|
int get_fd() override;
|
|
|
|
protected:
|
|
SPIBus &_bus;
|
|
SPIDeviceDriver &_desc;
|
|
|
|
/*
|
|
* Select device if using userspace CS
|
|
*/
|
|
void _cs_assert();
|
|
|
|
/*
|
|
* Deselect device if using userspace CS
|
|
*/
|
|
void _cs_release();
|
|
};
|
|
|
|
}
|