2018-02-03 09:46:18 -04:00
|
|
|
#pragma once
|
|
|
|
|
2016-08-04 14:18:12 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
|
|
|
|
|
|
#include <arch/board/board.h>
|
|
|
|
#include "board_config.h"
|
|
|
|
#include <drivers/device/i2c.h>
|
|
|
|
#include "AP_HAL_VRBRAIN.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
/*
|
|
|
|
wrapper class for I2C to expose protected functions from PX4Firmware
|
|
|
|
*/
|
|
|
|
class VRBRAIN::VRBRAIN_I2C : public device::I2C {
|
|
|
|
public:
|
2018-02-03 09:46:18 -04:00
|
|
|
VRBRAIN_I2C(uint8_t bus);
|
|
|
|
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers);
|
|
|
|
|
|
|
|
void set_retries(uint8_t retries) {
|
|
|
|
_retries = retries;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t map_bus_number(uint8_t bus) const;
|
2016-08-04 14:18:12 -03:00
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
// setup instance_lock
|
|
|
|
static void init_lock(void) {
|
|
|
|
pthread_mutex_init(&instance_lock, nullptr);
|
|
|
|
}
|
|
|
|
|
2016-08-04 14:18:12 -03:00
|
|
|
private:
|
|
|
|
static uint8_t instance;
|
2018-02-03 09:46:18 -04:00
|
|
|
static pthread_mutex_t instance_lock;
|
2016-08-04 14:18:12 -03:00
|
|
|
bool init_done;
|
|
|
|
bool init_ok;
|
|
|
|
char devname[10];
|
|
|
|
char devpath[14];
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
#endif // CONFIG_HAL_BOARD
|