Skip to content

Commit

Permalink
Plane: Rearrange header to save flash
Browse files Browse the repository at this point in the history
Saves 392 bytes of flash on CubeBlack builds without increasing RAM
consumption at all. This also translates to a speed up as some of these
are looked up every loop multiple times.
  • Loading branch information
WickedShell authored and tridge committed Sep 9, 2019
1 parent b924731 commit cf58f68
Showing 1 changed file with 48 additions and 48 deletions.
96 changes: 48 additions & 48 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -356,13 +356,13 @@ class Plane : public AP_HAL::HAL::Callbacks {
struct {
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
// RC receiver should be set up to output a low throttle value when signal is lost
bool rc_failsafe:1;
bool rc_failsafe;

// has the saved mode for failsafe been set?
bool saved_mode_set:1;
bool saved_mode_set;

// true if an adsb related failsafe has occurred
bool adsb:1;
bool adsb;

// saved flight mode
enum Mode::Number saved_mode_number;
Expand Down Expand Up @@ -467,69 +467,33 @@ class Plane : public AP_HAL::HAL::Callbacks {
uint32_t accel_event_ms;
uint32_t start_time_ms;
} takeoff_state;

// ground steering controller state
struct {
// Direction held during phases of takeoff and landing centidegrees
// A value of -1 indicates the course has not been set/is not in use
// this is a 0..36000 value, or -1 for disabled
int32_t hold_course_cd;
int32_t hold_course_cd = -1;

// locked_course and locked_course_cd are used in stabilize mode
// when ground steering is active, and for steering in auto-takeoff
bool locked_course;
float locked_course_err;
} steer_state { -1, false, 0 };
} steer_state;

// flight mode specific
struct {
// Flag for using gps ground course instead of INS yaw. Set false when takeoff command in process.
bool takeoff_complete:1;

// are we headed to the land approach waypoint? Works for any nav type
bool wp_is_land_approach:1;

// should we fly inverted?
bool inverted_flight:1;

// should we enable cross-tracking for the next waypoint?
bool next_wp_crosstrack:1;

// should we use cross-tracking for this waypoint?
bool crosstrack:1;

// in FBWA taildragger takeoff mode
bool fbwa_tdrag_takeoff_mode:1;

// have we checked for an auto-land?
bool checked_for_autoland:1;

// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters
// are we in idle mode? used for balloon launch to stop servo
// movement until altitude is reached
bool idle_mode:1;

// used to 'wiggle' servos in idle mode to prevent them freezing
// at high altitudes
uint8_t idle_wiggle_stage;

// Altitude threshold to complete a takeoff command in autonomous
// modes. Centimeters above home
int32_t takeoff_altitude_rel_cm;

// Minimum pitch to hold during takeoff command execution. Hundredths of a degree
int16_t takeoff_pitch_cd;

// Begin leveling out the enforced takeoff pitch angle min at this height to reduce/eliminate overshoot
int32_t height_below_takeoff_to_level_off_cm;

// the highest airspeed we have reached since entering AUTO. Used
// to control ground takeoff
float highest_airspeed;

// initial pitch. Used to detect if nose is rising in a tail dragger
int16_t initial_pitch_cd;

// turn angle for next leg of mission
float next_turn_angle {90};

Expand All @@ -554,11 +518,47 @@ class Plane : public AP_HAL::HAL::Callbacks {
// barometric altitude at start of takeoff
float baro_takeoff_alt;

// initial pitch. Used to detect if nose is rising in a tail dragger
int16_t initial_pitch_cd;

// Minimum pitch to hold during takeoff command execution. Hundredths of a degree
int16_t takeoff_pitch_cd;

// used to 'wiggle' servos in idle mode to prevent them freezing
// at high altitudes
uint8_t idle_wiggle_stage;

// Flag for using gps ground course instead of INS yaw. Set false when takeoff command in process.
bool takeoff_complete;

// are we headed to the land approach waypoint? Works for any nav type
bool wp_is_land_approach;

// should we fly inverted?
bool inverted_flight;

// should we enable cross-tracking for the next waypoint?
bool next_wp_crosstrack;

// should we use cross-tracking for this waypoint?
bool crosstrack;

// in FBWA taildragger takeoff mode
bool fbwa_tdrag_takeoff_mode;

// have we checked for an auto-land?
bool checked_for_autoland;

// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters
// are we in idle mode? used for balloon launch to stop servo
// movement until altitude is reached
bool idle_mode;

// are we in VTOL mode in AUTO?
bool vtol_mode:1;
bool vtol_mode;

// are we doing loiter mode as a VTOL?
bool vtol_loiter:1;
bool vtol_loiter;
} auto_state;

struct {
Expand All @@ -583,13 +583,13 @@ class Plane : public AP_HAL::HAL::Callbacks {
struct {
// on hard landings, only check once after directly a landing so you
// don't trigger a crash when picking up the aircraft
bool checkedHardLanding:1;
bool checkedHardLanding;

// crash detection. True when we are crashed
bool is_crashed:1;
bool is_crashed;

// impact detection flag. Expires after a few seconds via impact_timer_ms
bool impact_detected:1;
bool impact_detected;

// debounce timer
uint32_t debounce_timer_ms;
Expand Down Expand Up @@ -771,7 +771,7 @@ class Plane : public AP_HAL::HAL::Callbacks {
uint32_t last_elev_check_us;
} target_altitude {};

float relative_altitude = 0.0f;
float relative_altitude;

// INS variables
// The main loop execution time. Seconds
Expand Down

0 comments on commit cf58f68

Please sign in to comment.