AP_OpticalFlow_PX4Flow.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  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. driver for PX4Flow optical flow sensor
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #include "AP_OpticalFlow_PX4Flow.h"
  18. #include <AP_Math/crc.h>
  19. #include <AP_AHRS/AP_AHRS.h>
  20. #include <AP_HAL/I2CDevice.h>
  21. #include <utility>
  22. #include "OpticalFlow.h"
  23. #include <stdio.h>
  24. extern const AP_HAL::HAL& hal;
  25. #define PX4FLOW_BASE_I2C_ADDR 0x42
  26. #define PX4FLOW_INIT_RETRIES 10 // attempt to initialise the sensor up to 10 times at startup
  27. // constructor
  28. AP_OpticalFlow_PX4Flow::AP_OpticalFlow_PX4Flow(OpticalFlow &_frontend) :
  29. OpticalFlow_backend(_frontend)
  30. {
  31. }
  32. // detect the device
  33. AP_OpticalFlow_PX4Flow *AP_OpticalFlow_PX4Flow::detect(OpticalFlow &_frontend)
  34. {
  35. AP_OpticalFlow_PX4Flow *sensor = new AP_OpticalFlow_PX4Flow(_frontend);
  36. if (!sensor) {
  37. return nullptr;
  38. }
  39. if (!sensor->setup_sensor()) {
  40. delete sensor;
  41. return nullptr;
  42. }
  43. return sensor;
  44. }
  45. /*
  46. look for the sensor on different buses
  47. */
  48. bool AP_OpticalFlow_PX4Flow::scan_buses(void)
  49. {
  50. bool success = false;
  51. uint8_t retry_attempt = 0;
  52. while (!success && retry_attempt < PX4FLOW_INIT_RETRIES) {
  53. FOREACH_I2C_EXTERNAL(bus) {
  54. #ifdef HAL_OPTFLOW_PX4FLOW_I2C_BUS
  55. // only one bus from HAL
  56. if (bus != HAL_OPTFLOW_PX4FLOW_I2C_BUS) {
  57. continue;
  58. }
  59. #endif
  60. AP_HAL::OwnPtr<AP_HAL::Device> tdev = hal.i2c_mgr->get_device(bus, PX4FLOW_BASE_I2C_ADDR + get_address());
  61. if (!tdev) {
  62. continue;
  63. }
  64. WITH_SEMAPHORE(tdev->get_semaphore());
  65. struct i2c_integral_frame frame;
  66. success = tdev->read_registers(REG_INTEGRAL_FRAME, (uint8_t *)&frame, sizeof(frame));
  67. if (success) {
  68. printf("Found PX4Flow on bus %u\n", bus);
  69. dev = std::move(tdev);
  70. break;
  71. }
  72. }
  73. retry_attempt++;
  74. if (!success) {
  75. hal.scheduler->delay(10);
  76. }
  77. }
  78. return success;
  79. }
  80. // setup the device
  81. bool AP_OpticalFlow_PX4Flow::setup_sensor(void)
  82. {
  83. if (!scan_buses()) {
  84. return false;
  85. }
  86. // read at 10Hz
  87. dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_OpticalFlow_PX4Flow::timer, void));
  88. return true;
  89. }
  90. // update - read latest values from sensor and fill in x,y and totals.
  91. void AP_OpticalFlow_PX4Flow::update(void)
  92. {
  93. }
  94. // timer to read sensor
  95. void AP_OpticalFlow_PX4Flow::timer(void)
  96. {
  97. struct i2c_integral_frame frame;
  98. if (!dev->read_registers(REG_INTEGRAL_FRAME, (uint8_t *)&frame, sizeof(frame))) {
  99. return;
  100. }
  101. struct OpticalFlow::OpticalFlow_state state {};
  102. if (frame.integration_timespan > 0) {
  103. const Vector2f flowScaler = _flowScaler();
  104. float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x;
  105. float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y;
  106. float integralToRate = 1.0e6 / frame.integration_timespan;
  107. state.surface_quality = frame.qual;
  108. state.flowRate = Vector2f(frame.pixel_flow_x_integral * flowScaleFactorX,
  109. frame.pixel_flow_y_integral * flowScaleFactorY) * 1.0e-4 * integralToRate;
  110. state.bodyRate = Vector2f(frame.gyro_x_rate_integral, frame.gyro_y_rate_integral) * 1.0e-4 * integralToRate;
  111. _applyYaw(state.flowRate);
  112. _applyYaw(state.bodyRate);
  113. }
  114. _update_frontend(state);
  115. }