AP_VisualOdom_Backend.cpp 1.5 KB

1234567891011121314151617181920212223242526272829303132333435363738394041
  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_VisualOdom_Backend.h"
  14. /*
  15. base class constructor.
  16. This incorporates initialisation as well.
  17. */
  18. AP_VisualOdom_Backend::AP_VisualOdom_Backend(AP_VisualOdom &frontend) :
  19. _frontend(frontend)
  20. {
  21. }
  22. // set deltas (used by backend to update state)
  23. void AP_VisualOdom_Backend::set_deltas(const Vector3f &angle_delta, const Vector3f& position_delta, uint64_t time_delta_usec, float confidence)
  24. {
  25. // rotate and store angle_delta
  26. _frontend._state.angle_delta = angle_delta;
  27. _frontend._state.angle_delta.rotate((enum Rotation)_frontend._orientation.get());
  28. // rotate and store position_delta
  29. _frontend._state.position_delta = position_delta;
  30. _frontend._state.position_delta.rotate((enum Rotation)_frontend._orientation.get());
  31. _frontend._state.time_delta_usec = time_delta_usec;
  32. _frontend._state.confidence = confidence;
  33. _frontend._state.last_sensor_update_ms = AP_HAL::millis();
  34. }