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_Namespace.h"
23 #include "Device.h"
24 #include "utility/OwnPtr.h"
25 
26 namespace AP_HAL {
27 
28 class I2CDevice : public Device {
29 public:
31 
32  virtual ~I2CDevice() { }
33 
34  /* Device implementation */
35 
36  /* See Device::set_speed() */
37  virtual bool set_speed(Device::Speed speed) override = 0;
38 
39  /* See Device::transfer() */
40  virtual bool transfer(const uint8_t *send, uint32_t send_len,
41  uint8_t *recv, uint32_t recv_len) override = 0;
42 
43  /*
44  * Read location from device multiple times, advancing the buffer each
45  * time
46  */
47  virtual bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
48  uint32_t recv_len, uint8_t times) = 0;
49 
50  /* See Device::get_semaphore() */
51  virtual Semaphore *get_semaphore() override = 0;
52 
53  /* See Device::register_periodic_callback() */
55  uint32_t period_usec, Device::PeriodicCb) override = 0;
56 
57  /* See Device::adjust_periodic_callback() */
58  virtual bool adjust_periodic_callback(
59  Device::PeriodicHandle h, uint32_t period_usec) override = 0;
60 
61  /*
62  * Force I2C transfers to be split between send and receive parts, with a
63  * stop condition between them. Setting this allows to conveniently
64  * continue using the read_* and transfer() methods on those devices.
65  *
66  * Some platforms may have transfers always split, in which case
67  * this method is not needed.
68  */
69  virtual void set_split_transfers(bool set) {};
70 };
71 
73 public:
74  /* Get a device handle */
75  virtual OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
76  uint32_t bus_clock=400000,
77  bool use_smbus = false,
78  uint32_t timeout_ms=4) = 0;
79  /*
80  * Get device by looking up the I2C bus on the buses from @devpaths.
81  *
82  * Each string in @devpaths are possible locations for the bus. How the
83  * strings are implemented are HAL-specific. On Linux this is the info
84  * returned by 'udevadm info -q path /dev/i2c-X'. The first I2C bus
85  * matching a prefix in @devpaths is used to create a I2CDevice object.
86  */
87  virtual OwnPtr<I2CDevice> get_device(std::vector<const char *> devpaths,
88  uint8_t address) {
89  // Not implemented
90  return nullptr;
91  }
92 };
93 
94 }
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
virtual Semaphore * get_semaphore() override=0
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
virtual ~I2CDevice()
Definition: I2CDevice.h:32
virtual bool adjust_periodic_callback(Device::PeriodicHandle h, uint32_t period_usec) override=0
virtual void set_split_transfers(bool set)
Definition: I2CDevice.h:69
void * PeriodicHandle
Definition: Device.h:42
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
virtual OwnPtr< I2CDevice > get_device(std::vector< const char *> devpaths, uint8_t address)
Definition: I2CDevice.h:87
virtual bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times)=0
virtual bool set_speed(Device::Speed speed) override=0