OpticalFlow_backend.cpp 1.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748
  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 "OpticalFlow.h"
  14. extern const AP_HAL::HAL& hal;
  15. OpticalFlow_backend::OpticalFlow_backend(OpticalFlow &_frontend) :
  16. frontend(_frontend)
  17. {
  18. }
  19. OpticalFlow_backend::~OpticalFlow_backend(void)
  20. {
  21. }
  22. // update the frontend
  23. void OpticalFlow_backend::_update_frontend(const struct OpticalFlow::OpticalFlow_state &state)
  24. {
  25. frontend.update_state(state);
  26. }
  27. // apply yaw angle to a vector
  28. void OpticalFlow_backend::_applyYaw(Vector2f &v)
  29. {
  30. float yawAngleRad = _yawAngleRad();
  31. if (is_zero(yawAngleRad)) {
  32. return;
  33. }
  34. float cosYaw = cosf(yawAngleRad);
  35. float sinYaw = sinf(yawAngleRad);
  36. float x = v.x;
  37. float y = v.y;
  38. v.x = cosYaw * x - sinYaw * y;
  39. v.y = sinYaw * x + cosYaw * y;
  40. }