AC_PrecLand.h 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159
  1. #pragma once
  2. #include <AP_Math/AP_Math.h>
  3. #include <GCS_MAVLink/GCS_MAVLink.h>
  4. #include <stdint.h>
  5. #include "PosVelEKF.h"
  6. #include <AP_HAL/utility/RingBuffer.h>
  7. // declare backend classes
  8. class AC_PrecLand_Backend;
  9. class AC_PrecLand_Companion;
  10. class AC_PrecLand_IRLock;
  11. class AC_PrecLand_SITL_Gazebo;
  12. class AC_PrecLand_SITL;
  13. class AC_PrecLand
  14. {
  15. // declare backends as friends
  16. friend class AC_PrecLand_Backend;
  17. friend class AC_PrecLand_Companion;
  18. friend class AC_PrecLand_IRLock;
  19. friend class AC_PrecLand_SITL_Gazebo;
  20. friend class AC_PrecLand_SITL;
  21. public:
  22. AC_PrecLand();
  23. /* Do not allow copies */
  24. AC_PrecLand(const AC_PrecLand &other) = delete;
  25. AC_PrecLand &operator=(const AC_PrecLand&) = delete;
  26. // precision landing behaviours (held in PRECLAND_ENABLED parameter)
  27. enum PrecLandBehaviour {
  28. PRECLAND_BEHAVIOUR_DISABLED,
  29. PRECLAND_BEHAVIOR_ALWAYSLAND,
  30. PRECLAND_BEHAVIOR_CAUTIOUS
  31. };
  32. // types of precision landing (used for PRECLAND_TYPE parameter)
  33. enum PrecLandType {
  34. PRECLAND_TYPE_NONE = 0,
  35. PRECLAND_TYPE_COMPANION,
  36. PRECLAND_TYPE_IRLOCK,
  37. PRECLAND_TYPE_SITL_GAZEBO,
  38. PRECLAND_TYPE_SITL,
  39. };
  40. // perform any required initialisation of landing controllers
  41. // update_rate_hz should be the rate at which the update method will be called in hz
  42. void init(uint16_t update_rate_hz);
  43. // returns true if precision landing is healthy
  44. bool healthy() const { return _backend_state.healthy; }
  45. // returns true if precision landing is enabled (used only for logging)
  46. bool enabled() const { return _enabled.get(); }
  47. // returns time of last update
  48. uint32_t last_update_ms() const { return _last_update_ms; }
  49. // returns time of last time target was seen
  50. uint32_t last_backend_los_meas_ms() const { return _last_backend_los_meas_ms; }
  51. // returns estimator type
  52. uint8_t estimator_type() const { return _estimator_type; }
  53. // returns ekf outlier count
  54. uint32_t ekf_outlier_count() const { return _outlier_reject_count; }
  55. // give chance to driver to get updates from sensor, should be called at 400hz
  56. void update(float rangefinder_alt_cm, bool rangefinder_alt_valid);
  57. // returns target position relative to the EKF origin
  58. bool get_target_position_cm(Vector2f& ret);
  59. // returns target relative position as 3D vector
  60. void get_target_position_measurement_cm(Vector3f& ret);
  61. // returns target position relative to vehicle
  62. bool get_target_position_relative_cm(Vector2f& ret);
  63. // returns target velocity relative to vehicle
  64. bool get_target_velocity_relative_cms(Vector2f& ret);
  65. // returns true when the landing target has been detected
  66. bool target_acquired();
  67. // process a LANDING_TARGET mavlink message
  68. void handle_msg(const mavlink_message_t &msg);
  69. // parameter var table
  70. static const struct AP_Param::GroupInfo var_info[];
  71. private:
  72. enum estimator_type_t {
  73. ESTIMATOR_TYPE_RAW_SENSOR = 0,
  74. ESTIMATOR_TYPE_KALMAN_FILTER = 1
  75. };
  76. // returns enabled parameter as an behaviour
  77. enum PrecLandBehaviour get_behaviour() const { return (enum PrecLandBehaviour)(_enabled.get()); }
  78. // run target position estimator
  79. void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid);
  80. // If a new measurement was retrieved, sets _target_pos_rel_meas_NED and returns true
  81. bool construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid);
  82. // get vehicle body frame 3D vector from vehicle to target. returns true on success, false on failure
  83. bool retrieve_los_meas(Vector3f& target_vec_unit_body);
  84. // calculate target's position and velocity relative to the vehicle (used as input to position controller)
  85. // results are stored in_target_pos_rel_out_NE, _target_vel_rel_out_NE
  86. void run_output_prediction();
  87. // parameters
  88. AP_Int8 _enabled; // enabled/disabled and behaviour
  89. AP_Int8 _type; // precision landing sensor type
  90. AP_Int8 _bus; // which sensor bus
  91. AP_Int8 _estimator_type; // precision landing estimator type
  92. AP_Float _lag; // sensor lag in seconds
  93. AP_Float _yaw_align; // Yaw angle from body x-axis to sensor x-axis.
  94. AP_Float _land_ofs_cm_x; // Desired landing position of the camera forward of the target in vehicle body frame
  95. AP_Float _land_ofs_cm_y; // Desired landing position of the camera right of the target in vehicle body frame
  96. AP_Float _accel_noise; // accelerometer process noise
  97. AP_Vector3f _cam_offset; // Position of the camera relative to the CG
  98. uint32_t _last_update_ms; // system time in millisecond when update was last called
  99. bool _target_acquired; // true if target has been seen recently
  100. uint32_t _last_backend_los_meas_ms; // system time target was last seen
  101. PosVelEKF _ekf_x, _ekf_y; // Kalman Filter for x and y axis
  102. uint32_t _outlier_reject_count; // mini-EKF's outlier counter (3 consecutive outliers lead to EKF accepting updates)
  103. Vector3f _target_pos_rel_meas_NED; // target's relative position as 3D vector
  104. Vector2f _target_pos_rel_est_NE; // target's position relative to the IMU, not compensated for lag
  105. Vector2f _target_vel_rel_est_NE; // target's velocity relative to the IMU, not compensated for lag
  106. Vector2f _target_pos_rel_out_NE; // target's position relative to the camera, fed into position controller
  107. Vector2f _target_vel_rel_out_NE; // target's velocity relative to the CG, fed into position controller
  108. // structure and buffer to hold a history of vehicle velocity
  109. struct inertial_data_frame_s {
  110. Matrix3f Tbn; // dcm rotation matrix to rotate body frame to north
  111. Vector3f correctedVehicleDeltaVelocityNED;
  112. Vector3f inertialNavVelocity;
  113. bool inertialNavVelocityValid;
  114. float dt;
  115. uint64_t time_usec;
  116. };
  117. ObjectArray<inertial_data_frame_s> *_inertial_history;
  118. // backend state
  119. struct precland_state {
  120. bool healthy;
  121. } _backend_state;
  122. AC_PrecLand_Backend *_backend; // pointers to backend precision landing driver
  123. };