mirror of
https://github.com/okalachev/flix.git
synced 2025-08-17 17:16:10 +00:00
Major rework of rc subsystem
Implement channels mapping calibration. Store mapping in parameters. Get rid of `controls` array and store control inputs in `controlRoll`, `controlPitch`, ... variables. Move `channels` variable to rc.ino, channels are not involved when controled using mavlink. 'Neutral' values are renamed to 'zero' - more precise naming. `controlsTime` is renamed to `controlTime`. Use unsigned values for channels. Make channel values in simulation more alike to real world: unsigned values in range [1000, 2000]. Send RC_CHANNELS_RAW instead of RC_CHANNELS_SCALED via mavlink Don't send channels data via mavlink if rc is not used
This commit is contained in:
@@ -15,8 +15,7 @@
|
||||
double t = NAN;
|
||||
float dt;
|
||||
float motors[4];
|
||||
int16_t channels[16]; // raw rc channels
|
||||
float controls[16];
|
||||
float controlRoll, controlPitch, controlYaw, controlThrottle, controlArmed, controlMode;
|
||||
Vector acc;
|
||||
Vector gyro;
|
||||
Vector rates;
|
||||
@@ -41,9 +40,10 @@ void print(const char* format, ...);
|
||||
void pause(float duration);
|
||||
void doCommand(String str, bool echo);
|
||||
void handleInput();
|
||||
void calibrateRC();
|
||||
void normalizeRC();
|
||||
void printRCCal();
|
||||
void calibrateRC();
|
||||
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
|
||||
void printRCCalibration();
|
||||
void dumpLog();
|
||||
void processMavlink();
|
||||
void sendMavlink();
|
||||
|
Reference in New Issue
Block a user