mirror of https://github.com/ArduPilot/ardupilot
TradHeli: Move two static bools into heli_flags structure to save 2 bytes RAM.
This commit is contained in:
parent
4b9aea2c55
commit
022425584b
|
@ -14,7 +14,8 @@ ModeFilterInt16_Size5 rotor_speed_deglitch_filter(4);
|
|||
|
||||
// Tradheli flags
|
||||
static 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 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
|
||||
} heli_flags;
|
||||
|
||||
#endif // FRAME_CONFIG == HELI_FRAME
|
||||
|
|
|
@ -16,7 +16,6 @@ static bool heli_acro_init(bool ignore_checks)
|
|||
static void heli_acro_run()
|
||||
{
|
||||
float target_roll, target_pitch, target_yaw;
|
||||
static bool init_targets_on_arming;
|
||||
|
||||
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
|
||||
// we may be in autorotation flight. These should be reset only when transitioning from disarmed
|
||||
|
@ -25,12 +24,12 @@ static void heli_acro_run()
|
|||
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
||||
|
||||
if(!motors.armed()) {
|
||||
init_targets_on_arming=true;
|
||||
heli_flags.init_targets_on_arming=true;
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
}
|
||||
|
||||
if(motors.armed() && init_targets_on_arming) {
|
||||
init_targets_on_arming=false;
|
||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
|
||||
}
|
||||
|
|
|
@ -20,7 +20,6 @@ static void heli_stabilize_run()
|
|||
int16_t target_roll, target_pitch;
|
||||
float target_yaw_rate;
|
||||
int16_t pilot_throttle_scaled;
|
||||
static bool init_targets_on_arming;
|
||||
|
||||
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
|
||||
// we may be in autorotation flight. These should be reset only when transitioning from disarmed
|
||||
|
@ -29,12 +28,12 @@ static void heli_stabilize_run()
|
|||
// Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
|
||||
|
||||
if(!motors.armed()) {
|
||||
init_targets_on_arming=true;
|
||||
heli_flags.init_targets_on_arming=true;
|
||||
attitude_control.set_yaw_target_to_current_heading();
|
||||
}
|
||||
|
||||
if(motors.armed() && init_targets_on_arming) {
|
||||
init_targets_on_arming=false;
|
||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||
heli_flags.init_targets_on_arming=false;
|
||||
attitude_control.relax_bf_rate_controller();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue