AP_IRLock_SITL.cpp 1.9 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  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_IRLock_SITL.cpp
  15. *
  16. * Created on: June 09, 2016
  17. * Author: Ian Chen
  18. */
  19. #include <AP_HAL/AP_HAL.h>
  20. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  21. #include "AP_IRLock_SITL.h"
  22. #include "AP_AHRS/AP_AHRS.h"
  23. void AP_IRLock_SITL::init(int8_t bus)
  24. {
  25. _sitl = AP::sitl();
  26. _sitl->precland_sim._type.set_and_notify(SITL::SIM_Precland::PreclandType::PRECLAND_TYPE_CONE);
  27. }
  28. // retrieve latest sensor data - returns true if new data is available
  29. bool AP_IRLock_SITL::update()
  30. {
  31. // return immediately if not healthy
  32. _flags.healthy = _sitl->precland_sim.healthy();
  33. if (!_flags.healthy) {
  34. return false;
  35. }
  36. if (_sitl->precland_sim.last_update_ms() != _last_timestamp) {
  37. const Vector3f position = _sitl->precland_sim.get_target_position();
  38. const Matrix3f &body_to_ned = AP::ahrs().get_rotation_body_to_ned();
  39. const Vector3f real_position = body_to_ned.mul_transpose(-position);
  40. _last_timestamp = _sitl->precland_sim.last_update_ms();
  41. _last_update_ms = _last_timestamp;
  42. _target_info.timestamp = _last_timestamp;
  43. _target_info.pos_x = real_position.y;
  44. _target_info.pos_y = -real_position.x;
  45. _target_info.pos_z = real_position.z;
  46. return true;
  47. }
  48. return false;
  49. }
  50. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL