AP_InertialSensor_L3G4200D.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. This is an INS driver for the combination L3G4200D gyro and ADXL345 accelerometer.
  15. This combination is available as a cheap 10DOF sensor on ebay
  16. This sensor driver is an example only - it should not be used in any
  17. serious autopilot as the latencies on I2C prevent good timing at
  18. high sample rates. It is useful when doing an initial port of
  19. ardupilot to a board where only I2C is available, and a cheap sensor
  20. can be used.
  21. Datasheets:
  22. ADXL345 Accelerometer http://www.analog.com/static/imported-files/data_sheets/ADXL345.pdf
  23. L3G4200D gyro http://www.st.com/st-web-ui/static/active/en/resource/technical/document/datasheet/CD00265057.pdf
  24. */
  25. #include <AP_HAL/AP_HAL.h>
  26. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  27. #include "AP_InertialSensor_L3G4200D.h"
  28. #include <inttypes.h>
  29. #include <utility>
  30. const extern AP_HAL::HAL &hal;
  31. ///////
  32. /// Accelerometer ADXL345 register definitions
  33. #define ADXL345_ACCELEROMETER_ADDRESS 0x53
  34. #define ADXL345_ACCELEROMETER_XL345_DEVID 0xe5
  35. #define ADXL345_ACCELEROMETER_ADXLREG_BW_RATE 0x2c
  36. #define ADXL345_ACCELEROMETER_ADXLREG_POWER_CTL 0x2d
  37. #define ADXL345_ACCELEROMETER_ADXLREG_DATA_FORMAT 0x31
  38. #define ADXL345_ACCELEROMETER_ADXLREG_DEVID 0x00
  39. #define ADXL345_ACCELEROMETER_ADXLREG_DATAX0 0x32
  40. #define ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL 0x38
  41. #define ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL_STREAM 0x9F
  42. #define ADXL345_ACCELEROMETER_ADXLREG_FIFO_STATUS 0x39
  43. // ADXL345 accelerometer scaling
  44. // Result will be scaled to 1m/s/s
  45. // ADXL345 in Full resolution mode (any g scaling) is 256 counts/g, so scale by 9.81/256 = 0.038320312
  46. #define ADXL345_ACCELEROMETER_SCALE_M_S (GRAVITY_MSS / 256.0f)
  47. /// Gyro ITG3205 register definitions
  48. #define L3G4200D_I2C_ADDRESS 0x69
  49. #define L3G4200D_REG_WHO_AM_I 0x0f
  50. #define L3G4200D_REG_WHO_AM_I_VALUE 0xd3
  51. #define L3G4200D_REG_CTRL_REG1 0x20
  52. #define L3G4200D_REG_CTRL_REG1_DRBW_800_110 0xf0
  53. #define L3G4200D_REG_CTRL_REG1_PD 0x08
  54. #define L3G4200D_REG_CTRL_REG1_XYZ_ENABLE 0x07
  55. #define L3G4200D_REG_CTRL_REG4 0x23
  56. #define L3G4200D_REG_CTRL_REG4_FS_2000 0x30
  57. #define L3G4200D_REG_CTRL_REG5 0x24
  58. #define L3G4200D_REG_CTRL_REG5_FIFO_EN 0x40
  59. #define L3G4200D_REG_FIFO_CTL 0x2e
  60. #define L3G4200D_REG_FIFO_CTL_STREAM 0x40
  61. #define L3G4200D_REG_FIFO_SRC 0x2f
  62. #define L3G4200D_REG_FIFO_SRC_ENTRIES_MASK 0x1f
  63. #define L3G4200D_REG_FIFO_SRC_EMPTY 0x20
  64. #define L3G4200D_REG_FIFO_SRC_OVERRUN 0x40
  65. #define L3G4200D_REG_XL 0x28
  66. // this bit is ORd into the register to enable auto-increment mode
  67. #define L3G4200D_REG_AUTO_INCREMENT 0x80
  68. // L3G4200D Gyroscope scaling
  69. // running at 2000 DPS full range, 16 bit signed data, datasheet
  70. // specifies 70 mdps per bit
  71. #define L3G4200D_GYRO_SCALE_R_S (DEG_TO_RAD * 70.0f * 0.001f)
  72. // constructor
  73. AP_InertialSensor_L3G4200D::AP_InertialSensor_L3G4200D(AP_InertialSensor &imu,
  74. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  75. : AP_InertialSensor_Backend(imu)
  76. , _dev(std::move(dev))
  77. {
  78. }
  79. AP_InertialSensor_L3G4200D::~AP_InertialSensor_L3G4200D()
  80. {
  81. }
  82. /*
  83. detect the sensor
  84. */
  85. AP_InertialSensor_Backend *AP_InertialSensor_L3G4200D::probe(AP_InertialSensor &imu,
  86. AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  87. {
  88. if (!dev) {
  89. return nullptr;
  90. }
  91. AP_InertialSensor_L3G4200D *sensor
  92. = new AP_InertialSensor_L3G4200D(imu, std::move(dev));
  93. if (!sensor || !sensor->_init_sensor()) {
  94. delete sensor;
  95. return nullptr;
  96. }
  97. return sensor;
  98. }
  99. bool AP_InertialSensor_L3G4200D::_init_sensor(void)
  100. {
  101. if (!_dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  102. return false;
  103. }
  104. // Init the accelerometer
  105. uint8_t data = 0;
  106. _dev->read_registers(ADXL345_ACCELEROMETER_ADXLREG_DEVID, &data, 1);
  107. if (data != ADXL345_ACCELEROMETER_XL345_DEVID) {
  108. AP_HAL::panic("AP_InertialSensor_L3G4200D: could not find ADXL345 accelerometer sensor");
  109. }
  110. _dev->write_register(ADXL345_ACCELEROMETER_ADXLREG_POWER_CTL, 0x00);
  111. hal.scheduler->delay(5);
  112. _dev->write_register(ADXL345_ACCELEROMETER_ADXLREG_POWER_CTL, 0xff);
  113. hal.scheduler->delay(5);
  114. // Measure mode:
  115. _dev->write_register(ADXL345_ACCELEROMETER_ADXLREG_POWER_CTL, 0x08);
  116. hal.scheduler->delay(5);
  117. // Full resolution, 8g:
  118. // Caution, this must agree with ADXL345_ACCELEROMETER_SCALE_1G
  119. // In full resoution mode, the scale factor need not change
  120. _dev->write_register(ADXL345_ACCELEROMETER_ADXLREG_DATA_FORMAT, 0x08);
  121. hal.scheduler->delay(5);
  122. // Normal power, 800Hz Output Data Rate, 400Hz bandwidth:
  123. _dev->write_register(ADXL345_ACCELEROMETER_ADXLREG_BW_RATE, 0x0d);
  124. hal.scheduler->delay(5);
  125. // enable FIFO in stream mode. This will allow us to read the accelerometers
  126. // much less frequently
  127. _dev->write_register(ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL,
  128. ADXL345_ACCELEROMETER_ADXLREG_FIFO_CTL_STREAM);
  129. // Init the Gyro
  130. // Expect to read the right 'WHO_AM_I' value
  131. _dev->read_registers(L3G4200D_REG_WHO_AM_I, &data, 1);
  132. if (data != L3G4200D_REG_WHO_AM_I_VALUE) {
  133. AP_HAL::panic("AP_InertialSensor_L3G4200D: could not find L3G4200D gyro sensor");
  134. }
  135. // setup for 800Hz sampling with 110Hz filter
  136. _dev->write_register(L3G4200D_REG_CTRL_REG1,
  137. L3G4200D_REG_CTRL_REG1_DRBW_800_110 |
  138. L3G4200D_REG_CTRL_REG1_PD |
  139. L3G4200D_REG_CTRL_REG1_XYZ_ENABLE);
  140. hal.scheduler->delay(1);
  141. _dev->write_register(L3G4200D_REG_CTRL_REG1,
  142. L3G4200D_REG_CTRL_REG1_DRBW_800_110 |
  143. L3G4200D_REG_CTRL_REG1_PD |
  144. L3G4200D_REG_CTRL_REG1_XYZ_ENABLE);
  145. hal.scheduler->delay(1);
  146. _dev->write_register(L3G4200D_REG_CTRL_REG1,
  147. L3G4200D_REG_CTRL_REG1_DRBW_800_110 |
  148. L3G4200D_REG_CTRL_REG1_PD |
  149. L3G4200D_REG_CTRL_REG1_XYZ_ENABLE);
  150. hal.scheduler->delay(1);
  151. // setup for 2000 degrees/sec full range
  152. _dev->write_register(L3G4200D_REG_CTRL_REG4,
  153. L3G4200D_REG_CTRL_REG4_FS_2000);
  154. hal.scheduler->delay(1);
  155. // enable FIFO
  156. _dev->write_register(L3G4200D_REG_CTRL_REG5,
  157. L3G4200D_REG_CTRL_REG5_FIFO_EN);
  158. hal.scheduler->delay(1);
  159. // enable FIFO in stream mode. This will allow us to read the gyros much less frequently
  160. _dev->write_register(L3G4200D_REG_FIFO_CTL,
  161. L3G4200D_REG_FIFO_CTL_STREAM);
  162. hal.scheduler->delay(1);
  163. _dev->get_semaphore()->give();
  164. return true;
  165. }
  166. /*
  167. startup the sensor
  168. */
  169. void AP_InertialSensor_L3G4200D::start(void)
  170. {
  171. _gyro_instance = _imu.register_gyro(800, _dev->get_bus_id_devtype(DEVTYPE_L3G4200D));
  172. _accel_instance = _imu.register_accel(800, _dev->get_bus_id_devtype(DEVTYPE_L3G4200D));
  173. // start the timer process to read samples
  174. _dev->register_periodic_callback(1250, FUNCTOR_BIND_MEMBER(&AP_InertialSensor_L3G4200D::_accumulate, void));
  175. }
  176. /*
  177. copy filtered data to the frontend
  178. */
  179. bool AP_InertialSensor_L3G4200D::update(void)
  180. {
  181. update_gyro(_gyro_instance);
  182. update_accel(_accel_instance);
  183. return true;
  184. }
  185. // Accumulate values from accels and gyros
  186. void AP_InertialSensor_L3G4200D::_accumulate(void)
  187. {
  188. uint8_t num_samples_available;
  189. uint8_t fifo_status = 0;
  190. // Read gyro FIFO status
  191. fifo_status = 0;
  192. _dev->read_registers(L3G4200D_REG_FIFO_SRC, &fifo_status, 1);
  193. if (fifo_status & L3G4200D_REG_FIFO_SRC_OVERRUN) {
  194. // FIFO is full
  195. num_samples_available = 32;
  196. } else if (fifo_status & L3G4200D_REG_FIFO_SRC_EMPTY) {
  197. // FIFO is empty
  198. num_samples_available = 0;
  199. } else {
  200. // FIFO is partly full
  201. num_samples_available = fifo_status & L3G4200D_REG_FIFO_SRC_ENTRIES_MASK;
  202. }
  203. if (num_samples_available > 0) {
  204. // read all the entries in one go, using AUTO_INCREMENT. This saves a lot of time on I2C setup
  205. int16_t buffer[num_samples_available][3];
  206. if (!_dev->read_registers(L3G4200D_REG_XL | L3G4200D_REG_AUTO_INCREMENT,
  207. (uint8_t *)&buffer, sizeof(buffer))) {
  208. for (uint8_t i=0; i < num_samples_available; i++) {
  209. Vector3f gyro = Vector3f(buffer[i][0], -buffer[i][1], -buffer[i][2]);
  210. // Adjust for chip scaling to get radians/sec
  211. gyro *= L3G4200D_GYRO_SCALE_R_S;
  212. _rotate_and_correct_gyro(_gyro_instance, gyro);
  213. _notify_new_gyro_raw_sample(_gyro_instance, gyro);
  214. }
  215. }
  216. }
  217. // Read accelerometer FIFO to find out how many samples are available
  218. _dev->read_registers(ADXL345_ACCELEROMETER_ADXLREG_FIFO_STATUS,
  219. &fifo_status, 1);
  220. num_samples_available = fifo_status & 0x3F;
  221. // read the samples and apply the filter
  222. if (num_samples_available > 0) {
  223. int16_t buffer[num_samples_available][3];
  224. if (!_dev->read_registers_multiple(ADXL345_ACCELEROMETER_ADXLREG_DATAX0,
  225. (uint8_t *)buffer, sizeof(buffer[0]),
  226. num_samples_available)) {
  227. for (uint8_t i=0; i<num_samples_available; i++) {
  228. Vector3f accel = Vector3f(buffer[i][0], -buffer[i][1], -buffer[i][2]);
  229. // Adjust for chip scaling to get m/s/s
  230. accel *= ADXL345_ACCELEROMETER_SCALE_M_S;
  231. _rotate_and_correct_accel(_accel_instance, accel);
  232. _notify_new_accel_raw_sample(_accel_instance, accel);
  233. }
  234. }
  235. }
  236. }
  237. #endif