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:
@@ -71,11 +71,7 @@ public:
|
||||
gyro = Vector(imu->AngularVelocity().X(), imu->AngularVelocity().Y(), imu->AngularVelocity().Z());
|
||||
acc = this->accFilter.update(Vector(imu->LinearAcceleration().X(), imu->LinearAcceleration().Y(), imu->LinearAcceleration().Z()));
|
||||
|
||||
// read rc
|
||||
readRC();
|
||||
controls[modeChannel] = 1; // 0 acro, 1 stab
|
||||
controls[armedChannel] = 1; // armed
|
||||
|
||||
estimate();
|
||||
|
||||
// correct yaw to the actual yaw
|
||||
|
Reference in New Issue
Block a user