From f81d00594c156c51ab976d3b6d101915377d7afa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Dec 2012 23:28:03 +0100 Subject: Made PX4IO FMU timeout based on IOs HRT, updating mixers now on every FMU update and not at fixed rate, this is WIP and currently does not support mixing with RC-only --- apps/px4io/controls.c | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) (limited to 'apps/px4io/controls.c') diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index 9db9a0fa5..4bd6fe1a0 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -61,8 +61,8 @@ #include "px4io.h" #define RC_FAILSAFE_TIMEOUT 2000000 /**< two seconds failsafe timeout */ -#define RC_CHANNEL_HIGH_THRESH 1600 -#define RC_CHANNEL_LOW_THRESH 1400 +#define RC_CHANNEL_HIGH_THRESH 1700 +#define RC_CHANNEL_LOW_THRESH 1300 static void ppm_input(void); @@ -133,8 +133,7 @@ controls_main(void) system_state.fmu_report_due = true; } - /* do PWM output updates */ - mixer_tick(); + /* PWM output updates are performed directly on each comms update */ } } -- cgit v1.2.3