diff --git a/conf/conf_example.xml b/conf/conf_example.xml
index a7d50fdc1b..1c13c4c440 100644
--- a/conf/conf_example.xml
+++ b/conf/conf_example.xml
@@ -7,7 +7,7 @@
telemetry="telemetry/default_fixedwing_imu.xml"
flight_plan="flight_plans/versatile.xml"
settings="settings/fixedwing_basic.xml settings/nps.xml"
- settings_modules="modules/ahrs_float_dcm.xml modules/gps.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
+ settings_modules="modules/ahrs_float_dcm.xml modules/electrical.xml modules/gps.xml modules/gps_ublox.xml modules/guidance_basic_fw.xml modules/imu_common.xml modules/nav_basic_fw.xml modules/stabilization_attitude_fw.xml"
gui_color="blue"
/>
diff --git a/conf/conf_tests.xml b/conf/conf_tests.xml
index 3a9fbcbde3..85873b5332 100644
--- a/conf/conf_tests.xml
+++ b/conf/conf_tests.xml
@@ -84,7 +84,7 @@
telemetry="telemetry/default_rotorcraft_mavlink.xml"
flight_plan="flight_plans/rotorcraft_basic.xml"
settings="settings/rotorcraft_basic.xml settings/estimation/ahrs_secondary.xml"
- settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
+ settings_modules="modules/ahrs_float_mlkf.xml modules/ahrs_int_cmpl_quat.xml modules/air_data.xml modules/electrical.xml modules/geo_mag.xml modules/gps.xml modules/gps_ublox.xml modules/gps_ubx_ucenter.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="blue"
/>
diff --git a/conf/conf_tests_coverity.xml b/conf/conf_tests_coverity.xml
index d26ff838ae..7beae85f27 100644
--- a/conf/conf_tests_coverity.xml
+++ b/conf/conf_tests_coverity.xml
@@ -7,7 +7,7 @@
telemetry="telemetry/default_rotorcraft.xml"
flight_plan="flight_plans/rotorcraft_basic_geofence.xml"
settings="settings/rotorcraft_basic.xml settings/nps.xml"
- settings_modules="modules/battery_monitor.xml modules/gps.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_basic_rotorcraft.xml modules/stabilization_int_quat.xml"
+ settings_modules="modules/battery_monitor.xml modules/electrical.xml modules/gps.xml modules/guidance_pid_rotorcraft.xml modules/guidance_rotorcraft.xml modules/imu_common.xml modules/lidar_lite.xml modules/nav_rotorcraft.xml modules/stabilization_int_quat.xml"
gui_color="#ffff954c0000"
/>
diff --git a/sw/airborne/math/pprz_matrix_decomp_float.c b/sw/airborne/math/pprz_matrix_decomp_float.c
index 9907bff5db..f6c9d92b7f 100644
--- a/sw/airborne/math/pprz_matrix_decomp_float.c
+++ b/sw/airborne/math/pprz_matrix_decomp_float.c
@@ -167,7 +167,7 @@ static int imin(int num1, int num2) {
int pprz_svd_float(float **a, float *w, float **v, int m, int n)
{
/* Householder reduction to bidiagonal form. */
- int flag, i, its, j, jj, k, l, NM;
+ int flag, i, its, j, jj, k, l, NM = 0;
float C, F, H, S, X, Y, Z, tmp;
float G = 0.0;
float Scale = 0.0;
diff --git a/sw/airborne/modules/computer_vision/opticflow/linear_flow_fit.c b/sw/airborne/modules/computer_vision/opticflow/linear_flow_fit.c
index ba4e4afd03..0026b61766 100644
--- a/sw/airborne/modules/computer_vision/opticflow/linear_flow_fit.c
+++ b/sw/airborne/modules/computer_vision/opticflow/linear_flow_fit.c
@@ -396,8 +396,8 @@ void extract_information_from_parameters(float *parameters_u, float *parameters_
* @param[in] focal_length Focal length in pixels
* @param[out] info Contains all info extracted from the linear flow fit.
*/
-bool analyze_flow_field(struct flow_t *vectors, int count, float error_threshold, int n_iterations, int n_samples,
- int im_width, int im_height, float focal_length, struct linear_flow_fit_info *info)
+bool analyze_flow_field(struct flow_t *vectors __attribute__((unused)), int count, float error_threshold __attribute__((unused)), int n_iterations __attribute__((unused)), int n_samples __attribute__((unused)),
+ int im_width __attribute__((unused)), int im_height __attribute__((unused)), float focal_length __attribute__((unused)), struct linear_flow_fit_info *info __attribute__((unused)))
{
// Are there enough flow vectors to perform a fit?
if (count < N_PAR_TR_FIT) {
diff --git a/sw/airborne/modules/imu/imu_mpu9250.c b/sw/airborne/modules/imu/imu_mpu9250.c
index c245be3033..899848e1e6 100644
--- a/sw/airborne/modules/imu/imu_mpu9250.c
+++ b/sw/airborne/modules/imu/imu_mpu9250.c
@@ -63,14 +63,14 @@ void imu_mpu9250_report(void)
(int32_t)(mpu9250.data_accel.vect.y),
(int32_t)(mpu9250.data_accel.vect.z)
};
- DOWNLINK_SEND_IMU_ACCEL_RAW(DefaultChannel, DefaultDevice, &id, &accel.x, &accel.y, &accel.z, &temp);
+ DOWNLINK_SEND_IMU_ACCEL_RAW(DefaultChannel, DefaultDevice, &id, &temp, &accel.x, &accel.y, &accel.z);
struct Int32Rates rates = {
(int32_t)(mpu9250.data_rates.rates.p),
(int32_t)(mpu9250.data_rates.rates.q),
(int32_t)(mpu9250.data_rates.rates.r)
};
- DOWNLINK_SEND_IMU_GYRO_RAW(DefaultChannel, DefaultDevice, &id, &rates.p, &rates.q, &rates.r, &temp);
+ DOWNLINK_SEND_IMU_GYRO_RAW(DefaultChannel, DefaultDevice, &id, &temp, &rates.p, &rates.q, &rates.r);
struct Int32Vect3 mag = {
(int32_t)(mpu9250.akm.data.vect.x),
diff --git a/sw/airborne/modules/nav/nav_survey_hybrid.c b/sw/airborne/modules/nav/nav_survey_hybrid.c
index 473cf1cbb1..58df49cd10 100644
--- a/sw/airborne/modules/nav/nav_survey_hybrid.c
+++ b/sw/airborne/modules/nav/nav_survey_hybrid.c
@@ -29,6 +29,7 @@
#include "modules/nav/nav_survey_hybrid.h"
#include "firmwares/rotorcraft/navigation.h"
+#include "modules/nav/nav_rotorcraft_base.h"
#include "math/pprz_algebra_float.h"
#include "state.h"
#include "autopilot.h"
diff --git a/sw/airborne/test/modules/test_radio_control.c b/sw/airborne/test/modules/test_radio_control.c
index c996c6eabe..8fac6ced7f 100644
--- a/sw/airborne/test/modules/test_radio_control.c
+++ b/sw/airborne/test/modules/test_radio_control.c
@@ -30,7 +30,7 @@
static inline void main_init(void);
static inline void main_periodic_task(void);
static inline void main_event_task(void);
-static void main_on_radio_control_frame(void);
+//static void main_on_radio_control_frame(void);
int main(void)
{
@@ -91,9 +91,9 @@ static inline void main_event_task(void)
//RadioControlEvent(main_on_radio_control_frame); FIXME
}
-static void main_on_radio_control_frame(void)
+/*static void main_on_radio_control_frame(void)
{
- // RunOnceEvery(10, {DOWNLINK_SEND_RC(RADIO_CONTROL_NB_CHANNEL, radio_control.values);});
+ RunOnceEvery(10, {DOWNLINK_SEND_RC(RADIO_CONTROL_NB_CHANNEL, radio_control.values);});
-}
+}*/