diff --git a/sw/airborne/firmwares/fixedwing/autopilot.h b/sw/airborne/firmwares/fixedwing/autopilot.h index a7ae8e0d64..7e81247790 100644 --- a/sw/airborne/firmwares/fixedwing/autopilot.h +++ b/sw/airborne/firmwares/fixedwing/autopilot.h @@ -135,8 +135,4 @@ extern bool_t power_switch; #define NAVIGATION_FREQUENCY 4 #endif -#ifndef MODULES_FREQUENCY -#define MODULES_FREQUENCY 60 -#endif - #endif /* AUTOPILOT_H */ diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index e4fb19b0cd..2d46edf2d1 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -85,6 +85,16 @@ #include "gpio.h" #include "led.h" +/* if PRINT_CONFIG is defined, print some config options */ +PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) +PRINT_CONFIG_VAR(NAVIGATION_FREQUENCY) +PRINT_CONFIG_VAR(CONTROL_FREQUENCY) + +#ifndef MODULES_FREQUENCY +#define MODULES_FREQUENCY 60 +#endif +PRINT_CONFIG_VAR(MODULES_FREQUENCY) + #if USE_AHRS && USE_IMU diff --git a/sw/airborne/firmwares/rotorcraft/main.c b/sw/airborne/firmwares/rotorcraft/main.c index f0ee27496f..b76ad5ca98 100644 --- a/sw/airborne/firmwares/rotorcraft/main.c +++ b/sw/airborne/firmwares/rotorcraft/main.c @@ -71,9 +71,20 @@ #include "generated/modules.h" + +/* if PRINT_CONFIG is defined, print some config options */ +PRINT_CONFIG_VAR(PERIODIC_FREQUENCY) + +#ifndef MODULES_FREQUENCY +#define MODULES_FREQUENCY 512 +#endif +PRINT_CONFIG_VAR(MODULES_FREQUENCY) + #ifndef BARO_PERIODIC_FREQUENCY #define BARO_PERIODIC_FREQUENCY 50 #endif +PRINT_CONFIG_VAR(BARO_PERIODIC_FREQUENCY) + static inline void on_gyro_event( void ); static inline void on_accel_event( void ); @@ -84,6 +95,7 @@ static inline void on_mag_event( void ); tid_t main_periodic_tid; ///< id for main_periodic() timer +tid_t modules_tid; ///< id for modules_periodic_task() timer tid_t failsafe_tid; ///< id for failsafe_check() timer tid_t radio_control_tid; ///< id for radio_control_periodic_task() timer tid_t electrical_tid; ///< id for electrical_periodic() timer @@ -146,6 +158,7 @@ STATIC_INLINE void main_init( void ) { // register the timers for the periodic functions main_periodic_tid = sys_time_register_timer((1./PERIODIC_FREQUENCY), NULL); + modules_tid = sys_time_register_timer(1./MODULES_FREQUENCY, NULL); radio_control_tid = sys_time_register_timer((1./60.), NULL); failsafe_tid = sys_time_register_timer(0.05, NULL); electrical_tid = sys_time_register_timer(0.1, NULL); @@ -156,6 +169,8 @@ STATIC_INLINE void main_init( void ) { STATIC_INLINE void handle_periodic_tasks( void ) { if (sys_time_check_and_ack_timer(main_periodic_tid)) main_periodic(); + if (sys_time_check_and_ack_timer(modules_tid)) + modules_periodic_task(); if (sys_time_check_and_ack_timer(radio_control_tid)) radio_control_periodic_task(); if (sys_time_check_and_ack_timer(failsafe_tid)) @@ -178,8 +193,6 @@ STATIC_INLINE void main_periodic( void ) { //actuators_set(autopilot_motors_on); SetActuatorsFromCommands(commands); - modules_periodic_task(); - if (autopilot_in_flight) { RunOnceEvery(PERIODIC_FREQUENCY, { autopilot_flight_time++; datalink_time++; }); }