mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: removed vector based I2C get_device
this is unused and prevents building on QURT
This commit is contained in:
parent
dbba4559ee
commit
b34d0c9c87
|
@ -21,6 +21,8 @@
|
||||||
#include "AP_HAL_Namespace.h"
|
#include "AP_HAL_Namespace.h"
|
||||||
#include "utility/functor.h"
|
#include "utility/functor.h"
|
||||||
|
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* This is an interface abstracting I2C and SPI devices
|
* This is an interface abstracting I2C and SPI devices
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -17,7 +17,6 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <vector>
|
|
||||||
|
|
||||||
#include "AP_HAL_Namespace.h"
|
#include "AP_HAL_Namespace.h"
|
||||||
#include "Device.h"
|
#include "Device.h"
|
||||||
|
@ -76,20 +75,6 @@ public:
|
||||||
uint32_t bus_clock=400000,
|
uint32_t bus_clock=400000,
|
||||||
bool use_smbus = false,
|
bool use_smbus = false,
|
||||||
uint32_t timeout_ms=4) = 0;
|
uint32_t timeout_ms=4) = 0;
|
||||||
/*
|
|
||||||
* Get device by looking up the I2C bus on the buses from @devpaths.
|
|
||||||
*
|
|
||||||
* Each string in @devpaths are possible locations for the bus. How the
|
|
||||||
* strings are implemented are HAL-specific. On Linux this is the info
|
|
||||||
* returned by 'udevadm info -q path /dev/i2c-X'. The first I2C bus
|
|
||||||
* matching a prefix in @devpaths is used to create a I2CDevice object.
|
|
||||||
*/
|
|
||||||
virtual OwnPtr<I2CDevice> get_device(std::vector<const char *> devpaths,
|
|
||||||
uint8_t address) {
|
|
||||||
// Not implemented
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
get mask of bus numbers for all configured I2C buses
|
get mask of bus numbers for all configured I2C buses
|
||||||
*/
|
*/
|
||||||
|
|
Loading…
Reference in New Issue