diff --git a/sw/airborne/booz/booz2_telemetry.h b/sw/airborne/booz/booz2_telemetry.h index 73f0a4f79c..e85fce6f72 100644 --- a/sw/airborne/booz/booz2_telemetry.h +++ b/sw/airborne/booz/booz2_telemetry.h @@ -49,7 +49,7 @@ #include #include "booz_gps.h" #include -#include "ahrs.h" +#include #include "i2c_hw.h" @@ -301,7 +301,7 @@ extern uint8_t telemetry_mode_Main_DefaultChannel; #endif /* STABILISATION_ATTITUDE_TYPE_FLOAT */ -#include "ahrs/ahrs_aligner.h" +#include #define PERIODIC_SEND_BOOZ2_FILTER_ALIGNER(_chan) { \ DOWNLINK_SEND_BOOZ2_FILTER_ALIGNER(_chan, \ &ahrs_aligner.lp_gyro.p, \ @@ -325,7 +325,7 @@ extern uint8_t telemetry_mode_Main_DefaultChannel; #ifdef USE_AHRS_CMPL -#include "ahrs/ahrs_cmpl_euler.h" +#include #define PERIODIC_SEND_BOOZ2_FILTER(_chan) { \ DOWNLINK_SEND_BOOZ2_FILTER(_chan, \ &ahrs.ltp_to_imu_euler.phi, \ @@ -349,7 +349,7 @@ extern uint8_t telemetry_mode_Main_DefaultChannel; #endif #ifdef USE_AHRS_LKF -#include "ahrs.h" +#include #include "ahrs/ahrs_float_lkf.h" #define PERIODIC_SEND_AHRS_LKF(_chan) { \ DOWNLINK_SEND_AHRS_LKF(&bafl_eulers.phi, \ diff --git a/sw/airborne/booz/booz_fms.c b/sw/airborne/booz/booz_fms.c index d0757c5aa1..a3ff0a9c39 100644 --- a/sw/airborne/booz/booz_fms.c +++ b/sw/airborne/booz/booz_fms.c @@ -25,7 +25,7 @@ #include #include "booz_gps.h" -#include "ahrs.h" +#include #include "airframe.h" diff --git a/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_float.c b/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_float.c index ae98112264..2586669eff 100644 --- a/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_float.c +++ b/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_float.c @@ -24,7 +24,7 @@ #include "booz_stabilization.h" #include "math/pprz_algebra_float.h" -#include "ahrs.h" +#include #include "booz_radio_control.h" #include "airframe.h" diff --git a/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_int.c b/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_int.c index 9edfde87af..be03842a13 100644 --- a/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_int.c +++ b/sw/airborne/booz/stabilization/booz_stabilization_attitude_euler_int.c @@ -22,7 +22,7 @@ */ #include "booz_stabilization.h" -#include "ahrs.h" +#include #include "booz_radio_control.h" diff --git a/sw/airborne/booz/stabilization/booz_stabilization_attitude_quat_float.c b/sw/airborne/booz/stabilization/booz_stabilization_attitude_quat_float.c index 01d57c7c9f..5e1e6df30d 100644 --- a/sw/airborne/booz/stabilization/booz_stabilization_attitude_quat_float.c +++ b/sw/airborne/booz/stabilization/booz_stabilization_attitude_quat_float.c @@ -30,7 +30,7 @@ #include #include "math/pprz_algebra_float.h" #include "math/pprz_algebra_int.h" -#include "ahrs.h" +#include #include "airframe.h" struct FloatAttitudeGains booz_stabilization_gains[BOOZ_STABILIZATION_ATTITUDE_GAIN_NB]; diff --git a/sw/airborne/booz/stabilization/booz_stabilization_attitude_ref_quat_float.c b/sw/airborne/booz/stabilization/booz_stabilization_attitude_ref_quat_float.c index 2c19341ee9..953730dfc2 100644 --- a/sw/airborne/booz/stabilization/booz_stabilization_attitude_ref_quat_float.c +++ b/sw/airborne/booz/stabilization/booz_stabilization_attitude_ref_quat_float.c @@ -28,7 +28,7 @@ #include "airframe.h" #include "booz_stabilization.h" -#include "ahrs.h" +#include #include "booz_stabilization_attitude_ref_float.h" #include "quat_setpoint.h" diff --git a/sw/airborne/booz/stabilization/booz_stabilization_rate.c b/sw/airborne/booz/stabilization/booz_stabilization_rate.c index 8254854b03..81ebbbcd8a 100644 --- a/sw/airborne/booz/stabilization/booz_stabilization_rate.c +++ b/sw/airborne/booz/stabilization/booz_stabilization_rate.c @@ -24,7 +24,7 @@ #include "booz_stabilization.h" -#include "ahrs.h" +#include #include #include "booz_radio_control.h" diff --git a/sw/airborne/booz/test/test_mlkf.c b/sw/airborne/booz/test/test_mlkf.c index 882bcc92b2..3f2c4620f6 100644 --- a/sw/airborne/booz/test/test_mlkf.c +++ b/sw/airborne/booz/test/test_mlkf.c @@ -3,7 +3,7 @@ #include "math/pprz_algebra_double.h" #include -#include "ahrs.h" +#include #include "ahrs/ahrs_mlkf.h" static void read_data(const char* filename); diff --git a/sw/airborne/csc/mercury_xsens.h b/sw/airborne/csc/mercury_xsens.h index 01a9c5ca91..355d8535ca 100644 --- a/sw/airborne/csc/mercury_xsens.h +++ b/sw/airborne/csc/mercury_xsens.h @@ -62,7 +62,7 @@ extern uint16_t xsens_time_stamp[XSENS_COUNT]; extern int xsens_setzero; -#include "ahrs.h" +#include #define PERIODIC_SEND_BOOZ2_GYRO() { \ DOWNLINK_SEND_BOOZ2_GYRO(&imu.gyro.p, \ diff --git a/sw/airborne/firmwares/rotorcraft/ahrs.c b/sw/airborne/firmwares/rotorcraft/ahrs.c index 91774b2d57..3b13ab97dc 100644 --- a/sw/airborne/firmwares/rotorcraft/ahrs.c +++ b/sw/airborne/firmwares/rotorcraft/ahrs.c @@ -21,7 +21,7 @@ * Boston, MA 02111-1307, USA. */ -#include "ahrs.h" +#include #include struct Ahrs ahrs; diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c index 2e220b4b86..adc9fdd908 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_h.c @@ -25,7 +25,7 @@ //#define GUIDANCE_H_USE_REF #include -#include "ahrs.h" +#include #include "booz_stabilization.h" #include "booz_fms.h" #include diff --git a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c index ea8f7dc366..f4db460756 100644 --- a/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c +++ b/sw/airborne/firmwares/rotorcraft/guidance/guidance_v.c @@ -28,7 +28,7 @@ #include "booz_radio_control.h" #include "booz_stabilization.h" -#include "ahrs.h" +#include #include "booz_fms.h" #include "booz2_navigation.h" diff --git a/sw/airborne/firmwares/rotorcraft/ins.c b/sw/airborne/firmwares/rotorcraft/ins.c index cc4b5601f4..76c96774f7 100644 --- a/sw/airborne/firmwares/rotorcraft/ins.c +++ b/sw/airborne/firmwares/rotorcraft/ins.c @@ -32,7 +32,7 @@ #include "math/pprz_algebra_int.h" #include "math/pprz_algebra_float.h" -#include "ahrs.h" +#include #ifdef USE_VFF #include "ins/vf_float.h" diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index 1252aaf556..abeee7d4b3 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -47,12 +47,12 @@ #include "booz2_battery.h" #include "booz_fms.h" -#include "autopilot.h" +#include #include "booz_stabilization.h" #include -#include "ahrs.h" +#include #include #if defined USE_CAM || USE_DROP diff --git a/sw/airborne/modules/cam_control/booz_cam.c b/sw/airborne/modules/cam_control/booz_cam.c index 159da21188..abc2f1336b 100644 --- a/sw/airborne/modules/cam_control/booz_cam.c +++ b/sw/airborne/modules/cam_control/booz_cam.c @@ -24,7 +24,7 @@ #include "cam_control/booz_cam.h" #include "booz2_pwm_hw.h" -#include "ahrs.h" +#include #include "booz2_navigation.h" #include #include "flight_plan.h" diff --git a/sw/airborne/modules/cam_control/cam_track.c b/sw/airborne/modules/cam_control/cam_track.c index 8e171576a1..166a27b566 100644 --- a/sw/airborne/modules/cam_control/cam_track.c +++ b/sw/airborne/modules/cam_control/cam_track.c @@ -25,7 +25,7 @@ #include "cam_track.h" #include -#include "ahrs.h" +#include #ifdef USE_HFF #include "ins/hf_float.h" diff --git a/sw/simulator/nps/nps_autopilot_booz.c b/sw/simulator/nps/nps_autopilot_booz.c index 0d3288dbe0..b332ac750b 100644 --- a/sw/simulator/nps/nps_autopilot_booz.c +++ b/sw/simulator/nps/nps_autopilot_booz.c @@ -74,7 +74,7 @@ void nps_autopilot_run_step(double time __attribute__ ((unused))) { } #include "nps_fdm.h" -#include "ahrs.h" +#include #include "math/pprz_algebra.h" void sim_overwrite_ahrs(void) { diff --git a/sw/simulator/old_booz/booz2_sim_main.c b/sw/simulator/old_booz/booz2_sim_main.c index 6cc2605052..d1dc9830ac 100644 --- a/sw/simulator/old_booz/booz2_sim_main.c +++ b/sw/simulator/old_booz/booz2_sim_main.c @@ -125,7 +125,7 @@ static gboolean booz2_sim_periodic(gpointer data __attribute__ ((unused))) { } -#include "ahrs.h" +#include static void sim_run_one_step(void) { @@ -195,7 +195,7 @@ static void sim_run_one_step(void) { #ifdef BYPASS_AHRS #include "booz_geometry_mixed.h" -#include "ahrs.h" +#include static void sim_overwrite_ahrs(void) { ahrs.ltp_to_body_euler.phi = BOOZ_ANGLE_I_OF_F(bfm.eulers->ve[AXIS_X]); ahrs.ltp_to_body_euler.theta = BOOZ_ANGLE_I_OF_F(bfm.eulers->ve[AXIS_Y]);