mirror of
https://github.com/okalachev/flix.git
synced 2025-07-27 09:39:33 +00:00
Move controlsTime variable to rc.ino
This commit is contained in:
parent
7bf5ee330b
commit
9e4a2c5ffc
@ -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() {
|
||||
|
@ -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
|
||||
|
@ -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() {
|
||||
|
@ -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];
|
||||
|
||||
|
@ -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;
|
||||
|
Loading…
x
Reference in New Issue
Block a user