Copter: pass heli_flags into flightmode constructor

This commit is contained in:
Peter Barker 2017-11-10 12:09:27 +11:00 committed by Randy Mackay
parent 83d0a71e10
commit 477ae8f7be
2 changed files with 7 additions and 3 deletions

View File

@ -597,11 +597,12 @@ private:
ModeFilterInt16_Size5 rotor_speed_deglitch_filter {4};
// Tradheli flags
struct {
typedef struct {
uint8_t dynamic_flight : 1; // 0 // true if we are moving at a significant speed (used to turn on/off leaky I terms)
uint8_t init_targets_on_arming : 1; // 1 // true if we have been disarmed, and need to reset rate controller targets when we arm
uint8_t inverted_flight : 1; // 2 // true for inverted flight mode
} heli_flags;
} heli_flags_t;
heli_flags_t heli_flags;
int16_t hover_roll_trim_scalar_slew;
#endif

View File

@ -27,7 +27,8 @@ public:
takeoff_state(_copter.takeoff_state),
ekfGndSpdLimit(_copter.ekfGndSpdLimit),
ekfNavVelGainScaler(_copter.ekfNavVelGainScaler),
auto_yaw_mode(_copter.auto_yaw_mode)
auto_yaw_mode(_copter.auto_yaw_mode),
heli_flags(_copter.heli_flags)
{ };
protected:
@ -76,6 +77,8 @@ protected:
// auto flight mode's yaw mode
uint8_t &auto_yaw_mode;
heli_flags_t &heli_flags;
// pass-through functions to reduce code churn on conversion;
// these are candidates for moving into the FlightMode base
// class.