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 
25 namespace Empty {
26 
27 class I2CDevice : public AP_HAL::I2CDevice {
28 public:
30  {
31  }
32 
33  virtual ~I2CDevice() { }
34 
35  /* AP_HAL::I2CDevice implementation */
36 
37  /* See AP_HAL::I2CDevice::set_address() */
38  void set_address(uint8_t address) override { }
39 
40  /* See AP_HAL::I2CDevice::set_retries() */
41  void set_retries(uint8_t retries) override { }
42 
43 
44  /* AP_HAL::Device implementation */
45 
46  /* See AP_HAL::Device::transfer() */
47  bool transfer(const uint8_t *send, uint32_t send_len,
48  uint8_t *recv, uint32_t recv_len) override
49  {
50  return true;
51  }
52 
53  bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
54  uint32_t recv_len, uint8_t times)
55  {
56  return true;
57  }
58 
59 
60  /* See AP_HAL::Device::set_speed() */
61  bool set_speed(enum AP_HAL::Device::Speed speed) override { return true; }
62 
63  /* See AP_HAL::Device::get_semaphore() */
64  AP_HAL::Semaphore *get_semaphore() { return nullptr; }
65 
66  /* See AP_HAL::Device::register_periodic_callback() */
68  uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
69  {
70  return nullptr;
71  }
72 
73  /* See Device::adjust_periodic_callback() */
75  AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
76  {
77  return true;
78  }
79 };
80 
82 public:
84 
85  /* AP_HAL::I2CDeviceManager implementation */
86  AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus, uint8_t address,
87  uint32_t bus_clock=400000,
88  bool use_smbus = false,
89  uint32_t timeout_ms=4) override
90  {
91  return nullptr;
92  }
93 };
94 
95 }
bool set_speed(enum AP_HAL::Device::Speed speed) override
Definition: I2CDevice.h:61
virtual ~I2CDevice()
Definition: I2CDevice.h:33
void set_retries(uint8_t retries) override
Definition: I2CDevice.h:41
void * PeriodicHandle
Definition: Device.h:42
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: I2CDevice.h:47
AP_HAL::Semaphore * get_semaphore()
Definition: I2CDevice.h:64
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times)
Definition: I2CDevice.h:53
virtual bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: I2CDevice.h:74
void set_address(uint8_t address) override
Definition: I2CDevice.h:38
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4) override
Definition: I2CDevice.h:86
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: I2CDevice.h:67