APM:Libraries
I2CWrapper.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
6 
7 #include <arch/board/board.h>
8 #include "board_config.h"
9 #include <drivers/device/i2c.h>
10 #include "AP_HAL_VRBRAIN.h"
11 
12 extern const AP_HAL::HAL& hal;
13 /*
14  wrapper class for I2C to expose protected functions from PX4Firmware
15  */
16 class VRBRAIN::VRBRAIN_I2C : public device::I2C {
17 public:
18  VRBRAIN_I2C(uint8_t bus);
19  bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers);
20 
21  void set_retries(uint8_t retries) {
22  _retries = retries;
23  }
24 
25  uint8_t map_bus_number(uint8_t bus) const;
26 
27  // setup instance_lock
28  static void init_lock(void) {
29  pthread_mutex_init(&instance_lock, nullptr);
30  }
31 
32 private:
33  static uint8_t instance;
34  static pthread_mutex_t instance_lock;
35  bool init_done;
36  bool init_ok;
37  char devname[10];
38  char devpath[14];
39 };
40 
41 
42 #endif // CONFIG_HAL_BOARD
static pthread_mutex_t instance_lock
Definition: I2CWrapper.h:34
void set_retries(uint8_t retries)
Definition: I2CWrapper.h:21
static uint8_t instance
Definition: I2CWrapper.h:33
static void init_lock(void)
Definition: I2CWrapper.h:28
uint8_t map_bus_number(uint8_t bus) const
Definition: I2CDevice.cpp:39
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers)
Definition: I2CDevice.cpp:72
VRBRAIN_I2C(uint8_t bus)
Definition: I2CDevice.cpp:32
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14