AP_OpticalFlow_SITL.cpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126
  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. * AP_OpticalFlow_SITL.cpp - SITL emulation of optical flow sensor.
  15. */
  16. #include <AP_HAL/AP_HAL.h>
  17. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  18. #include "AP_OpticalFlow_SITL.h"
  19. extern const AP_HAL::HAL& hal;
  20. AP_OpticalFlow_SITL::AP_OpticalFlow_SITL(OpticalFlow &_frontend) :
  21. OpticalFlow_backend(_frontend),
  22. _sitl(AP::sitl())
  23. {
  24. }
  25. void AP_OpticalFlow_SITL::init(void)
  26. {
  27. }
  28. void AP_OpticalFlow_SITL::update(void)
  29. {
  30. if (!_sitl->flow_enable) {
  31. return;
  32. }
  33. // update at the requested rate
  34. uint32_t now = AP_HAL::millis();
  35. if (now - last_flow_ms < 1000*(1.0f/_sitl->flow_rate)) {
  36. return;
  37. }
  38. last_flow_ms = now;
  39. Vector3f gyro(radians(_sitl->state.rollRate),
  40. radians(_sitl->state.pitchRate),
  41. radians(_sitl->state.yawRate));
  42. OpticalFlow::OpticalFlow_state state;
  43. // NED velocity vector in m/s
  44. Vector3f velocity(_sitl->state.speedN,
  45. _sitl->state.speedE,
  46. _sitl->state.speedD);
  47. // a rotation matrix following DCM conventions
  48. Matrix3f rotmat;
  49. rotmat.from_euler(radians(_sitl->state.rollDeg),
  50. radians(_sitl->state.pitchDeg),
  51. radians(_sitl->state.yawDeg));
  52. state.surface_quality = 51;
  53. // sensor position offset in body frame
  54. Vector3f posRelSensorBF = _sitl->optflow_pos_offset;
  55. // estimate range to centre of image
  56. float range;
  57. if (rotmat.c.z > 0.05f && _sitl->height_agl > 0) {
  58. Vector3f relPosSensorEF = rotmat * posRelSensorBF;
  59. range = (_sitl->height_agl - relPosSensorEF.z) / rotmat.c.z;
  60. } else {
  61. range = 1e38f;
  62. }
  63. // Calculate relative velocity in sensor frame assuming no misalignment between sensor and vehicle body axes
  64. Vector3f relVelSensor = rotmat.mul_transpose(velocity);
  65. // correct relative velocity for rotation rates and sensor offset
  66. relVelSensor += gyro % posRelSensorBF;
  67. // Divide velocity by range and add body rates to get predicted sensed angular
  68. // optical rates relative to X and Y sensor axes assuming no misalignment or scale
  69. // factor error. Note - these are instantaneous values. The sensor sums these values across the interval from the last
  70. // poll to provide a delta angle across the interface
  71. state.flowRate.x = -relVelSensor.y/range + gyro.x + _sitl->flow_noise * rand_float();
  72. state.flowRate.y = relVelSensor.x/range + gyro.y + _sitl->flow_noise * rand_float();
  73. // The flow sensors body rates are assumed to be the same as the vehicle body rates (ie no misalignment)
  74. // Note - these are instantaneous values. The sensor sums these values across the interval from the last
  75. // poll to provide a delta angle across the interface.
  76. state.bodyRate = Vector2f(gyro.x, gyro.y);
  77. optflow_data[next_optflow_index++] = state;
  78. if (next_optflow_index >= optflow_delay+1) {
  79. next_optflow_index = 0;
  80. }
  81. state = optflow_data[next_optflow_index];
  82. if (_sitl->flow_delay != optflow_delay) {
  83. // cope with updates to the delay control
  84. if (_sitl->flow_delay > 0 &&
  85. (uint8_t)(_sitl->flow_delay) > ARRAY_SIZE(optflow_data)) {
  86. _sitl->flow_delay = ARRAY_SIZE(optflow_data);
  87. }
  88. optflow_delay = _sitl->flow_delay;
  89. for (uint8_t i=0; i<optflow_delay; i++) {
  90. optflow_data[i] = state;
  91. }
  92. }
  93. _applyYaw(state.flowRate);
  94. // copy results to front end
  95. _update_frontend(state);
  96. }
  97. #endif // CONFIG_HAL_BOARD