I2CDevice.h 4.1 KB

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