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 #include <vector>
21 
22 #include <AP_HAL/HAL.h>
23 #include <AP_HAL/I2CDevice.h>
24 #include <AP_HAL/utility/OwnPtr.h>
25 
26 #include "Semaphores.h"
27 
28 namespace Linux {
29 
30 class I2CBus;
31 
32 class I2CDevice : public AP_HAL::I2CDevice {
33 public:
35  {
36  return static_cast<I2CDevice*>(dev);
37  }
38 
39  /* AP_HAL::I2CDevice implementation */
40 
41  I2CDevice(I2CBus &bus, uint8_t address);
42 
43  ~I2CDevice();
44 
45  /* See AP_HAL::I2CDevice::set_address() */
46  void set_address(uint8_t address) override { _address = address; }
47 
48  /* See AP_HAL::I2CDevice::set_retries() */
49  void set_retries(uint8_t retries) override { _retries = retries; }
50 
51  /* AP_HAL::Device implementation */
52 
53  /* See AP_HAL::Device::set_speed(): Empty implementation, not supported. */
54  bool set_speed(enum Device::Speed speed) override { return true; }
55 
56  /* See AP_HAL::Device::transfer() */
57  bool transfer(const uint8_t *send, uint32_t send_len,
58  uint8_t *recv, uint32_t recv_len) override;
59 
60  bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
61  uint32_t recv_len, uint8_t times) override;
62 
63  /* See AP_HAL::Device::get_semaphore() */
64  AP_HAL::Semaphore *get_semaphore() override;
65 
66  /* See AP_HAL::Device::register_periodic_callback() */
68  uint32_t period_usec, AP_HAL::Device::PeriodicCb) override;
69 
70  /* See AP_HAL::Device::adjust_periodic_callback() */
72  AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override;
73 
74  /* set split transfers flag */
75  void set_split_transfers(bool set) override {
76  _split_transfers = set;
77  }
78 
79 protected:
81  uint8_t _address;
82  uint8_t _retries = 0;
83  bool _split_transfers = false;
84 };
85 
87 public:
88  friend class I2CDevice;
89 
91  {
92  return static_cast<I2CDeviceManager*>(i2c_mgr);
93  }
94 
96 
98  std::vector<const char *> devpaths, uint8_t address) override;
99 
100  /* AP_HAL::I2CDeviceManager implementation */
101  AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
102  uint32_t bus_clock=400000,
103  bool use_smbus = false,
104  uint32_t timeout_ms=4) override;
105 
106  /*
107  * Stop all I2C threads and block until they are finalized. This doesn't
108  * free memory because they can still be used by devices, however device
109  * drivers won't receive any new event
110  */
111  void teardown();
112 
113 protected:
114  void _unregister(I2CBus &b);
115  AP_HAL::OwnPtr<AP_HAL::I2CDevice> _create_device(I2CBus &b, uint8_t address) const;
116 
117  std::vector<I2CBus*> _buses;
118 };
119 
120 }
std::vector< I2CBus * > _buses
Definition: I2CDevice.h:117
bool _split_transfers
Definition: I2CDevice.h:83
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
AP_HAL::Semaphore * get_semaphore() override
Definition: I2CDevice.cpp:248
void set_retries(uint8_t retries) override
Definition: I2CDevice.h:49
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: I2CDevice.cpp:273
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
I2CBus & _bus
Definition: I2CDevice.h:80
void * PeriodicHandle
Definition: Device.h:42
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: I2CDevice.cpp:253
static I2CDeviceManager * from(AP_HAL::I2CDeviceManager *i2c_mgr)
Definition: I2CDevice.h:90
static I2CDevice * from(AP_HAL::I2CDevice *dev)
Definition: I2CDevice.h:34
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times) override
Definition: I2CDevice.cpp:202
uint8_t _retries
Definition: I2CDevice.h:82
void set_address(uint8_t address) override
Definition: I2CDevice.h:46
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: I2CDevice.cpp:154
void set_split_transfers(bool set) override
Definition: I2CDevice.h:75
uint8_t _address
Definition: I2CDevice.h:81
bool set_speed(enum Device::Speed speed) override
Definition: I2CDevice.h:54