APM:Libraries
I2CDevice.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #pragma once
18 
19 #include <inttypes.h>
20 
21 #include <AP_HAL/HAL.h>
22 #include <AP_HAL/I2CDevice.h>
23 #include <AP_HAL/utility/OwnPtr.h>
24 #include "Semaphores.h"
25 #include "I2CWrapper.h"
26 #include "Device.h"
27 
28 namespace VRBRAIN {
29 
30 class I2CDevice : public AP_HAL::I2CDevice {
31 public:
33  {
34  return static_cast<I2CDevice*>(dev);
35  }
36 
37  I2CDevice(uint8_t bus, uint8_t address);
38  ~I2CDevice();
39 
40  /* See AP_HAL::I2CDevice::set_address() */
41  void set_address(uint8_t address) override { _address = address; }
42 
43  /* See AP_HAL::I2CDevice::set_retries() */
44  void set_retries(uint8_t retries) override { _vrbraindev.set_retries(retries); }
45 
46  /* See AP_HAL::Device::set_speed(): Empty implementation, not supported. */
47  bool set_speed(enum Device::Speed speed) override { return true; }
48 
49  /* See AP_HAL::Device::transfer() */
50  bool transfer(const uint8_t *send, uint32_t send_len,
51  uint8_t *recv, uint32_t recv_len) override;
52 
53  bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
54  uint32_t recv_len, uint8_t times) override;
55 
56  /* See AP_HAL::Device::register_periodic_callback() */
58  uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
59 
60  /* See AP_HAL::Device::adjust_periodic_callback() */
61  bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
62 
64  // if asking for invalid bus number use bus 0 semaphore
66  }
67 
68  void set_split_transfers(bool set) override {
69  _split_transfers = set;
70  }
71 
72 private:
73  static const uint8_t num_buses = 3;
75 
76  uint8_t _busnum;
78  uint8_t _address;
79  perf_counter_t perf;
80  char *pname;
82 };
83 
85 public:
86  friend class I2CDevice;
87 
89  {
90  return static_cast<I2CDeviceManager*>(i2c_mgr);
91  }
92 
93  AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
94  uint32_t bus_clock=400000,
95  bool use_smbus = false,
96  uint32_t timeout_ms=4) override;
97 };
98 
99 }
static const uint8_t num_buses
Definition: I2CDevice.h:73
void set_retries(uint8_t retries) override
Definition: I2CDevice.h:44
static DeviceBus businfo[num_buses]
Definition: I2CDevice.h:74
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
void set_retries(uint8_t retries)
Definition: I2CWrapper.h:21
static I2CDeviceManager * from(AP_HAL::I2CDeviceManager *i2c_mgr)
Definition: I2CDevice.h:88
bool set_speed(enum Device::Speed speed) override
Definition: I2CDevice.h:47
perf_counter_t perf
Definition: I2CDevice.h:79
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: I2CDevice.cpp:171
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: I2CDevice.cpp:139
void * PeriodicHandle
Definition: Device.h:42
Semaphore semaphore
Definition: Device.h:30
static I2CDevice * from(AP_HAL::I2CDevice *dev)
Definition: I2CDevice.h:32
uint8_t _address
Definition: I2CDevice.h:78
VRBRAIN_I2C _vrbraindev
Definition: I2CDevice.h:77
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: I2CDevice.cpp:158
AP_HAL::Semaphore * get_semaphore() override
Definition: I2CDevice.h:63
void set_address(uint8_t address) override
Definition: I2CDevice.h:41
void set_split_transfers(bool set) override
Definition: I2CDevice.h:68
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times) override
Definition: I2CDevice.cpp:148