mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AC_AttitudeControl_Heli: Create Flybar Passthrough flag which will be used for control pass-through.
This commit is contained in:
parent
2d02d8d15f
commit
deaffecbf5
@ -47,10 +47,11 @@ private:
|
||||
|
||||
// To-Do: move these limits flags into the heli motors class
|
||||
struct AttControlHeliFlags {
|
||||
uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move
|
||||
uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move
|
||||
uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move
|
||||
uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
|
||||
uint8_t limit_roll : 1; // 1 if we have requested larger roll angle than swash can physically move
|
||||
uint8_t limit_pitch : 1; // 1 if we have requested larger pitch angle than swash can physically move
|
||||
uint8_t limit_yaw : 1; // 1 if we have requested larger yaw angle than tail servo can physically move
|
||||
uint8_t leaky_i : 1; // 1 if we should use leaky i term for body-frame rate to motor stage
|
||||
uint8_t flybar_passthrough : 1; // 1 if we should pass through pilots input directly to swash-plate
|
||||
} _flags_heli;
|
||||
|
||||
//
|
||||
|
Loading…
Reference in New Issue
Block a user