AC_PrecLand_SITL_Gazebo.h 1.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344
  1. #pragma once
  2. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  3. #include <AP_Math/AP_Math.h>
  4. #include <AC_PrecLand/AC_PrecLand_Backend.h>
  5. #include <AP_IRLock/AP_IRLock_SITL_Gazebo.h>
  6. /*
  7. * AC_PrecLand_SITL_Gazebo - implements precision landing using target
  8. * vectors provided Gazebo via a network socket
  9. */
  10. class AC_PrecLand_SITL_Gazebo : public AC_PrecLand_Backend
  11. {
  12. public:
  13. // Constructor
  14. AC_PrecLand_SITL_Gazebo(const AC_PrecLand& frontend, AC_PrecLand::precland_state& state);
  15. // perform any required initialisation of backend
  16. void init() override;
  17. // retrieve updates from sensor
  18. void update() override;
  19. // provides a unit vector towards the target in body frame
  20. // returns same as have_los_meas()
  21. bool get_los_body(Vector3f& ret) override;
  22. // returns system time in milliseconds of last los measurement
  23. uint32_t los_meas_time_ms() override;
  24. // return true if there is a valid los measurement available
  25. bool have_los_meas() override;
  26. private:
  27. AP_IRLock_SITL_Gazebo irlock;
  28. Vector3f _los_meas_body; // unit vector in body frame pointing towards target
  29. bool _have_los_meas; // true if there is a valid measurement from the camera
  30. uint32_t _los_meas_time_ms; // system time in milliseconds when los was measured
  31. };
  32. #endif