diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile index aaae7a5aa8f..ceec6d9d86f 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_quat.makefile @@ -8,7 +8,7 @@ USE_MAGNETOMETER ?= 0 AHRS_ALIGNER_LED ?= none -AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -DAHRS_GRAVITY_UPDATE_COORDINATED_TURN ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE)) @@ -48,7 +48,7 @@ nps.srcs += $(AHRS_SRCS) # Simple simulation of the AHRS result # ahrssim_CFLAGS = -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -ahrssim_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +ahrssim_CFLAGS += -DUSE_AHRS ahrssim_srcs = $(SRC_SUBSYSTEMS)/ahrs.c ahrssim_srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile index b996e653c04..51d63fb73a8 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_cmpl_rmat.makefile @@ -8,7 +8,7 @@ USE_MAGNETOMETER ?= 0 AHRS_ALIGNER_LED ?= none -AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -DAHRS_GRAVITY_UPDATE_COORDINATED_TURN ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE)) @@ -40,7 +40,7 @@ nps.srcs += $(AHRS_SRCS) # Simple simulation of the AHRS result # ahrssim_CFLAGS = -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -ahrssim_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +ahrssim_CFLAGS += -DUSE_AHRS ahrssim_srcs = $(SRC_SUBSYSTEMS)/ahrs.c ahrssim_srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile index b88c4d96cce..26b63dc8dad 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_float_dcm.makefile @@ -7,7 +7,7 @@ AHRS_ALIGNER_LED ?= none AHRS_CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_float_dcm.h\" AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -AHRS_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +AHRS_CFLAGS += -DUSE_AHRS ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE)) AHRS_CFLAGS += -DUSE_MAGNETOMETER @@ -36,7 +36,7 @@ nps.srcs += $(AHRS_SRCS) # Simple simulation of the AHRS result # ahrssim_CFLAGS = -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -ahrssim_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +ahrssim_CFLAGS += -DUSE_AHRS ahrssim_srcs = $(SRC_SUBSYSTEMS)/ahrs.c ahrssim_srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile index 9b420e4fe38..1df57d57adc 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_gx3.makefile @@ -10,8 +10,6 @@ AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_IMU AHRS_CFLAGS += -DUSE_IMU_FLOAT -#fixedwings -AHRS_CFLAGS += -DAHRS_UPDATE_FW_ESTIMATOR AHRS_CFLAGS += -DUSE_AHRS_ALIGNER ifneq ($(AHRS_ALIGNER_LED),none) diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile index 6e53c73e56d..6f2de55e7ab 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_quat.makefile @@ -9,7 +9,7 @@ USE_MAGNETOMETER ?= 0 AHRS_ALIGNER_LED ?= none -AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_AHRS_ALIGNER -DAHRS_GRAVITY_UPDATE_COORDINATED_TURN ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE)) @@ -49,7 +49,7 @@ nps.srcs += $(AHRS_SRCS) # Simple simulation of the AHRS result # ahrssim_CFLAGS = -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -ahrssim_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +ahrssim_CFLAGS += -DUSE_AHRS ahrssim_srcs = $(SRC_SUBSYSTEMS)/ahrs.c ahrssim_srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/conf/firmwares/subsystems/fixedwing/ins_float_invariant.makefile b/conf/firmwares/subsystems/fixedwing/ins_float_invariant.makefile index 34c7e228174..7a688bf77d3 100644 --- a/conf/firmwares/subsystems/fixedwing/ins_float_invariant.makefile +++ b/conf/firmwares/subsystems/fixedwing/ins_float_invariant.makefile @@ -37,7 +37,7 @@ nps.srcs += $(INS_SRCS) # Simple simulation of the AHRS result # ahrssim_CFLAGS = -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -ahrssim_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +ahrssim_CFLAGS += -DUSE_AHRS ahrssim_srcs = $(SRC_SUBSYSTEMS)/ahrs.c ahrssim_srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile b/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile index b9589d04c54..6c856ac42f1 100644 --- a/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile +++ b/conf/firmwares/subsystems/fixedwing/ins_xsens.makefile @@ -52,7 +52,7 @@ SIM_TARGETS = sim jsbsim nps ifneq (,$(findstring $(TARGET),$(SIM_TARGETS))) $(TARGET).CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -$(TARGET).CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +$(TARGET).CFLAGS += -DUSE_AHRS $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ahrs.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile deleted file mode 100644 index f7f280abe07..00000000000 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_euler.makefile +++ /dev/null @@ -1,29 +0,0 @@ -# Hey Emacs, this is a -*- makefile -*- -# -# Fixed point complementary filter using euler angles for attitude estimation -# - -USE_MAGNETOMETER ?= 1 -AHRS_ALIGNER_LED ?= none - -AHRS_CFLAGS = -DUSE_AHRS -AHRS_CFLAGS += -DUSE_AHRS_ALIGNER - -ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE)) - AHRS_CFLAGS += -DUSE_MAGNETOMETER -endif - -ifneq ($(AHRS_ALIGNER_LED),none) - AHRS_CFLAGS += -DAHRS_ALIGNER_LED=$(AHRS_ALIGNER_LED) -endif - -AHRS_CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_int_cmpl_euler.h\" -AHRS_SRCS += subsystems/ahrs.c -AHRS_SRCS += subsystems/ahrs/ahrs_int_cmpl_euler.c -AHRS_SRCS += subsystems/ahrs/ahrs_aligner.c - -ap.CFLAGS += $(AHRS_CFLAGS) -ap.srcs += $(AHRS_SRCS) - -nps.CFLAGS += $(AHRS_CFLAGS) -nps.srcs += $(AHRS_SRCS) diff --git a/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_quat.makefile b/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_quat.makefile index f892e0e8b01..310df57d6b4 100644 --- a/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_quat.makefile +++ b/conf/firmwares/subsystems/rotorcraft/ahrs_int_cmpl_quat.makefile @@ -6,6 +6,7 @@ # USE_MAGNETOMETER ?= 1 +AHRS_ALIGNER_LED ?= none AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_AHRS_ALIGNER diff --git a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile b/conf/firmwares/subsystems/shared/ahrs_int_cmpl_euler.makefile similarity index 87% rename from conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile rename to conf/firmwares/subsystems/shared/ahrs_int_cmpl_euler.makefile index 61a5e809379..f51c9c4d476 100644 --- a/conf/firmwares/subsystems/fixedwing/ahrs_int_cmpl_euler.makefile +++ b/conf/firmwares/subsystems/shared/ahrs_int_cmpl_euler.makefile @@ -1,10 +1,12 @@ # Hey Emacs, this is a -*- makefile -*- # +# Fixed point complementary filter using euler angles for attitude estimation +# USE_MAGNETOMETER ?= 1 AHRS_ALIGNER_LED ?= none -AHRS_CFLAGS = -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +AHRS_CFLAGS = -DUSE_AHRS AHRS_CFLAGS += -DUSE_AHRS_ALIGNER ifeq (,$(findstring $(USE_MAGNETOMETER),0 FALSE)) @@ -30,7 +32,7 @@ nps.srcs += $(AHRS_SRCS) # Simple simulation of the AHRS result # ahrssim_CFLAGS = -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" -ahrssim_CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR +ahrssim_CFLAGS += -DUSE_AHRS ahrssim_srcs = $(SRC_SUBSYSTEMS)/ahrs.c ahrssim_srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c index 2977c599cce..8188f54c532 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.c @@ -94,18 +94,6 @@ PRINT_CONFIG_VAR(AHRS_MAG_CORRECT_FREQUENCY) #define AHRS_GRAVITY_HEURISTIC_FACTOR 30 #endif -#ifdef AHRS_UPDATE_FW_ESTIMATOR -// remotely settable -#ifndef INS_ROLL_NEUTRAL_DEFAULT -#define INS_ROLL_NEUTRAL_DEFAULT 0 -#endif -#ifndef INS_PITCH_NEUTRAL_DEFAULT -#define INS_PITCH_NEUTRAL_DEFAULT 0 -#endif -float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; -float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; -#endif //AHRS_UPDATE_FW_ESTIMATOR - void ahrs_update_mag_full(void); void ahrs_update_mag_2d(void); @@ -573,16 +561,7 @@ static inline void compute_body_orientation_and_rates(void) { struct FloatQuat *body_to_imu_quat = orientationGetQuat_f(&imu.body_to_imu); FLOAT_QUAT_COMP_INV(ltp_to_body_quat, ahrs_impl.ltp_to_imu_quat, *body_to_imu_quat); /* Set state */ -#ifdef AHRS_UPDATE_FW_ESTIMATOR - struct FloatEulers neutrals_to_body_eulers = { ins_roll_neutral, ins_pitch_neutral, 0. }; - struct FloatQuat neutrals_to_body_quat, ltp_to_neutrals_quat; - FLOAT_QUAT_OF_EULERS(neutrals_to_body_quat, neutrals_to_body_eulers); - FLOAT_QUAT_NORMALIZE(neutrals_to_body_quat); - FLOAT_QUAT_COMP_INV(ltp_to_neutrals_quat, ltp_to_body_quat, neutrals_to_body_quat); - stateSetNedToBodyQuat_f(<p_to_neutrals_quat); -#else stateSetNedToBodyQuat_f(<p_to_body_quat); -#endif /* compute body rates */ struct FloatRates body_rate; diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h index cca2281eb22..3d756b3d03d 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h +++ b/sw/airborne/subsystems/ahrs/ahrs_float_cmpl.h @@ -74,10 +74,5 @@ void ahrs_update_heading(float heading); */ void ahrs_realign_heading(float heading); -#ifdef AHRS_UPDATE_FW_ESTIMATOR -extern float ins_roll_neutral; -extern float ins_pitch_neutral; -#endif - #endif /* AHRS_FLOAT_CMPL_RMAT */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c index f1a8b86f03d..8a5352fe6d3 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c +++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.c @@ -58,17 +58,6 @@ #define AHRS_PROPAGATE_FREQUENCY PERIODIC_FREQUENCY #endif -// FIXME this is still needed for fixedwing integration -// remotely settable -#ifndef INS_ROLL_NEUTRAL_DEFAULT -#define INS_ROLL_NEUTRAL_DEFAULT 0 -#endif -#ifndef INS_PITCH_NEUTRAL_DEFAULT -#define INS_PITCH_NEUTRAL_DEFAULT 0 -#endif -float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; -float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; - struct AhrsFloatDCM ahrs_impl; @@ -538,15 +527,7 @@ static inline void set_body_orientation_and_rates(void) { FLOAT_RMAT_OF_EULERS(ltp_to_imu_rmat, ahrs_impl.ltp_to_imu_euler); FLOAT_RMAT_COMP_INV(ltp_to_body_rmat, ltp_to_imu_rmat, *body_to_imu_rmat); - // Some stupid lines of code for neutrals - struct FloatEulers ltp_to_body_euler; - FLOAT_EULERS_OF_RMAT(ltp_to_body_euler, ltp_to_body_rmat); - ltp_to_body_euler.phi -= ins_roll_neutral; - ltp_to_body_euler.theta -= ins_pitch_neutral; - stateSetNedToBodyEulers_f(<p_to_body_euler); - - // should be replaced at the end by: - // stateSetNedToBodyRMat_f(<p_to_body_rmat); + stateSetNedToBodyRMat_f(<p_to_body_rmat); } diff --git a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h index 7b1f9f0e50c..d761f08dc2b 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h +++ b/sw/airborne/subsystems/ahrs/ahrs_float_dcm.h @@ -43,11 +43,6 @@ struct AhrsFloatDCM { extern struct AhrsFloatDCM ahrs_impl; -// FIXME neutrals should be a feature of state interface ? -extern float ins_roll_neutral; -extern float ins_pitch_neutral; - - // DCM Parameters //#define Kp_ROLLPITCH 0.2 diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.c b/sw/airborne/subsystems/ahrs/ahrs_gx3.c index 275e1dcec62..b3580239e2a 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_gx3.c +++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.c @@ -31,17 +31,6 @@ */ #include "subsystems/ahrs/ahrs_gx3.h" -#ifdef AHRS_UPDATE_FW_ESTIMATOR -// remotely settable -#ifndef INS_ROLL_NEUTRAL_DEFAULT -#define INS_ROLL_NEUTRAL_DEFAULT 0 -#endif -#ifndef INS_PITCH_NEUTRAL_DEFAULT -#define INS_PITCH_NEUTRAL_DEFAULT 0 -#endif -float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; -float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; -#endif #define GX3_CHKSM(_ubx_payload) (uint16_t)((uint16_t)(*((uint8_t*)_ubx_payload+66+1))|(uint16_t)(*((uint8_t*)_ubx_payload+66+0))<<8) @@ -266,29 +255,26 @@ void gx3_packet_read_message(void) { // Attitude struct FloatRMat ltp_to_body_rmat; FLOAT_RMAT_COMP(ltp_to_body_rmat, ahrs_impl.gx3_rmat, *body_to_imu_rmat); -#ifdef AHRS_UPDATE_FW_ESTIMATOR // fixedwing + +#if AHRS_USE_GPS_HEADING && USE_GPS struct FloatEulers ltp_to_body_eulers; FLOAT_EULERS_OF_RMAT(ltp_to_body_eulers, ltp_to_body_rmat); - ltp_to_body_eulers.phi -= ins_roll_neutral; - ltp_to_body_eulers.theta -= ins_pitch_neutral; -#if AHRS_USE_GPS_HEADING && USE_GPS float course_f = (float)DegOfRad(gps.course / 1e7); if (course_f > 180.0) { course_f -= 360.0; } ltp_to_body_eulers.psi = (float)RadOfDeg(course_f); -#endif stateSetNedToBodyEulers_f(<p_to_body_eulers); -#else -#ifdef IMU_MAG_OFFSET //rotorcraft +#else // !AHRS_USE_GPS_HEADING +#ifdef IMU_MAG_OFFSET struct FloatEulers ltp_to_body_eulers; FLOAT_EULERS_OF_RMAT(ltp_to_body_eulers, ltp_to_body_rmat); ltp_to_body_eulers.psi -= ahrs_impl.mag_offset; stateSetNedToBodyEulers_f(<p_to_body_eulers); #else stateSetNedToBodyRMat_f(<p_to_body_rmat); -#endif -#endif +#endif // IMU_MAG_OFFSET +#endif // !AHRS_USE_GPS_HEADING } diff --git a/sw/airborne/subsystems/ahrs/ahrs_gx3.h b/sw/airborne/subsystems/ahrs/ahrs_gx3.h index cf2c464f218..25c79e585e8 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_gx3.h +++ b/sw/airborne/subsystems/ahrs/ahrs_gx3.h @@ -123,9 +123,4 @@ static inline void ImuEvent(void (* _gyro_handler)(void), void (* _accel_handler } } -#ifdef AHRS_UPDATE_FW_ESTIMATOR -extern float ins_roll_neutral; -extern float ins_pitch_neutral; -#endif - #endif /* AHRS_GX3_H*/ diff --git a/sw/airborne/subsystems/ahrs/ahrs_infrared.h b/sw/airborne/subsystems/ahrs/ahrs_infrared.h index 0ff3cd83f24..fddea4cfaef 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_infrared.h +++ b/sw/airborne/subsystems/ahrs/ahrs_infrared.h @@ -32,14 +32,6 @@ #include "subsystems/ahrs.h" #include "std.h" -/** - * @todo harmonize infrared neutrals with ins_neutrals - * or get rid of ins neutrals - * this ins only needed for sim right now - */ -extern float ins_roll_neutral; -extern float ins_pitch_neutral; - extern void ahrs_update_infrared(void); #endif /* AHRS_INFRARED_H */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c index b486ed31614..b304266e9a2 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.c @@ -46,19 +46,6 @@ #define AHRS_MAG_OFFSET 0. #endif -#ifdef AHRS_UPDATE_FW_ESTIMATOR -// remotely settable (for FW) -#ifndef INS_ROLL_NEUTRAL_DEFAULT -#define INS_ROLL_NEUTRAL_DEFAULT 0 -#endif -#ifndef INS_PITCH_NEUTRAL_DEFAULT -#define INS_PITCH_NEUTRAL_DEFAULT 0 -#endif -float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; -float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; -#endif - - struct AhrsIntCmplEuler ahrs_impl; static inline void get_phi_theta_measurement_fom_accel(int32_t* phi_meas, int32_t* theta_meas, struct Int32Vect3 accel); @@ -329,15 +316,7 @@ static void set_body_state_from_euler(void) { /* Compute LTP to BODY rotation matrix */ INT32_RMAT_COMP_INV(ltp_to_body_rmat, ltp_to_imu_rmat, *body_to_imu_rmat); /* Set state */ -#ifdef AHRS_UPDATE_FW_ESTIMATOR - struct Int32Eulers ltp_to_body_euler; - INT32_EULERS_OF_RMAT(ltp_to_body_euler, ltp_to_body_rmat); - ltp_to_body_euler.phi -= ANGLE_BFP_OF_REAL(ins_roll_neutral); - ltp_to_body_euler.theta -= ANGLE_BFP_OF_REAL(ins_pitch_neutral); - stateSetNedToBodyEulers_i(<p_to_body_euler); -#else stateSetNedToBodyRMat_i(<p_to_body_rmat); -#endif struct Int32Rates body_rate; /* compute body rates */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h index 8ad70b21473..d410bbe69a3 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_euler.h @@ -49,9 +49,4 @@ struct AhrsIntCmplEuler { extern struct AhrsIntCmplEuler ahrs_impl; -#ifdef AHRS_UPDATE_FW_ESTIMATOR -extern float ins_roll_neutral; -extern float ins_pitch_neutral; -#endif - #endif /* AHRS_INT_CMPL_EULER_H */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c index e322002d317..acd51dca180 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.c @@ -127,18 +127,6 @@ PRINT_CONFIG_VAR(AHRS_MAG_ZETA) #define AHRS_HEADING_UPDATE_GPS_MIN_SPEED 5.0 #endif -#ifdef AHRS_UPDATE_FW_ESTIMATOR -// remotely settable -#ifndef INS_ROLL_NEUTRAL_DEFAULT -#define INS_ROLL_NEUTRAL_DEFAULT 0 -#endif -#ifndef INS_PITCH_NEUTRAL_DEFAULT -#define INS_PITCH_NEUTRAL_DEFAULT 0 -#endif -float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; -float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; -#endif - struct AhrsIntCmplQuat ahrs_impl; static inline void set_body_state_from_quat(void); @@ -698,19 +686,7 @@ static inline void set_body_state_from_quat(void) { struct Int32Quat *body_to_imu_quat = orientationGetQuat_i(&imu.body_to_imu); INT32_QUAT_COMP_INV(ltp_to_body_quat, ahrs_impl.ltp_to_imu_quat, *body_to_imu_quat); /* Set state */ -#ifdef AHRS_UPDATE_FW_ESTIMATOR - struct Int32Eulers neutrals_to_body_eulers = { - ANGLE_BFP_OF_REAL(ins_roll_neutral), - ANGLE_BFP_OF_REAL(ins_pitch_neutral), - 0 }; - struct Int32Quat neutrals_to_body_quat, ltp_to_neutrals_quat; - INT32_QUAT_OF_EULERS(neutrals_to_body_quat, neutrals_to_body_eulers); - INT32_QUAT_NORMALIZE(neutrals_to_body_quat); - INT32_QUAT_COMP_INV(ltp_to_neutrals_quat, ltp_to_body_quat, neutrals_to_body_quat); - stateSetNedToBodyQuat_i(<p_to_neutrals_quat); -#else stateSetNedToBodyQuat_i(<p_to_body_quat); -#endif /* compute body rates */ struct Int32Rates body_rate; diff --git a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h index e7c5fbce6d0..ae3c15eaea5 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h +++ b/sw/airborne/subsystems/ahrs/ahrs_int_cmpl_quat.h @@ -132,9 +132,4 @@ static inline void ahrs_int_cmpl_quat_SetMagZeta(float zeta) { } -#ifdef AHRS_UPDATE_FW_ESTIMATOR -extern float ins_roll_neutral; -extern float ins_pitch_neutral; -#endif - #endif /* AHRS_INT_CMPL_QUAT_H */ diff --git a/sw/airborne/subsystems/ahrs/ahrs_sim.c b/sw/airborne/subsystems/ahrs/ahrs_sim.c index 5c1d5c726f9..7d8a10aec44 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_sim.c +++ b/sw/airborne/subsystems/ahrs/ahrs_sim.c @@ -39,8 +39,7 @@ extern float sim_q; extern float sim_r; extern bool_t ahrs_sim_available; -#ifdef AHRS_UPDATE_FW_ESTIMATOR -// remotely settable +// for sim of e.g. Xsens ins #ifndef INS_ROLL_NEUTRAL_DEFAULT #define INS_ROLL_NEUTRAL_DEFAULT 0 #endif @@ -49,15 +48,11 @@ extern bool_t ahrs_sim_available; #endif float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; -#endif //AHRS_UPDATE_FW_ESTIMATOR + void update_ahrs_from_sim(void) { struct FloatEulers ltp_to_imu_euler = { sim_phi, sim_theta, sim_psi }; -#ifdef AHRS_UPDATE_FW_ESTIMATOR - ltp_to_imu_euler.phi -= ins_roll_neutral; - ltp_to_imu_euler.theta -= ins_pitch_neutral; -#endif struct FloatRates imu_rate = { sim_p, sim_q, sim_r }; /* set ltp_to_body to same as ltp_to_imu, currently no difference simulated */ stateSetNedToBodyEulers_f(<p_to_imu_euler); diff --git a/sw/airborne/subsystems/ahrs/ahrs_sim.h b/sw/airborne/subsystems/ahrs/ahrs_sim.h index 0a79b17d419..ad5ff605469 100644 --- a/sw/airborne/subsystems/ahrs/ahrs_sim.h +++ b/sw/airborne/subsystems/ahrs/ahrs_sim.h @@ -34,10 +34,8 @@ extern bool_t ahrs_sim_available; -#ifdef AHRS_UPDATE_FW_ESTIMATOR extern float ins_roll_neutral; extern float ins_pitch_neutral; -#endif extern void update_ahrs_from_sim(void); diff --git a/sw/airborne/subsystems/ins/ins_float_invariant.c b/sw/airborne/subsystems/ins/ins_float_invariant.c index 7d5c541621c..d86e425b700 100644 --- a/sw/airborne/subsystems/ins/ins_float_invariant.c +++ b/sw/airborne/subsystems/ins/ins_float_invariant.c @@ -158,19 +158,6 @@ bool_t log_started = FALSE; #endif -// FIXME this is still needed for fixedwing integration -#if INS_UPDATE_FW_ESTIMATOR -// remotely settable -#ifndef INS_ROLL_NEUTRAL_DEFAULT -#define INS_ROLL_NEUTRAL_DEFAULT 0. -#endif -#ifndef INS_PITCH_NEUTRAL_DEFAULT -#define INS_PITCH_NEUTRAL_DEFAULT 0. -#endif -float ins_roll_neutral = INS_ROLL_NEUTRAL_DEFAULT; -float ins_pitch_neutral = INS_PITCH_NEUTRAL_DEFAULT; -#endif - struct InsFloatInv ins_impl; /* integration time step */ @@ -380,18 +367,7 @@ void ahrs_propagate(void) { FLOAT_QUAT_NORMALIZE(ins_impl.state.quat); // set global state -#if INS_UPDATE_FW_ESTIMATOR || SEND_INVARIANT_FILTER - struct FloatEulers eulers; - FLOAT_EULERS_OF_QUAT(eulers, ins_impl.state.quat); -#endif -#if INS_UPDATE_FW_ESTIMATOR - // Some stupid lines of code for neutrals - eulers.phi -= ins_roll_neutral; - eulers.theta -= ins_pitch_neutral; - stateSetNedToBodyEulers_f(&eulers); -#else stateSetNedToBodyQuat_f(&ins_impl.state.quat); -#endif RATES_DIFF(body_rates, ins_impl.cmd.rates, ins_impl.state.bias); stateSetBodyRates_f(&body_rates); stateSetPositionNed_f(&ins_impl.state.pos); @@ -405,6 +381,8 @@ void ahrs_propagate(void) { //------------------------------------------------------------// #if SEND_INVARIANT_FILTER + struct FloatEulers eulers; + FLOAT_EULERS_OF_QUAT(eulers, ins_impl.state.quat); RunOnceEvery(3,{ DOWNLINK_SEND_INV_FILTER(DefaultChannel, DefaultDevice, &ins_impl.state.quat.qi, diff --git a/sw/airborne/subsystems/ins/ins_float_invariant.h b/sw/airborne/subsystems/ins/ins_float_invariant.h index eaebf1529ec..61ee8e55b42 100644 --- a/sw/airborne/subsystems/ins/ins_float_invariant.h +++ b/sw/airborne/subsystems/ins/ins_float_invariant.h @@ -113,8 +113,5 @@ struct InsFloatInv { extern struct InsFloatInv ins_impl; -extern float ins_roll_neutral; -extern float ins_pitch_neutral; - #endif /* INS_FLOAT_INVARIANT_H */