AP_OpticalFlow_MAV.cpp 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106
  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_HAL/AP_HAL.h>
  14. #include <AP_AHRS/AP_AHRS.h>
  15. #include "AP_OpticalFlow_MAV.h"
  16. #define OPTFLOW_MAV_TIMEOUT_SEC 0.5f
  17. // detect the device
  18. AP_OpticalFlow_MAV *AP_OpticalFlow_MAV::detect(OpticalFlow &_frontend)
  19. {
  20. // we assume mavlink messages will be sent into this driver
  21. AP_OpticalFlow_MAV *sensor = new AP_OpticalFlow_MAV(_frontend);
  22. return sensor;
  23. }
  24. // read latest values from sensor and fill in x,y and totals.
  25. void AP_OpticalFlow_MAV::update(void)
  26. {
  27. // record gyro values as long as they are being used
  28. // the sanity check of dt below ensures old gyro values are not used
  29. if (gyro_sum_count < 1000) {
  30. const Vector3f& gyro = AP::ahrs().get_gyro();
  31. gyro_sum.x += gyro.x;
  32. gyro_sum.y += gyro.y;
  33. gyro_sum_count++;
  34. }
  35. // return without updating state if no readings
  36. if (count == 0) {
  37. return;
  38. }
  39. struct OpticalFlow::OpticalFlow_state state {};
  40. state.surface_quality = quality_sum / count;
  41. // calculate dt
  42. const float dt = (latest_frame_us - prev_frame_us) * 1.0e-6;
  43. prev_frame_us = latest_frame_us;
  44. // sanity check dt
  45. if (is_positive(dt) && (dt < OPTFLOW_MAV_TIMEOUT_SEC)) {
  46. // calculate flow values
  47. const float flow_scale_factor_x = 1.0f + 0.001f * _flowScaler().x;
  48. const float flow_scale_factor_y = 1.0f + 0.001f * _flowScaler().y;
  49. // copy flow rates to state structure
  50. state.flowRate = { ((float)flow_sum.x / count) * flow_scale_factor_x * dt,
  51. ((float)flow_sum.y / count) * flow_scale_factor_y * dt };
  52. // copy average body rate to state structure
  53. state.bodyRate = { gyro_sum.x / gyro_sum_count, gyro_sum.y / gyro_sum_count };
  54. _applyYaw(state.flowRate);
  55. _applyYaw(state.bodyRate);
  56. } else {
  57. // first frame received in some time so cannot calculate flow values
  58. state.flowRate.zero();
  59. state.bodyRate.zero();
  60. }
  61. _update_frontend(state);
  62. // reset local buffers
  63. flow_sum.zero();
  64. quality_sum = 0;
  65. count = 0;
  66. // reset gyro sum
  67. gyro_sum.zero();
  68. gyro_sum_count = 0;
  69. }
  70. // handle OPTICAL_FLOW mavlink messages
  71. void AP_OpticalFlow_MAV::handle_msg(const mavlink_message_t &msg)
  72. {
  73. mavlink_optical_flow_t packet;
  74. mavlink_msg_optical_flow_decode(&msg, &packet);
  75. // record time message was received
  76. // ToDo: add jitter correction
  77. latest_frame_us = AP_HAL::micros64();
  78. // add sensor values to sum
  79. flow_sum.x += packet.flow_x;
  80. flow_sum.y += packet.flow_y;
  81. quality_sum += packet.quality;
  82. count++;
  83. // take sensor id from message
  84. sensor_id = packet.sensor_id;
  85. }