APM:Libraries
AC_PrecLand.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_Math/AP_Math.h>
6 #include <stdint.h>
7 #include "PosVelEKF.h"
8 #include <AP_Buffer/AP_Buffer.h>
9 #include <AP_AHRS/AP_AHRS.h>
10 
11 // declare backend classes
14 class AC_PrecLand_IRLock;
16 class AC_PrecLand_SITL;
17 
19 {
20  // declare backends as friends
21  friend class AC_PrecLand_Backend;
22  friend class AC_PrecLand_Companion;
23  friend class AC_PrecLand_IRLock;
25  friend class AC_PrecLand_SITL;
26 
27 public:
29 
30  /* Do not allow copies */
31  AC_PrecLand(const AC_PrecLand &other) = delete;
32  AC_PrecLand &operator=(const AC_PrecLand&) = delete;
33 
34  // precision landing behaviours (held in PRECLAND_ENABLED parameter)
39  };
40 
41  // types of precision landing (used for PRECLAND_TYPE parameter)
42  enum PrecLandType {
48  };
49 
50  // perform any required initialisation of landing controllers
51  void init();
52 
53  // returns true if precision landing is healthy
54  bool healthy() const { return _backend_state.healthy; }
55 
56  // returns true if precision landing is enabled (used only for logging)
57  bool enabled() const { return _enabled.get(); }
58 
59  // returns time of last update
60  uint32_t last_update_ms() const { return _last_update_ms; }
61 
62  // give chance to driver to get updates from sensor, should be called at 400hz
63  void update(float rangefinder_alt_cm, bool rangefinder_alt_valid);
64 
65  // returns target position relative to the EKF origin
67 
68  // returns target position relative to vehicle
70 
71  // returns target velocity relative to vehicle
73 
74  // returns true when the landing target has been detected
75  bool target_acquired();
76 
77  // process a LANDING_TARGET mavlink message
78  void handle_msg(mavlink_message_t* msg);
79 
80  // parameter var table
81  static const struct AP_Param::GroupInfo var_info[];
82 
83 private:
87  };
88 
89  // returns enabled parameter as an behaviour
90  enum PrecLandBehaviour get_behaviour() const { return (enum PrecLandBehaviour)(_enabled.get()); }
91 
92  // run target position estimator
93  void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid);
94 
95  // If a new measurement was retreived, sets _target_pos_rel_meas_NED and returns true
96  bool construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid);
97 
98  // get vehicle body frame 3D vector from vehicle to target. returns true on success, false on failure
99  bool retrieve_los_meas(Vector3f& target_vec_unit_body);
100 
101  // calculate target's position and velocity relative to the vehicle (used as input to position controller)
102  // results are stored in_target_pos_rel_out_NE, _target_vel_rel_out_NE
103  void run_output_prediction();
104 
105  // references to inertial nav and ahrs libraries
107 
108  // parameters
109  AP_Int8 _enabled; // enabled/disabled and behaviour
110  AP_Int8 _type; // precision landing sensor type
111  AP_Int8 _bus; // which sensor bus
112  AP_Int8 _estimator_type; // precision landing estimator type
113  AP_Float _yaw_align; // Yaw angle from body x-axis to sensor x-axis.
114  AP_Float _land_ofs_cm_x; // Desired landing position of the camera forward of the target in vehicle body frame
115  AP_Float _land_ofs_cm_y; // Desired landing position of the camera right of the target in vehicle body frame
116  AP_Float _accel_noise; // accelometer process noise
117  AP_Vector3f _cam_offset; // Position of the camera relative to the CG
118 
119  uint32_t _last_update_ms; // system time in millisecond when update was last called
120  bool _target_acquired; // true if target has been seen recently
121  uint32_t _last_backend_los_meas_ms; // system time target was last seen
122 
123  PosVelEKF _ekf_x, _ekf_y; // Kalman Filter for x and y axis
124  uint32_t _outlier_reject_count; // mini-EKF's outlier counter (3 consecutive outliers lead to EKF accepting updates)
125 
126  Vector3f _target_pos_rel_meas_NED; // target's relative position as 3D vector
127 
128  Vector2f _target_pos_rel_est_NE; // target's position relative to the IMU, not compensated for lag
129  Vector2f _target_vel_rel_est_NE; // target's velocity relative to the IMU, not compensated for lag
130 
131  Vector2f _target_pos_rel_out_NE; // target's position relative to the camera, fed into position controller
132  Vector2f _target_vel_rel_out_NE; // target's velocity relative to the CG, fed into position controller
133 
134  // structure and buffer to hold a short history of vehicle velocity
136  Matrix3f Tbn; // dcm rotation matrix to rotate body frame to north
140  float dt;
141  };
143 
144  // backend state
145  struct precland_state {
146  bool healthy;
147  } _backend_state;
148  AC_PrecLand_Backend *_backend; // pointers to backend precision landing driver
149 };
struct AC_PrecLand::precland_state _backend_state
AP_Float _land_ofs_cm_y
Definition: AC_PrecLand.h:115
AP_Buffer< inertial_data_frame_s, 8 > _inertial_history
Definition: AC_PrecLand.h:142
AP_Int8 _bus
Definition: AC_PrecLand.h:111
bool get_target_position_cm(Vector2f &ret)
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
Vector2f _target_vel_rel_est_NE
Definition: AC_PrecLand.h:129
AP_Int8 _estimator_type
Definition: AC_PrecLand.h:112
bool construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid)
AC_PrecLand(const AP_AHRS_NavEKF &ahrs)
AP_Float _yaw_align
Definition: AC_PrecLand.h:113
bool get_target_velocity_relative_cms(Vector2f &ret)
Vector2f _target_pos_rel_est_NE
Definition: AC_PrecLand.h:128
bool target_acquired()
AP_Float _land_ofs_cm_x
Definition: AC_PrecLand.h:114
void run_output_prediction()
uint32_t _last_update_ms
Definition: AC_PrecLand.h:119
static const struct AP_Param::GroupInfo var_info[]
Definition: AC_PrecLand.h:81
AC_PrecLand & operator=(const AC_PrecLand &)=delete
Vector3f _target_pos_rel_meas_NED
Definition: AC_PrecLand.h:126
bool retrieve_los_meas(Vector3f &target_vec_unit_body)
PosVelEKF _ekf_y
Definition: AC_PrecLand.h:123
bool get_target_position_relative_cm(Vector2f &ret)
PosVelEKF _ekf_x
Definition: AC_PrecLand.h:123
AP_Int8 _enabled
Definition: AC_PrecLand.h:109
bool _target_acquired
Definition: AC_PrecLand.h:120
AP_Vector3f _cam_offset
Definition: AC_PrecLand.h:117
void update(float rangefinder_alt_cm, bool rangefinder_alt_valid)
bool healthy() const
Definition: AC_PrecLand.h:54
uint32_t _last_backend_los_meas_ms
Definition: AC_PrecLand.h:121
enum PrecLandBehaviour get_behaviour() const
Definition: AC_PrecLand.h:90
Common definitions and utility routines for the ArduPilot libraries.
AP_Int8 _type
Definition: AC_PrecLand.h:110
bool enabled() const
Definition: AC_PrecLand.h:57
const AP_AHRS_NavEKF & _ahrs
Definition: AC_PrecLand.h:106
Vector2f _target_vel_rel_out_NE
Definition: AC_PrecLand.h:132
void handle_msg(mavlink_message_t *msg)
void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid)
fifo (queue) buffer template class
Vector2f _target_pos_rel_out_NE
Definition: AC_PrecLand.h:131
AC_PrecLand_Backend * _backend
Definition: AC_PrecLand.h:148
uint32_t _outlier_reject_count
Definition: AC_PrecLand.h:124
AP_Float _accel_noise
Definition: AC_PrecLand.h:116
uint32_t last_update_ms() const
Definition: AC_PrecLand.h:60