31 #include "stabilization/stabilization_attitude.h"
32 #include "generated/airframe.h"
39 #if defined SITL && USE_NPS
46 #error INS initialization from flight plan is not yet supported
50 #ifndef INS_EKF2_AGL_ID
51 #define INS_EKF2_AGL_ID ABI_BROADCAST
56 #ifndef INS_SONAR_MIN_RANGE
57 #define INS_SONAR_MIN_RANGE 0.001
62 #ifndef INS_SONAR_MAX_RANGE
63 #define INS_SONAR_MAX_RANGE 4.0
68 #ifndef INS_EKF2_BARO_ID
70 #define INS_EKF2_BARO_ID BARO_BOARD_SENDER_ID
72 #define INS_EKF2_BARO_ID ABI_BROADCAST
78 #ifndef INS_EKF2_GYRO_ID
79 #define INS_EKF2_GYRO_ID ABI_BROADCAST
84 #ifndef INS_EKF2_ACCEL_ID
85 #define INS_EKF2_ACCEL_ID ABI_BROADCAST
90 #ifndef INS_EKF2_MAG_ID
91 #define INS_EKF2_MAG_ID ABI_BROADCAST
96 #ifndef INS_EKF2_GPS_ID
97 #define INS_EKF2_GPS_ID GPS_MULTI_ID
152 #if PERIODIC_TELEMETRY
157 float qfe = 101325.0;
159 pprz_msg_send_INS_REF(trans,
dev, AC_ID,
167 uint16_t gps_check_status, filter_fault_status, soln_status;
169 ekf.get_gps_check_status(&gps_check_status);
170 ekf.get_filter_fault_status(&filter_fault_status);
171 ekf.get_control_mode(&control_mode);
172 ekf.get_ekf_soln_status(&soln_status);
175 float mag, vel, pos, hgt, tas, hagl, beta, mag_decl;
176 ekf.get_innovation_test_status(&innov_test_status, &mag, &vel, &pos, &hgt, &tas, &hagl, &beta);
177 ekf.get_mag_decl_deg(&mag_decl);
178 pprz_msg_send_INS_EKF2(trans,
dev, AC_ID,
179 &control_mode, &filter_fault_status, &gps_check_status, &soln_status,
180 &innov_test_status, &mag, &vel, &pos, &hgt, &tas, &hagl, &beta,
186 float gps_drift[3], vibe[3];
189 ekf.get_gps_drift_metrics(gps_drift, &gps_blocked);
190 ekf.get_imu_vibe_metrics(vibe);
191 gps_blocked_b = gps_blocked;
193 pprz_msg_send_INS_EKF2_EXT(trans,
dev, AC_ID,
194 &gps_drift[0], &gps_drift[1], &gps_drift[2], &gps_blocked_b,
195 &vibe[0], &vibe[1], &vibe[2]);
203 ekf.get_control_mode(&control_mode);
204 ekf.get_filter_fault_status(&filter_fault_status);
207 if ((control_mode & 0x7) == 0x7) {
209 }
else if ((control_mode & 0x7) == 0x3) {
216 if (filter_fault_status) {
220 pprz_msg_send_STATE_FILTER_STATUS(trans,
dev, AC_ID, &
ahrs_ekf2_id, &mde, &filter_fault_status);
225 float velNE_wind[2], tas;
229 ekf.get_wind_velocity(velNE_wind);
230 ekf.get_true_airspeed(&tas);
232 pprz_msg_send_WIND_INFO_RET(trans,
dev, AC_ID, &flags, &velNE_wind[1], &velNE_wind[0], &f_zero, &tas);
237 float accel_bias[3], gyro_bias[3],
states[24];
238 ekf.get_accel_bias(accel_bias);
239 ekf.get_gyro_bias(gyro_bias);
242 pprz_msg_send_AHRS_BIAS(trans,
dev, AC_ID, &accel_bias[0], &accel_bias[1], &accel_bias[2],
252 ekf_params->mag_fusion_type = MAG_FUSE_TYPE_HEADING;
267 #if PERIODIC_TELEMETRY
296 filter_control_status_u control_status;
297 ekf.get_control_mode(&control_status.value);
300 if (control_status.flags.tilt_align) {
304 ekf.get_position(pos_f);
315 ekf.get_velocity(vel_f);
324 float vel_deriv_f[3] = {};
326 ekf.get_vel_deriv_ned(vel_deriv_f);
327 accel.
x = vel_deriv_f[0];
328 accel.
y = vel_deriv_f[1];
329 accel.
z = vel_deriv_f[2];
336 struct map_projection_reference_s ekf_origin = {};
342 bool ekf_origin_valid =
ekf.get_ekf_origin(&origin_time, &ekf_origin, &ref_alt);
344 lla_ref.
lat = ekf_origin.lat_rad * 180.0 / M_PI * 1e7;
345 lla_ref.
lon = ekf_origin.lon_rad * 180.0 / M_PI * 1e7;
346 lla_ref.
alt = ref_alt * 1000.0;
355 #if defined SITL && USE_NPS
373 imuSample imu_sample;
374 imu_sample.time_us = stamp;
379 ekf.setIMUData(imu_sample);
381 if (
ekf.attitude_valid()) {
384 const Quatf att_q{
ekf.calculate_quaternion()};
385 ltp_to_body_quat.
qi = att_q(0);
386 ltp_to_body_quat.
qx = att_q(1);
387 ltp_to_body_quat.
qy = att_q(2);
388 ltp_to_body_quat.
qz = att_q(3);
394 float delta_q_reset[4];
396 ekf.get_quat_reset(delta_q_reset, &quat_reset_counter);
398 #ifndef NO_RESET_UPDATE_SETPOINT_HEADING
401 float psi = matrix::Eulerf(matrix::Quatf(delta_q_reset)).psi();
402 #if defined STABILIZATION_ATTITUDE_TYPE_INT
419 ekf.get_gyro_bias(gyro_bias);
430 ekf.get_accel_bias(accel_bias);
450 ekf.set_air_density(rho);
455 ekf.setBaroData(stamp, height_amsl_m);
461 ekf.setRangeData(stamp, distance);
535 mag_r[0] = mag_body.
x;
536 mag_r[1] = mag_body.
y;
537 mag_r[2] = mag_body.
z;
539 ekf.setMagData(stamp, mag_r);