AP_OpticalFlow_Onboard.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100
  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. #include "AP_OpticalFlow_Onboard.h"
  14. #include <AP_HAL/AP_HAL.h>
  15. #include "OpticalFlow.h"
  16. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX &&\
  17. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
  18. #ifndef OPTICALFLOW_ONBOARD_DEBUG
  19. #define OPTICALFLOW_ONBOARD_DEBUG 0
  20. #endif
  21. #define OPTICALFLOW_ONBOARD_ID 1
  22. extern const AP_HAL::HAL& hal;
  23. AP_OpticalFlow_Onboard::AP_OpticalFlow_Onboard(OpticalFlow &_frontend) :
  24. OpticalFlow_backend(_frontend)
  25. {}
  26. void AP_OpticalFlow_Onboard::init(void)
  27. {
  28. /* register callback to get gyro data */
  29. hal.opticalflow->init();
  30. }
  31. void AP_OpticalFlow_Onboard::update()
  32. {
  33. AP_HAL::OpticalFlow::Data_Frame data_frame;
  34. // read at maximum 10Hz
  35. uint32_t now = AP_HAL::millis();
  36. if (now - _last_read_ms < 100) {
  37. return;
  38. }
  39. _last_read_ms = now;
  40. if (!hal.opticalflow->read(data_frame)) {
  41. return;
  42. }
  43. struct OpticalFlow::OpticalFlow_state state;
  44. state.surface_quality = data_frame.quality;
  45. if (data_frame.delta_time > 0) {
  46. const Vector2f flowScaler = _flowScaler();
  47. float flowScaleFactorX = 1.0f + 0.001f * flowScaler.x;
  48. float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y;
  49. // delta_time is in microseconds and flow is in milliradians
  50. // per second, so multiply by 1000
  51. state.flowRate.x = flowScaleFactorX * 1000.0f /
  52. float(data_frame.delta_time) *
  53. data_frame.pixel_flow_x_integral;
  54. state.flowRate.y = flowScaleFactorY * 1000.0f /
  55. float(data_frame.delta_time) *
  56. data_frame.pixel_flow_y_integral;
  57. // delta_time is in microseconds so multiply to get back to seconds
  58. state.bodyRate.x = 1000000.0f / float(data_frame.delta_time) *
  59. data_frame.gyro_x_integral;
  60. state.bodyRate.y = 1000000.0f / float(data_frame.delta_time) *
  61. data_frame.gyro_y_integral;
  62. _applyYaw(state.flowRate);
  63. } else {
  64. state.flowRate.zero();
  65. state.bodyRate.zero();
  66. }
  67. // copy results to front end
  68. _update_frontend(state);
  69. #if OPTICALFLOW_ONBOARD_DEBUG
  70. hal.console->printf("FLOW_ONBOARD qual:%u FlowRateX:%4.2f Y:%4.2f"
  71. "BodyRateX:%4.2f Y:%4.2f, delta_time = %u\n",
  72. (unsigned)state.surface_quality,
  73. (double)state.flowRate.x,
  74. (double)state.flowRate.y,
  75. (double)state.bodyRate.x,
  76. (double)state.bodyRate.y,
  77. data_frame.delta_time);
  78. #endif
  79. }
  80. #endif