mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 17:25:18 +03:00
Fixed compile errors
This commit is contained in:
parent
4b2095f3c0
commit
10931fe10d
2 changed files with 30 additions and 30 deletions
|
@ -106,13 +106,13 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
||||||
.extra_arming_safety = SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT,
|
.extra_arming_safety = SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT,
|
||||||
.user_control_mode = SETTING_NAV_USER_CONTROL_MODE_DEFAULT,
|
.user_control_mode = SETTING_NAV_USER_CONTROL_MODE_DEFAULT,
|
||||||
.rth_alt_control_mode = SETTING_NAV_RTH_ALT_MODE_DEFAULT,
|
.rth_alt_control_mode = SETTING_NAV_RTH_ALT_MODE_DEFAULT,
|
||||||
.rth_climb_first = SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT, // Climb first, turn after reaching safe altitude
|
.rth_climb_first = SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT, // Climb first, turn after reaching safe altitude
|
||||||
.rth_climb_first_stage_mode = SETTING_NAV_CLIMB_FIRST_STAGE_TYPE_DEFAULT, // To determine how rth_climb_first_stage_altitude is used
|
.rth_climb_first_stage_mode = SETTING_NAV_RTH_CLIMB_FIRST_STAGE_MODE_DEFAULT, // To determine how rth_climb_first_stage_altitude is used
|
||||||
.rth_climb_ignore_emerg = SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT, // Ignore GPS loss on initial climb
|
.rth_climb_ignore_emerg = SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT, // Ignore GPS loss on initial climb
|
||||||
.rth_tail_first = SETTING_NAV_RTH_TAIL_FIRST_DEFAULT,
|
.rth_tail_first = SETTING_NAV_RTH_TAIL_FIRST_DEFAULT,
|
||||||
.disarm_on_landing = SETTING_NAV_DISARM_ON_LANDING_DEFAULT,
|
.disarm_on_landing = SETTING_NAV_DISARM_ON_LANDING_DEFAULT,
|
||||||
.rth_allow_landing = SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT,
|
.rth_allow_landing = SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT,
|
||||||
.rth_alt_control_override = SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_DEFAULT, // Override RTH Altitude and Climb First using Pitch and Roll stick
|
.rth_alt_control_override = SETTING_NAV_RTH_ALT_CONTROL_OVERRIDE_DEFAULT, // Override RTH Altitude and Climb First using Pitch and Roll stick
|
||||||
.nav_overrides_motor_stop = SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT,
|
.nav_overrides_motor_stop = SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT,
|
||||||
.safehome_usage_mode = SETTING_SAFEHOME_USAGE_MODE_DEFAULT,
|
.safehome_usage_mode = SETTING_SAFEHOME_USAGE_MODE_DEFAULT,
|
||||||
},
|
},
|
||||||
|
@ -134,7 +134,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
||||||
.min_rth_distance = SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT, // centimeters, if closer than this land immediately
|
.min_rth_distance = SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT, // centimeters, if closer than this land immediately
|
||||||
.rth_altitude = SETTING_NAV_RTH_ALTITUDE_DEFAULT, // altitude in centimeters
|
.rth_altitude = SETTING_NAV_RTH_ALTITUDE_DEFAULT, // altitude in centimeters
|
||||||
.rth_home_altitude = SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT, // altitude in centimeters
|
.rth_home_altitude = SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT, // altitude in centimeters
|
||||||
.rth_climb_first_stage_altitude = SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_DEFAULT // altitude in centimetres, 0= off
|
.rth_climb_first_stage_altitude = SETTING_NAV_RTH_CLIMB_FIRST_STAGE_ALTITUDE_DEFAULT, // altitude in centimetres, 0= off
|
||||||
.rth_abort_threshold = SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT, // centimeters - 500m should be safe for all aircraft
|
.rth_abort_threshold = SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT, // centimeters - 500m should be safe for all aircraft
|
||||||
.max_terrain_follow_altitude = SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT, // max altitude in centimeters in terrain following mode
|
.max_terrain_follow_altitude = SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT, // max altitude in centimeters in terrain following mode
|
||||||
.safehome_max_distance = SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT, // Max distance that a safehome is from the arming point
|
.safehome_max_distance = SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT, // Max distance that a safehome is from the arming point
|
||||||
|
@ -2460,15 +2460,15 @@ static bool rthAltControlStickOverrideCheck(unsigned axis)
|
||||||
* Limited to fixed wing only.
|
* Limited to fixed wing only.
|
||||||
* --------------------------------------------------- */
|
* --------------------------------------------------- */
|
||||||
bool rthClimbStageActiveAndComplete() {
|
bool rthClimbStageActiveAndComplete() {
|
||||||
if ((STATE(FIXED_WING_LEGACY) || STATE(AIRPLANE)) && (general.rth_climb_first_stage_altitude > 0)) {
|
if ((STATE(FIXED_WING_LEGACY) || STATE(AIRPLANE)) && (navConfig()->general.rth_climb_first_stage_altitude > 0)) {
|
||||||
switch (navConfig()->general.flags.rth_climb_first_stage_mode) {
|
switch (navConfig()->general.flags.rth_climb_first_stage_mode) {
|
||||||
case NAV_RTH_CLIMB_STAGE_AT_LEAST:
|
case NAV_RTH_CLIMB_STAGE_AT_LEAST:
|
||||||
if (posControl.actualState.abs.pos.z >= general.rth_climb_first_stage_altitude) {
|
if (posControl.actualState.abs.pos.z >= navConfig()->general.rth_climb_first_stage_altitude) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case NAV_RTH_CLIMB_STAGE_EXTRA:
|
case NAV_RTH_CLIMB_STAGE_EXTRA:
|
||||||
if (posControl.actualState.abs.pos.z >= (posControl.rthState.rthInitialAltitude + general.rth_climb_first_stage_altitude)) {
|
if (posControl.actualState.abs.pos.z >= (posControl.rthState.rthInitialAltitude + navConfig()->general.rth_climb_first_stage_altitude)) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -197,7 +197,7 @@ typedef struct navConfig_s {
|
||||||
uint8_t user_control_mode; // NAV_GPS_ATTI or NAV_GPS_CRUISE
|
uint8_t user_control_mode; // NAV_GPS_ATTI or NAV_GPS_CRUISE
|
||||||
uint8_t rth_alt_control_mode; // Controls the logic for choosing the RTH altitude
|
uint8_t rth_alt_control_mode; // Controls the logic for choosing the RTH altitude
|
||||||
uint8_t rth_climb_first; // Controls the logic for initial RTH climbout
|
uint8_t rth_climb_first; // Controls the logic for initial RTH climbout
|
||||||
uint8_t rth_climb_first_stage_mode // To determine how rth_climb_first_stage_altitude is used
|
uint8_t rth_climb_first_stage_mode; // To determine how rth_climb_first_stage_altitude is used
|
||||||
uint8_t rth_tail_first; // Return to home tail first
|
uint8_t rth_tail_first; // Return to home tail first
|
||||||
uint8_t disarm_on_landing; //
|
uint8_t disarm_on_landing; //
|
||||||
uint8_t rth_allow_landing; // Enable landing as last stage of RTH. Use constants in navRTHAllowLanding_e.
|
uint8_t rth_allow_landing; // Enable landing as last stage of RTH. Use constants in navRTHAllowLanding_e.
|
||||||
|
@ -207,27 +207,27 @@ typedef struct navConfig_s {
|
||||||
uint8_t safehome_usage_mode; // Controls when safehomes are used
|
uint8_t safehome_usage_mode; // Controls when safehomes are used
|
||||||
} flags;
|
} flags;
|
||||||
|
|
||||||
uint8_t pos_failure_timeout; // Time to wait before switching to emergency landing (0 - disable)
|
uint8_t pos_failure_timeout; // Time to wait before switching to emergency landing (0 - disable)
|
||||||
uint16_t waypoint_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm)
|
uint16_t waypoint_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm)
|
||||||
uint16_t waypoint_safe_distance; // Waypoint mission sanity check distance
|
uint16_t waypoint_safe_distance; // Waypoint mission sanity check distance
|
||||||
bool waypoint_load_on_boot; // load waypoints automatically during boot
|
bool waypoint_load_on_boot; // load waypoints automatically during boot
|
||||||
uint16_t max_auto_speed; // autonomous navigation speed cm/sec
|
uint16_t max_auto_speed; // autonomous navigation speed cm/sec
|
||||||
uint16_t max_auto_climb_rate; // max vertical speed limitation cm/sec
|
uint16_t max_auto_climb_rate; // max vertical speed limitation cm/sec
|
||||||
uint16_t max_manual_speed; // manual velocity control max horizontal speed
|
uint16_t max_manual_speed; // manual velocity control max horizontal speed
|
||||||
uint16_t max_manual_climb_rate; // manual velocity control max vertical speed
|
uint16_t max_manual_climb_rate; // manual velocity control max vertical speed
|
||||||
uint16_t land_minalt_vspd; // Final RTH landing descent rate under minalt
|
uint16_t land_minalt_vspd; // Final RTH landing descent rate under minalt
|
||||||
uint16_t land_maxalt_vspd; // RTH landing descent rate target at maxalt
|
uint16_t land_maxalt_vspd; // RTH landing descent rate target at maxalt
|
||||||
uint16_t land_slowdown_minalt; // Altitude to stop lowering descent rate during RTH descend
|
uint16_t land_slowdown_minalt; // Altitude to stop lowering descent rate during RTH descend
|
||||||
uint16_t land_slowdown_maxalt; // Altitude to start lowering descent rate during RTH descend
|
uint16_t land_slowdown_maxalt; // Altitude to start lowering descent rate during RTH descend
|
||||||
uint16_t emerg_descent_rate; // emergency landing descent rate
|
uint16_t emerg_descent_rate; // emergency landing descent rate
|
||||||
uint16_t rth_altitude; // altitude to maintain when RTH is active (depends on rth_alt_control_mode) (cm)
|
uint16_t rth_altitude; // altitude to maintain when RTH is active (depends on rth_alt_control_mode) (cm)
|
||||||
uint16_t rth_home_altitude; // altitude to go to during RTH after the craft reached home (cm)
|
uint16_t rth_home_altitude; // altitude to go to during RTH after the craft reached home (cm)
|
||||||
uint16_t rth_climb_first_stage_altitude // Altitude to reach before transitioning from climb first to turn first
|
uint16_t rth_climb_first_stage_altitude; // Altitude to reach before transitioning from climb first to turn first
|
||||||
uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland
|
uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland
|
||||||
uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home
|
uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home
|
||||||
uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode
|
uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode
|
||||||
uint16_t safehome_max_distance; // Max distance that a safehome is from the arming point
|
uint16_t safehome_max_distance; // Max distance that a safehome is from the arming point
|
||||||
uint16_t max_altitude; // Max altitude when in AltHold mode (not Surface Following)
|
uint16_t max_altitude; // Max altitude when in AltHold mode (not Surface Following)
|
||||||
} general;
|
} general;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue