diff --git a/flix/failsafe.ino b/flix/failsafe.ino index be36551..d554941 100644 --- a/flix/failsafe.ino +++ b/flix/failsafe.ino @@ -6,6 +6,7 @@ #define RC_LOSS_TIMEOUT 0.2 #define DESCEND_TIME 3.0 // time to descend from full throttle to zero +extern float controlsTime; extern int rollChannel, pitchChannel, throttleChannel, yawChannel; void failsafe() { diff --git a/flix/flix.ino b/flix/flix.ino index b1baa23..7e55c43 100644 --- a/flix/flix.ino +++ b/flix/flix.ino @@ -14,7 +14,6 @@ float t = NAN; // current step time, s float dt; // time delta from previous step, s int16_t channels[16]; // raw rc channels float controls[16]; // normalized controls in range [-1..1] ([0..1] for throttle) -float controlsTime; // time of the last controls update Vector gyro; // gyroscope data Vector acc; // accelerometer data, m/s/s Vector rates; // filtered angular rates, rad/s diff --git a/flix/mavlink.ino b/flix/mavlink.ino index 46e13f8..d09f0e8 100644 --- a/flix/mavlink.ino +++ b/flix/mavlink.ino @@ -13,6 +13,7 @@ #define MAVLINK_CONTROL_SCALE 0.7f #define MAVLINK_CONTROL_YAW_DEAD_ZONE 0.1f +extern float controlsTime; extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; void processMavlink() { diff --git a/flix/rc.ino b/flix/rc.ino index 48f5827..91dec8a 100644 --- a/flix/rc.ino +++ b/flix/rc.ino @@ -14,6 +14,7 @@ int yawChannel = 3; int armedChannel = 4; int modeChannel = 5; +float controlsTime; // time of the last controls update float channelNeutral[16] = {NAN}; // first element NAN means not calibrated float channelMax[16]; diff --git a/gazebo/flix.h b/gazebo/flix.h index c457d07..918aabe 100644 --- a/gazebo/flix.h +++ b/gazebo/flix.h @@ -18,7 +18,6 @@ float dt; float motors[4]; int16_t channels[16]; // raw rc channels float controls[16]; -float controlsTime; Vector acc; Vector gyro; Vector rates;