From 369fafdabcf5b9470653d94184dfff4162e56d89 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 25 Jul 2022 22:28:03 +0100 Subject: [PATCH 01/20] Initial cut --- docs/Settings.md | 10 ++++++++++ src/main/fc/settings.yaml | 5 +++++ src/main/navigation/navigation.c | 1 + src/main/navigation/navigation.h | 1 + src/main/navigation/navigation_fw_launch.c | 14 +++++++++++++- 5 files changed, 30 insertions(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index 8966d74d82..9731c1fa48 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -3032,6 +3032,16 @@ Launch idle throttle - throttle to be set before launch sequence is initiated. I --- +### nav_fw_launch_jerk_wake_idle + +Trigger the idle throttle by jerking the plane + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### nav_fw_launch_manual_throttle Allows launch with manually controlled throttle. INAV only levels wings and controls climb pitch during launch. Throttle is controlled directly by throttle stick movement. IF USED WITHOUT A GPS LOCK plane must be launched immediately after throttle is increased to avoid issues with climb out stabilisation and the launch ending sooner than expected (launch end timer starts as soon as the throttle stick is raised). diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ae5d7d04ea..4e1800822f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2797,6 +2797,11 @@ groups: field: fw.launch_idle_motor_timer min: 0 max: 60000 + - name: nav_fw_launch_jerk_wake_idle + description: "Trigger the idle throttle by jerking the plane" + field: fw.launch_jerk_wake_idle + type: bool + default_value: OFF - name: nav_fw_launch_motor_delay description: "Delay between detected launch and launch sequence start and throttling up (ms)" default_value: 500 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 56912d4b23..e6e8e189e7 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -196,6 +196,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms + .launch_jerk_wake_idle = SETTING_NAV_FW_LAUNCH_JERK_WAKE_IDLE_DEFAULT, // bool .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 21eda4a37c..08cb2b1c46 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -294,6 +294,7 @@ typedef struct navConfig_s { uint16_t launch_time_thresh; // Time threshold for launch detection (ms) uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms) uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms) + bool launch_jerk_wake_idle; // Activate the idle throttle by jerking the plane uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention) uint16_t launch_end_time; // Time to make the transition from launch angle to leveled and throttle transition from launch throttle to the stick position uint16_t launch_min_time; // Minimum time in launch mode to prevent possible bump of the sticks from leaving launch mode early diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 1515f46004..5b8a1e7d66 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -312,16 +312,28 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs) { + bool isIdleJerkActivationTriggered = false; + if (isThrottleLow()) { return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE } applyThrottleIdleLogic(true); - if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) { + // Check to see if the plane has been jerked. If so, wake the idle throttle now + if (navConfig()->fw.launch_jerk_wake_idle) { + const float preIdleSwingVelocity = (fabsf(imuMeasuredRotationBF.z) > SWING_LAUNCH_MIN_ROTATION_RATE) ? (imuMeasuredAccelBF.y / imuMeasuredRotationBF.z) : 0; + const bool isPreIdleSwingLaunched = (preIdleSwingVelocity > navConfig()->fw.launch_velocity_thresh) && (imuMeasuredAccelBF.x > 0); + const bool isPreIdleForwardAccelerationHigh = (imuMeasuredAccelBF.x > navConfig()->fw.launch_accel_thresh); + + isIdleJerkActivationTriggered = (isPreIdleSwingLaunched || isPreIdleForwardAccelerationHigh); + } + + if ((currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) || isIdleJerkActivationTriggered) { idleMotorAboutToStart = false; return FW_LAUNCH_EVENT_SUCCESS; } + // 5 second warning motor about to start at idle, changes Beeper sound idleMotorAboutToStart = navConfig()->fw.launch_idle_motor_timer - currentStateElapsedMs(currentTimeUs) < 5000; From 92d51edc5e4533de79ad65b7c7c105f675a11f26 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 29 Jul 2022 15:45:48 +0100 Subject: [PATCH 02/20] FW launch: Wiggle to wake idle throttle - Added options for detection for different type/size planes - Changed trigger to only use the yaw axis gyro data. - Time limit for individual wiggle to prevent accidental triggers - Time limit for double wiggle, again to prevent accidental triggers. --- docs/Settings.md | 24 +++--- src/main/fc/settings.yaml | 16 ++-- src/main/navigation/navigation.c | 48 +++++------ src/main/navigation/navigation.h | 8 +- src/main/navigation/navigation_fw_launch.c | 94 ++++++++++++++++++---- 5 files changed, 127 insertions(+), 63 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 9731c1fa48..eec9b27498 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -2974,11 +2974,11 @@ Launch abort stick deadband in [r/c points], applied after r/c deadband and expo ### nav_fw_launch_accel -Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s +Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s | Default | Min | Max | | --- | --- | --- | -| 1863 | 1000 | 20000 | +| 1863 | 1500 | 20000 | --- @@ -3032,16 +3032,6 @@ Launch idle throttle - throttle to be set before launch sequence is initiated. I --- -### nav_fw_launch_jerk_wake_idle - -Trigger the idle throttle by jerking the plane - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - ### nav_fw_launch_manual_throttle Allows launch with manually controlled throttle. INAV only levels wings and controls climb pitch during launch. Throttle is controlled directly by throttle stick movement. IF USED WITHOUT A GPS LOCK plane must be launched immediately after throttle is increased to avoid issues with climb out stabilisation and the launch ending sooner than expected (launch end timer starts as soon as the throttle stick is raised). @@ -3132,6 +3122,16 @@ Forward velocity threshold for swing-launch detection [cm/s] --- +### nav_fw_launch_wiggle_to_wake_idle + +Trigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 2 | + +--- + ### nav_fw_loiter_radius PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 4e1800822f..cf95a162d2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2774,10 +2774,10 @@ groups: min: 100 max: 10000 - name: nav_fw_launch_accel - description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" + description: "Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s" default_value: 1863 field: fw.launch_accel_thresh - min: 1000 + min: 1500 max: 20000 - name: nav_fw_launch_max_angle description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" @@ -2797,11 +2797,13 @@ groups: field: fw.launch_idle_motor_timer min: 0 max: 60000 - - name: nav_fw_launch_jerk_wake_idle - description: "Trigger the idle throttle by jerking the plane" - field: fw.launch_jerk_wake_idle - type: bool - default_value: OFF + - name: nav_fw_launch_wiggle_to_wake_idle + description: "Trigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails." + field: fw.launch_wiggle_wake_idle + type: uint8_t + default_value: 0 + min: 0 + max: 2 - name: nav_fw_launch_motor_delay description: "Delay between detected launch and launch sequence start and throttling up (ms)" default_value: 500 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index e6e8e189e7..b0ceb77de4 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -178,40 +178,40 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, // Fixed wing .fw = { - .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees - .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees - .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees - .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s + .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees + .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees + .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees + .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s .control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT, .pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT, .pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT, - .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m + .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m //Fixed wing landing - .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default + .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default // Fixed wing launch - .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s - .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) - .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms - .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms - .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms - .launch_jerk_wake_idle = SETTING_NAV_FW_LAUNCH_JERK_WAKE_IDLE_DEFAULT, // bool - .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch - .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode - .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode - .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure - .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended - .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees - .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg - .launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT,// OFF - .launch_abort_deadband = SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT, // 100 us - .cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps + .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s + .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) + .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms + .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms + .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms + .launch_wiggle_wake_idle = SETTING_NAV_FW_LAUNCH_WIGGLE_TO_WAKE_IDLE_DEFAULT, // uint8_t + .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch + .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode + .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode + .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure + .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended + .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees + .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg + .launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT, // OFF + .launch_abort_deadband = SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT, // 100 us + .cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps .allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT, .useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT, .yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT, - .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT,// pitch angle mode deadband when Saoring mode enabled - .auto_disarm_delay = SETTING_NAV_FW_AUTO_DISARM_DELAY_DEFAULT, // ms - time delay to disarm when auto disarm after landing enabled + .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT, // pitch angle mode deadband when Saoring mode enabled + .auto_disarm_delay = SETTING_NAV_FW_AUTO_DISARM_DELAY_DEFAULT, // ms - time delay to disarm when auto disarm after landing enabled } ); diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 08cb2b1c46..412c025fe1 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -145,9 +145,9 @@ typedef enum { } navRTHClimbFirst_e; typedef enum { // keep aligned with fixedWingLaunchState_t - FW_LAUNCH_DETECTED = 4, - FW_LAUNCH_ABORTED = 9, - FW_LAUNCH_FLYING = 10, + FW_LAUNCH_DETECTED = 5, + FW_LAUNCH_ABORTED = 10, + FW_LAUNCH_FLYING = 11, } navFwLaunchStatus_e; typedef enum { @@ -294,7 +294,7 @@ typedef struct navConfig_s { uint16_t launch_time_thresh; // Time threshold for launch detection (ms) uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms) uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms) - bool launch_jerk_wake_idle; // Activate the idle throttle by jerking the plane + uint8_t launch_wiggle_wake_idle; // Activate the idle throttle by wiggling the plane. 0 = disabled, 1 or 2 specify the number of wiggles. uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention) uint16_t launch_end_time; // Time to make the transition from launch angle to leveled and throttle transition from launch throttle to the stick position uint16_t launch_min_time; // Minimum time in launch mode to prevent possible bump of the sticks from leaving launch mode early diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 5b8a1e7d66..c2045acfdf 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -49,6 +49,7 @@ #include "io/gps.h" #include "sensors/battery.h" +#include "sensors/gyro.h" #define SWING_LAUNCH_MIN_ROTATION_RATE DEGREES_TO_RADIANS(100) // expect minimum 100dps rotation rate #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms @@ -79,20 +80,22 @@ typedef enum { typedef enum { // if changed update navFwLaunchStatus_e FW_LAUNCH_STATE_WAIT_THROTTLE = 0, + FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT, FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, FW_LAUNCH_STATE_MOTOR_IDLE, FW_LAUNCH_STATE_WAIT_DETECTION, - FW_LAUNCH_STATE_DETECTED, // 4 + FW_LAUNCH_STATE_DETECTED, // FW_LAUNCH_DETECTED = 5 FW_LAUNCH_STATE_MOTOR_DELAY, FW_LAUNCH_STATE_MOTOR_SPINUP, FW_LAUNCH_STATE_IN_PROGRESS, FW_LAUNCH_STATE_FINISH, - FW_LAUNCH_STATE_ABORTED, // 9 - FW_LAUNCH_STATE_FLYING, // 10 + FW_LAUNCH_STATE_ABORTED, // FW_LAUNCH_ABORTED = 10 + FW_LAUNCH_STATE_FLYING, // FW_LAUNCH_FLYING = 11 FW_LAUNCH_STATE_COUNT } fixedWingLaunchState_t; static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs_t currentTimeUs); +static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeUs_t currentTimeUs); @@ -124,12 +127,22 @@ static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE [FW_LAUNCH_STATE_WAIT_THROTTLE] = { .onEntry = fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE, .onEvent = { - [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, + [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT, [FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_WAIT_DETECTION }, .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE }, + [FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT] = { + .onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT, + .onEvent = { + [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE, + [FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, + [FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE, + }, + .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE + }, + [FW_LAUNCH_STATE_IDLE_MOTOR_DELAY] = { .onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, .onEvent = { @@ -253,6 +266,47 @@ static inline bool isThrottleLow(void) return calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW; } +static bool hasIdleWakeWiggleSucceeded(timeUs_t currentTimeUs) { + static timeMs_t wiggleTime = 0; + static timeMs_t wigglesTime = 0; + static int8_t wiggleStageOne = 0; + static uint8_t wiggleCount = 0; + const bool isAircraftWithinLaunchAngle = (calculateCosTiltAngle() >= cos_approx(DEGREES_TO_RADIANS(navConfig()->fw.launch_max_angle))); + const uint8_t wiggleStrength = (navConfig()->fw.launch_wiggle_wake_idle == 1) ? 50 : 40; + int8_t wiggleDirection = 0; + int16_t yawRate = (int16_t)(gyroRateDps(YAW) * (4 / 16.4)); + + // Check to see if yaw rate has exceeded 50 dps. If so proceed to the next stage or continue to idle + if ((yawRate < -wiggleStrength || yawRate > wiggleStrength) && isAircraftWithinLaunchAngle) { + wiggleDirection = (yawRate > 0) ? 1 : -1; + + if (wiggleStageOne == 0) { + wiggleStageOne = wiggleDirection; + wigglesTime = US2MS(currentTimeUs); + } else if (wiggleStageOne != wiggleDirection) { + wiggleStageOne = 0; + wiggleCount++; + + if (wiggleCount == navConfig()->fw.launch_wiggle_wake_idle) { + return true; + } + } + + wiggleTime = US2MS(currentTimeUs); + } + + // If time between wiggle stages is > 100ms, or the time between two wiggles is > 1s. Reset the wiggle + if ( + ((wiggleStageOne != 0) && (US2MS(currentTimeUs) > (wiggleTime + 100))) || + ((wiggleCount != 0) && (US2MS(currentTimeUs) > (wigglesTime + 500))) + ) { + wiggleStageOne = 0; + wiggleCount = 0; + } + + return false; +} + static inline bool isLaunchMaxAltitudeReached(void) { return (navConfig()->fw.launch_max_altitude > 0) && (getEstimatedActualPosition(Z) >= navConfig()->fw.launch_max_altitude); @@ -310,26 +364,34 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs return FW_LAUNCH_EVENT_NONE; } +static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT(timeUs_t currentTimeUs) { + if (isThrottleLow()) { + return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE + } + + if (navConfig()->fw.launch_wiggle_wake_idle == 0 || navConfig()->fw.launch_idle_motor_timer > 0 ) { + return FW_LAUNCH_EVENT_GOTO_DETECTION; + } + + applyThrottleIdleLogic(true); + + if (hasIdleWakeWiggleSucceeded(currentTimeUs)) { + idleMotorAboutToStart = false; + return FW_LAUNCH_EVENT_SUCCESS; + } + + return FW_LAUNCH_EVENT_NONE; +} + static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs) { - bool isIdleJerkActivationTriggered = false; - if (isThrottleLow()) { return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE } applyThrottleIdleLogic(true); - // Check to see if the plane has been jerked. If so, wake the idle throttle now - if (navConfig()->fw.launch_jerk_wake_idle) { - const float preIdleSwingVelocity = (fabsf(imuMeasuredRotationBF.z) > SWING_LAUNCH_MIN_ROTATION_RATE) ? (imuMeasuredAccelBF.y / imuMeasuredRotationBF.z) : 0; - const bool isPreIdleSwingLaunched = (preIdleSwingVelocity > navConfig()->fw.launch_velocity_thresh) && (imuMeasuredAccelBF.x > 0); - const bool isPreIdleForwardAccelerationHigh = (imuMeasuredAccelBF.x > navConfig()->fw.launch_accel_thresh); - - isIdleJerkActivationTriggered = (isPreIdleSwingLaunched || isPreIdleForwardAccelerationHigh); - } - - if ((currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) || isIdleJerkActivationTriggered) { + if ((currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) || (navConfig()->fw.launch_wiggle_wake_idle > 0 && hasIdleWakeWiggleSucceeded(currentTimeUs))) { idleMotorAboutToStart = false; return FW_LAUNCH_EVENT_SUCCESS; } From dbd1ed103976b748a8fb4ceeafbbc121a067a2ad Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 4 Dec 2023 12:30:01 +0100 Subject: [PATCH 03/20] IFLIGHT_2RAW_H743 --- .../target/IFLIGHT_2RAW_H743/CMakeLists.txt | 1 + src/main/target/IFLIGHT_2RAW_H743/config.c | 31 ++++ src/main/target/IFLIGHT_2RAW_H743/target.c | 49 ++++++ src/main/target/IFLIGHT_2RAW_H743/target.h | 165 ++++++++++++++++++ 4 files changed, 246 insertions(+) create mode 100644 src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt create mode 100644 src/main/target/IFLIGHT_2RAW_H743/config.c create mode 100644 src/main/target/IFLIGHT_2RAW_H743/target.c create mode 100644 src/main/target/IFLIGHT_2RAW_H743/target.h diff --git a/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt new file mode 100644 index 0000000000..6a430dc675 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(IFLIGHT_2RAW_H743) diff --git a/src/main/target/IFLIGHT_2RAW_H743/config.c b/src/main/target/IFLIGHT_2RAW_H743/config.c new file mode 100644 index 0000000000..0f1fec5a81 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/config.c @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "fc/config.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.c b/src/main/target/IFLIGHT_2RAW_H743/target.c new file mode 100644 index 0000000000..23dd0e0c37 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/target.c @@ -0,0 +1,49 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2 + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6 + + DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7 + DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8 + DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE + + DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11 + DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DMA_NONE + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.h b/src/main/target/IFLIGHT_2RAW_H743/target.h new file mode 100644 index 0000000000..f0cf03e33d --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/target.h @@ -0,0 +1,165 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "2RH7" + +#define USBD_PRODUCT_STRING "IFLIGHT_2RAW_H743" + +#define LED0 PE3 +#define LED1 PE4 + +#define BEEPER PC9 +#define BEEPER_INVERTED + +// SPI Buses +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PD7 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +// I2C +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +// Gyro +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PC15 + +// OSD +// #define USE_MAX7456 +// #define MAX7456_SPI_BUS BUS_SPI2 +// #define MAX7456_CS_PIN PB12 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_ALL + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_ALL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 + +#define USE_UART4 +#define UART4_TX_PIN PB9 +#define UART4_RX_PIN PB8 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define USE_UART7 +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART6 + +// SD Card +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PA15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// ADC +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC5 +#define ADC_CHANNEL_4_PIN PC4 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +// PINIO +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PD10 +#define PINIO2_PIN PD11 + +// *************** LEDSTRIP ************************ +// #define USE_LED_STRIP +// #define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 250 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 12 +#define USE_DSHOT +#define USE_ESC_SENSOR + From dde9aabfc69cc46875dce08b98056e5fe06ac786 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 2 Jan 2024 17:21:43 +0100 Subject: [PATCH 04/20] Target update --- src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt | 1 - src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt | 1 + .../{IFLIGHT_2RAW_H743 => IFLIGHT_BLITZ_H7_PRO}/config.c | 0 .../{IFLIGHT_2RAW_H743 => IFLIGHT_BLITZ_H7_PRO}/target.c | 0 .../{IFLIGHT_2RAW_H743 => IFLIGHT_BLITZ_H7_PRO}/target.h | 4 ++-- 5 files changed, 3 insertions(+), 3 deletions(-) delete mode 100644 src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt create mode 100644 src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt rename src/main/target/{IFLIGHT_2RAW_H743 => IFLIGHT_BLITZ_H7_PRO}/config.c (100%) rename src/main/target/{IFLIGHT_2RAW_H743 => IFLIGHT_BLITZ_H7_PRO}/target.c (100%) rename src/main/target/{IFLIGHT_2RAW_H743 => IFLIGHT_BLITZ_H7_PRO}/target.h (97%) diff --git a/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt deleted file mode 100644 index 6a430dc675..0000000000 --- a/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -target_stm32h743xi(IFLIGHT_2RAW_H743) diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt b/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt new file mode 100644 index 0000000000..acea488c75 --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO) diff --git a/src/main/target/IFLIGHT_2RAW_H743/config.c b/src/main/target/IFLIGHT_BLITZ_H7_PRO/config.c similarity index 100% rename from src/main/target/IFLIGHT_2RAW_H743/config.c rename to src/main/target/IFLIGHT_BLITZ_H7_PRO/config.c diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.c b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.c similarity index 100% rename from src/main/target/IFLIGHT_2RAW_H743/target.c rename to src/main/target/IFLIGHT_BLITZ_H7_PRO/target.c diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.h b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h similarity index 97% rename from src/main/target/IFLIGHT_2RAW_H743/target.h rename to src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h index f0cf03e33d..97116c078f 100644 --- a/src/main/target/IFLIGHT_2RAW_H743/target.h +++ b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h @@ -18,9 +18,9 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "2RH7" +#define TARGET_BOARD_IDENTIFIER "IH7P" -#define USBD_PRODUCT_STRING "IFLIGHT_2RAW_H743" +#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_H7_PRO" #define LED0 PE3 #define LED1 PE4 From 363d071c34b688189a13afcbe1b2bd38956b1b76 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 9 Jan 2024 18:33:27 +0100 Subject: [PATCH 05/20] Target updates for iFlight Blitz H7 Pro --- src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h index 97116c078f..cc3205fd68 100644 --- a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h +++ b/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h @@ -58,7 +58,7 @@ // Gyro #define USE_IMU_ICM42605 -#define IMU_ICM42605_ALIGN CW90_DEG +#define IMU_ICM42605_ALIGN CW0_DEG #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PC15 @@ -138,6 +138,8 @@ #define RSSI_ADC_CHANNEL ADC_CHN_3 #define AIRSPEED_ADC_CHANNEL ADC_CHN_4 +#define VBAT_SCALE_DEFAULT 2100 + // PINIO #define USE_PINIO #define USE_PINIOBOX From a3308fbd47f4318592c2d55a9d3fb736e655d617 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 17 Jan 2024 15:14:08 +0100 Subject: [PATCH 06/20] Revert "Target update" This reverts commit dde9aabfc69cc46875dce08b98056e5fe06ac786. --- src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt | 1 + .../{IFLIGHT_BLITZ_H7_PRO => IFLIGHT_2RAW_H743}/config.c | 0 .../{IFLIGHT_BLITZ_H7_PRO => IFLIGHT_2RAW_H743}/target.c | 0 .../{IFLIGHT_BLITZ_H7_PRO => IFLIGHT_2RAW_H743}/target.h | 4 ++-- src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt | 1 - 5 files changed, 3 insertions(+), 3 deletions(-) create mode 100644 src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt rename src/main/target/{IFLIGHT_BLITZ_H7_PRO => IFLIGHT_2RAW_H743}/config.c (100%) rename src/main/target/{IFLIGHT_BLITZ_H7_PRO => IFLIGHT_2RAW_H743}/target.c (100%) rename src/main/target/{IFLIGHT_BLITZ_H7_PRO => IFLIGHT_2RAW_H743}/target.h (97%) delete mode 100644 src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt diff --git a/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt new file mode 100644 index 0000000000..6a430dc675 --- /dev/null +++ b/src/main/target/IFLIGHT_2RAW_H743/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(IFLIGHT_2RAW_H743) diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/config.c b/src/main/target/IFLIGHT_2RAW_H743/config.c similarity index 100% rename from src/main/target/IFLIGHT_BLITZ_H7_PRO/config.c rename to src/main/target/IFLIGHT_2RAW_H743/config.c diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.c b/src/main/target/IFLIGHT_2RAW_H743/target.c similarity index 100% rename from src/main/target/IFLIGHT_BLITZ_H7_PRO/target.c rename to src/main/target/IFLIGHT_2RAW_H743/target.c diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h b/src/main/target/IFLIGHT_2RAW_H743/target.h similarity index 97% rename from src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h rename to src/main/target/IFLIGHT_2RAW_H743/target.h index cc3205fd68..d8a33a12ee 100644 --- a/src/main/target/IFLIGHT_BLITZ_H7_PRO/target.h +++ b/src/main/target/IFLIGHT_2RAW_H743/target.h @@ -18,9 +18,9 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "IH7P" +#define TARGET_BOARD_IDENTIFIER "2RH7" -#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_H7_PRO" +#define USBD_PRODUCT_STRING "IFLIGHT_2RAW_H743" #define LED0 PE3 #define LED1 PE4 diff --git a/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt b/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt deleted file mode 100644 index acea488c75..0000000000 --- a/src/main/target/IFLIGHT_BLITZ_H7_PRO/CMakeLists.txt +++ /dev/null @@ -1 +0,0 @@ -target_stm32h743xi(IFLIGHT_BLITZ_H7_PRO) From 2729b6d52a1bd913fb4f546f42639722e3e37501 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 17 Jan 2024 15:28:15 +0100 Subject: [PATCH 07/20] Revert "Target updates for iFlight Blitz H7 Pro" This reverts commit 363d071c34b688189a13afcbe1b2bd38956b1b76. --- src/main/target/IFLIGHT_2RAW_H743/target.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.h b/src/main/target/IFLIGHT_2RAW_H743/target.h index d8a33a12ee..f0cf03e33d 100644 --- a/src/main/target/IFLIGHT_2RAW_H743/target.h +++ b/src/main/target/IFLIGHT_2RAW_H743/target.h @@ -58,7 +58,7 @@ // Gyro #define USE_IMU_ICM42605 -#define IMU_ICM42605_ALIGN CW0_DEG +#define IMU_ICM42605_ALIGN CW90_DEG #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PC15 @@ -138,8 +138,6 @@ #define RSSI_ADC_CHANNEL ADC_CHN_3 #define AIRSPEED_ADC_CHANNEL ADC_CHN_4 -#define VBAT_SCALE_DEFAULT 2100 - // PINIO #define USE_PINIO #define USE_PINIOBOX From 68412e68ee21af5d9e09946e8674a57646113229 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 17 Jan 2024 15:36:57 +0100 Subject: [PATCH 08/20] Revert "Revert "Target updates for iFlight Blitz H7 Pro"" This reverts commit 2729b6d52a1bd913fb4f546f42639722e3e37501. --- src/main/target/IFLIGHT_2RAW_H743/target.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/target/IFLIGHT_2RAW_H743/target.h b/src/main/target/IFLIGHT_2RAW_H743/target.h index f0cf03e33d..d8a33a12ee 100644 --- a/src/main/target/IFLIGHT_2RAW_H743/target.h +++ b/src/main/target/IFLIGHT_2RAW_H743/target.h @@ -58,7 +58,7 @@ // Gyro #define USE_IMU_ICM42605 -#define IMU_ICM42605_ALIGN CW90_DEG +#define IMU_ICM42605_ALIGN CW0_DEG #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PC15 @@ -138,6 +138,8 @@ #define RSSI_ADC_CHANNEL ADC_CHN_3 #define AIRSPEED_ADC_CHANNEL ADC_CHN_4 +#define VBAT_SCALE_DEFAULT 2100 + // PINIO #define USE_PINIO #define USE_PINIOBOX From 7bd1f279432df05d411b9d37c1662c4c0a2f9aa5 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 22 Mar 2024 15:26:16 +0100 Subject: [PATCH 09/20] Minor readme update --- readme.md | 15 +++++---------- 1 file changed, 5 insertions(+), 10 deletions(-) diff --git a/readme.md b/readme.md index 724f1a88c1..e30d2fcc8d 100644 --- a/readme.md +++ b/readme.md @@ -12,24 +12,23 @@ * [INAV Discord Server](https://discord.gg/peg2hhbYwN) * [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial) -* [INAV Official on Telegram](https://t.me/INAVFlight) ## Features * Runs on the most popular F4, F7 and H7 flight controllers -* On Screen Display (OSD) - both character and pixel style -* DJI OSD integration: all elements, system messages and warnings +* MSP Displayport for all the HD Digital FPV systems: DJI, Walksnail and HDZero * Outstanding performance out of the box * Position Hold, Altitude Hold, Return To Home and Waypoint Missions * Excellent support for fixed wing UAVs: airplanes, flying wings +* Blackbox flight recorder logging +* Advanced gyro filtering * Fully configurable mixer that allows to run any hardware you want: multirotor, fixed wing, rovers, boats and other experimental devices * Multiple sensor support: GPS, Pitot tube, sonar, lidar, temperature, ESC with BlHeli_32 telemetry +* Logic Conditions, Global Functions and Global Variables: you can program INAV with a GUI * SmartAudio and IRC Tramp VTX support -* Blackbox flight recorder logging * Telemetry: SmartPort, FPort, MAVlink, LTM, CRSF * Multi-color RGB LED Strip support -* Advanced gyro filtering -* Logic Conditions, Global Functions and Global Variables: you can program INAV with a GUI +* On Screen Display (OSD) - both character and pixel style * And many more! For a list of features, changes and some discussion please review consult the releases [page](https://github.com/iNavFlight/inav/releases) and the documentation. @@ -52,10 +51,6 @@ Command line tools (`blackbox_decode`, `blackbox_render`) for Blackbox log conve Users of EdgeTX and OpenTX radios (Taranis, Horus, Jumper, Radiomaster, Nirvana) can use INAV OpenTX Telemetry Widget screen. Software and installation instruction are available here: [https://github.com/iNavFlight/OpenTX-Telemetry-Widget](https://github.com/iNavFlight/OpenTX-Telemetry-Widget) -### INAV magnetometer alignment helper - -[INAV Magnetometer Alignment helper](https://kernel-machine.github.io/INavMagAlignHelper/) allows to align INAV magnetometer despite position and orientation. This simplifies the process of INAV setup on multirotors with tilted GPS modules. - ### OSD layout Copy, Move, or Replace helper tool [Easy INAV OSD switcher tool](https://www.mrd-rc.com/tutorials-tools-and-testing/useful-tools/inav-osd-switcher-tool/) allows you to easily switch your OSD layouts around in INAV. Choose the from and to OSD layouts, and the method of transfering the layouts. From cf402d4eca05d826292143c5200f83628394ff2f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Spychalski?= Date: Sat, 23 Mar 2024 12:42:41 +0100 Subject: [PATCH 10/20] Merge pull request #9818 from TUNERC-Aria/add-TUNERCF405 Add new target TUNERC405 --- src/main/target/TUNERCF405/CMakeLists.txt | 1 + src/main/target/TUNERCF405/target.c | 39 ++++++ src/main/target/TUNERCF405/target.h | 137 ++++++++++++++++++++++ 3 files changed, 177 insertions(+) create mode 100644 src/main/target/TUNERCF405/CMakeLists.txt create mode 100644 src/main/target/TUNERCF405/target.c create mode 100644 src/main/target/TUNERCF405/target.h diff --git a/src/main/target/TUNERCF405/CMakeLists.txt b/src/main/target/TUNERCF405/CMakeLists.txt new file mode 100644 index 0000000000..ba4e9fd3cd --- /dev/null +++ b/src/main/target/TUNERCF405/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(TUNERCF405) diff --git a/src/main/target/TUNERCF405/target.c b/src/main/target/TUNERCF405/target.c new file mode 100644 index 0000000000..bc0b4e86f6 --- /dev/null +++ b/src/main/target/TUNERCF405/target.c @@ -0,0 +1,39 @@ +/* + * This file is part of INAV Project. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MOTOR, 0, 0), //D2s6 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), //D2s6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), //D1s7 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MOTOR, 0, 0), //D1s5 + + DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s7 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s2 / D2s4 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s2 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_OUTPUT_AUTO, 0, 0), //D2s2 + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/TUNERCF405/target.h b/src/main/target/TUNERCF405/target.h new file mode 100644 index 0000000000..f193377c6e --- /dev/null +++ b/src/main/target/TUNERCF405/target.h @@ -0,0 +1,137 @@ +/* + * This file is part of INAV Project. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "TURC" + +#define USBD_PRODUCT_STRING "TUNERCF405" + +// Indicators +#define LED0 PB9 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// WS2812 +#define USE_LED_STRIP +#define WS2811_PIN PB1 + +// Gyro & ACC +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN SPI1_NSS_PIN +#define BMI270_SPI_BUS BUS_SPI1 + +// OSD +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +// Onboard Flash +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define USE_FLASHFS +#define USE_FLASH_M25P16 //W25Q32JVXGIQ TR +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PB6 + +// IIC +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C1_SCL PB10 +#define I2C1_SDA PB11 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C2 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_ALL + +// Serial ports +#define USE_VCP +#define VBUS_SENSING_PIN PB7 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF + +// ADC +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_SCALE 453 + +// SET +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT ) +#define USE_DSHOT +#define USE_DSHOT_DMAR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define MAX_PWM_OUTPUT_PORTS 8 +#define TARGET_MOTOR_COUNT 8 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff From 07706c5a3d9179565671ecfd4f7eb99962b93131 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 23 Mar 2024 13:09:18 +0100 Subject: [PATCH 11/20] magless navigation PSA --- readme.md | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/readme.md b/readme.md index e30d2fcc8d..53b8046be3 100644 --- a/readme.md +++ b/readme.md @@ -1,6 +1,6 @@ # INAV - navigation capable flight controller -# PSA +# F411 PSA > INAV no longer accepts targets based on STM32 F411 MCU. @@ -8,6 +8,28 @@ ![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png) +# PosHold, Navigation and RTH without compass PSA + +Attention all drone pilots and enthusiasts, + +Are you ready to take your flights to new heights with INAV 7.1? We've got some important information to share with you. + +INAV 7.1 brings an exciting update to navigation capabilities. Now, you can soar through the skies, navigate waypoints, and even return to home without relying on a compass. Yes, you heard that right! But before you launch into the air, there's something crucial to consider. + +While INAV 7.1 may not require a compass for basic navigation functions, we strongly advise you to install one for optimal flight performance. Here's why: + +🛰️ Better Flight Precision: A compass provides essential data for accurate navigation, ensuring smoother and more precise flight paths. + +🌐 Enhanced Reliability: With a compass onboard, your drone can maintain stability even in challenging environments, low speeds and strong wind. + +🚀 Minimize Risks: Although INAV 7.1 can get you where you need to go without a compass, flying without one may result in a bumpier ride and increased risk of drift or inaccurate positioning. + +Remember, safety and efficiency are paramount when operating drones. By installing a compass, you're not just enhancing your flight experience, but also prioritizing safety for yourself and those around you. + +So, before you take off on your next adventure, make sure to equip your drone with a compass. It's the smart choice for smoother flights and better navigation. + +Fly safe, fly smart with INAV 7.1 and a compass by your side! + # INAV Community * [INAV Discord Server](https://discord.gg/peg2hhbYwN) From 5bfcc7c3ef9d1a8d8f5730635b403a7ad385df44 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 24 Mar 2024 07:06:45 +0000 Subject: [PATCH 12/20] Revert "Show a timeout for in flight rearming" --- src/main/fc/fc_core.c | 16 ++------------- src/main/fc/fc_core.h | 2 -- src/main/io/osd.c | 45 ++++++++++++++----------------------------- 3 files changed, 16 insertions(+), 47 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index c51519927b..0d0863760d 100644 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -507,18 +507,6 @@ bool emergencyArmingUpdate(bool armingSwitchIsOn, bool forceArm) return counter >= EMERGENCY_ARMING_MIN_ARM_COUNT; } -uint16_t emergencyInFlightRearmTimeMS(void) -{ - uint16_t rearmMS = 0; - - if (STATE(IN_FLIGHT_EMERG_REARM)) { - timeMs_t currentTimeMs = millis(); - rearmMS = (uint16_t)((US2MS(lastDisarmTimeUs) + EMERGENCY_INFLIGHT_REARM_TIME_WINDOW_MS) - currentTimeMs); - } - - return rearmMS; -} - bool emergInflightRearmEnabled(void) { /* Emergency rearm allowed within 5s timeout period after disarm if craft still flying */ @@ -892,6 +880,7 @@ static void applyThrottleTiltCompensation(void) void taskMainPidLoop(timeUs_t currentTimeUs) { + cycleTime = getTaskDeltaTime(TASK_SELF); dT = (float)cycleTime * 0.000001f; @@ -910,8 +899,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs) } } - if (armTime > 1 * USECS_PER_SEC) { - // reset in flight emerg rearm flag 1 sec after arming once it's served its purpose + if (armTime > 1 * USECS_PER_SEC) { // reset in flight emerg rearm flag 1 sec after arming once it's served its purpose DISABLE_STATE(IN_FLIGHT_EMERG_REARM); } diff --git a/src/main/fc/fc_core.h b/src/main/fc/fc_core.h index 455e5b3849..c66a0050ba 100644 --- a/src/main/fc/fc_core.h +++ b/src/main/fc/fc_core.h @@ -42,9 +42,7 @@ timeUs_t getLastDisarmTimeUs(void); void tryArm(void); disarmReason_t getDisarmReason(void); -uint16_t emergencyInFlightRearmTimeMS(void); bool emergencyArmingUpdate(bool armingSwitchIsOn, bool forceArm); -bool emergInflightRearmEnabled(void); bool areSensorsCalibrating(void); float getFlightTime(void); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 201f3efb7b..f0cc50bbaa 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -28,7 +28,6 @@ #include #include #include -#include #include "platform.h" @@ -4561,16 +4560,8 @@ static void osdShowStats(bool isSinglePageStatsCompatible, uint8_t page) displayWrite(osdDisplayPort, statValuesX + multiValueLengthOffset, top++, buff); } - uint16_t rearmMs = (emergInflightRearmEnabled()) ? emergencyInFlightRearmTimeMS() : 0; - if (savingSettings == true) { displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS)); - } else if (rearmMs > 0) { // Show rearming time if settings not actively being saved. Ignore the settings saved message if rearm available. - char emReArmMsg[23]; - tfp_sprintf(emReArmMsg, "** REARM PERIOD: "); - tfp_sprintf(emReArmMsg + strlen(emReArmMsg), "%02d", (uint8_t)MS2S(rearmMs)); - strcat(emReArmMsg, " **\0"); - displayWrite(osdDisplayPort, statNameX, top++, OSD_MESSAGE_STR(emReArmMsg)); } else if (notify_settings_saved > 0) { if (millis() > notify_settings_saved) { notify_settings_saved = 0; @@ -4870,10 +4861,9 @@ static void osdRefresh(timeUs_t currentTimeUs) } bool statsSinglePageCompatible = (osdDisplayPort->rows >= OSD_STATS_SINGLE_PAGE_MIN_ROWS); - static uint8_t statsCurrentPage = 0; - static timeMs_t statsRefreshTime = 0; - static bool statsDisplayed = false; - static bool statsAutoPagingEnabled = true; + static uint8_t statsCurrentPage = 0; + static bool statsDisplayed = false; + static bool statsAutoPagingEnabled = true; // Detect arm/disarm if (armState != ARMING_FLAG(ARMED)) { @@ -4941,24 +4931,25 @@ static void osdRefresh(timeUs_t currentTimeUs) // Alternate screens for multi-page stats. // Also, refreshes screen at swap interval for single-page stats. if (OSD_ALTERNATING_CHOICES((osdConfig()->stats_page_auto_swap_time * 1000), 2)) { - if (statsCurrentPage == 0) + if (statsCurrentPage == 0) { + osdShowStats(statsSinglePageCompatible, statsCurrentPage); statsCurrentPage = 1; + } } else { - if (statsCurrentPage == 1) + if (statsCurrentPage == 1) { + osdShowStats(statsSinglePageCompatible, statsCurrentPage); statsCurrentPage = 0; + } } } else { // Process manual page change events for multi-page stats. - if (manualPageUpRequested) + if (manualPageUpRequested) { + osdShowStats(statsSinglePageCompatible, 1); statsCurrentPage = 1; - else if (manualPageDownRequested) + } else if (manualPageDownRequested) { + osdShowStats(statsSinglePageCompatible, 0); statsCurrentPage = 0; - } - - // Only refresh the stats every 1/4 of a second. - if (statsRefreshTime <= millis()) { - statsRefreshTime = millis() + 250; - osdShowStats(statsSinglePageCompatible, statsCurrentPage); + } } } @@ -5315,16 +5306,9 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter } /* Messages that are shown regardless of Arming state */ - uint16_t rearmMs = (emergInflightRearmEnabled()) ? emergencyInFlightRearmTimeMS() : 0; if (savingSettings == true) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_SAVING_SETTNGS); - } else if (rearmMs > 0) { // Show rearming time if settings not actively being saved. Ignore the settings saved message if rearm available. - char emReArmMsg[23]; - tfp_sprintf(emReArmMsg, "** REARM PERIOD: "); - tfp_sprintf(emReArmMsg + strlen(emReArmMsg), "%02d", (uint8_t)MS2S(rearmMs)); - strcat(emReArmMsg, " **\0"); - messages[messageCount++] = OSD_MESSAGE_STR(emReArmMsg); } else if (notify_settings_saved > 0) { if (millis() > notify_settings_saved) { notify_settings_saved = 0; @@ -5333,7 +5317,6 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter } } - if (messageCount > 0) { message = messages[OSD_ALTERNATING_CHOICES(systemMessageCycleTime(messageCount, messages), messageCount)]; if (message == failsafeInfoMessage) { From 4a24018bde3acbb3bbbd569274836abfd2ed6892 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 24 Mar 2024 12:07:05 +0100 Subject: [PATCH 13/20] Add target to use second gyro, instead of first gyro --- docs/boards/MAMBAH743_2022B.md | 4 ++++ src/main/target/MAMBAH743/CMakeLists.txt | 3 ++- src/main/target/MAMBAH743/target.c | 2 +- src/main/target/MAMBAH743/target.h | 22 ++++++++++++++++++---- 4 files changed, 25 insertions(+), 6 deletions(-) diff --git a/docs/boards/MAMBAH743_2022B.md b/docs/boards/MAMBAH743_2022B.md index 688c630cb8..d3d91e14c1 100644 --- a/docs/boards/MAMBAH743_2022B.md +++ b/docs/boards/MAMBAH743_2022B.md @@ -2,4 +2,8 @@ Contrary to what the documentation suggests, VTX power is actually on USER2. +# Dual Gyros + +INAV 7.1 changed the default gyro of the board from the gyro on SPI4 back to the one on SPI1. A new tagrt ```MAMBAH743_2022B_GYRO2``` was added to use gyro on SPI4, in case you suspect an issue with the gyro on SPI1, you can switch to the gyro on SPI4 by using the new target. + diff --git a/src/main/target/MAMBAH743/CMakeLists.txt b/src/main/target/MAMBAH743/CMakeLists.txt index 61b073da93..801467cdb8 100644 --- a/src/main/target/MAMBAH743/CMakeLists.txt +++ b/src/main/target/MAMBAH743/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32h743xi(MAMBAH743) -target_stm32h743xi(MAMBAH743_2022B) \ No newline at end of file +target_stm32h743xi(MAMBAH743_2022B) +target_stm32h743xi(MAMBAH743_2022B_GYRO2) diff --git a/src/main/target/MAMBAH743/target.c b/src/main/target/MAMBAH743/target.c index 46231fdbd7..1e4f8fe246 100644 --- a/src/main/target/MAMBAH743/target.c +++ b/src/main/target/MAMBAH743/target.c @@ -29,7 +29,7 @@ BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); -#ifdef MAMBAH743_2022B +#ifdef USE_IMU_ICM42605 BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); #endif diff --git a/src/main/target/MAMBAH743/target.h b/src/main/target/MAMBAH743/target.h index 7fcea85f48..bc4a73979e 100644 --- a/src/main/target/MAMBAH743/target.h +++ b/src/main/target/MAMBAH743/target.h @@ -22,6 +22,11 @@ #define TARGET_BOARD_IDENTIFIER "M743" #define USBD_PRODUCT_STRING "MAMBAH743_2022B" +#elif defined(MAMBAH743_2022B_GYRO2) + +#define TARGET_BOARD_IDENTIFIER "M743" +#define USBD_PRODUCT_STRING "MAMBAH743_2022B_GYRO2" + #else #define TARGET_BOARD_IDENTIFIER "M743" @@ -58,13 +63,22 @@ #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PA4 -#ifdef MAMBAH743_2022B - #define USE_SPI_DEVICE_4 #define SPI4_SCK_PIN PE12 #define SPI4_MISO_PIN PE13 #define SPI4_MOSI_PIN PE14 +#ifdef MAMBAH743_2022B + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 + +#endif + +#ifdef MAMBAH743_2022B_GYRO2 + #define USE_IMU_ICM42605 #define IMU_ICM42605_ALIGN CW270_DEG #define ICM42605_SPI_BUS BUS_SPI4 @@ -175,7 +189,7 @@ #define USE_ADC #define ADC_INSTANCE ADC3 -#ifdef MAMBAH743_2022B +#if defined(MAMBAH743_2022B) || defined(MAMBAH743_2022B_GYRO2) #define ADC_CHANNEL_1_PIN PC1 #define ADC_CHANNEL_2_PIN PC3 @@ -203,7 +217,7 @@ #define USE_PINIO #define USE_PINIOBOX -#ifdef MAMBAH743_2022B +#if defined(MAMBAH743_2022B) || defined(MAMBAH743_2022B_GYRO2) #define PINIO1_PIN PC2 #define PINIO2_PIN PC5 From f84f2edd9d77b36d7711eec4feab8a293dfaceb4 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 24 Mar 2024 12:12:56 +0100 Subject: [PATCH 14/20] Fix gyro alignment --- src/main/target/MAMBAH743/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MAMBAH743/target.h b/src/main/target/MAMBAH743/target.h index bc4a73979e..387893402e 100644 --- a/src/main/target/MAMBAH743/target.h +++ b/src/main/target/MAMBAH743/target.h @@ -71,7 +71,7 @@ #ifdef MAMBAH743_2022B #define USE_IMU_ICM42605 -#define IMU_ICM42605_ALIGN CW0_DEG +#define IMU_ICM42605_ALIGN CW180_DEG #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PA4 From 79cd891daa921ec98b3b0e2f48162a976cdc1255 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Sun, 24 Mar 2024 12:28:14 +0100 Subject: [PATCH 15/20] Oops... My board was flipped, not the gyro. --- src/main/target/MAMBAH743/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/MAMBAH743/target.h b/src/main/target/MAMBAH743/target.h index 387893402e..bc4a73979e 100644 --- a/src/main/target/MAMBAH743/target.h +++ b/src/main/target/MAMBAH743/target.h @@ -71,7 +71,7 @@ #ifdef MAMBAH743_2022B #define USE_IMU_ICM42605 -#define IMU_ICM42605_ALIGN CW180_DEG +#define IMU_ICM42605_ALIGN CW0_DEG #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PA4 From 2f6c56a7f12f580781cbcda2efbebc3cc1561a8b Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 24 Mar 2024 18:01:34 +0000 Subject: [PATCH 16/20] Add missing outputs for SKYSTARSHD2 --- src/main/target/SKYSTARSF405HD/CMakeLists.txt | 1 + src/main/target/SKYSTARSF405HD/target.c | 4 ++++ src/main/target/SKYSTARSF405HD/target.h | 4 ++++ 3 files changed, 9 insertions(+) diff --git a/src/main/target/SKYSTARSF405HD/CMakeLists.txt b/src/main/target/SKYSTARSF405HD/CMakeLists.txt index cc9515d9e0..b097558284 100644 --- a/src/main/target/SKYSTARSF405HD/CMakeLists.txt +++ b/src/main/target/SKYSTARSF405HD/CMakeLists.txt @@ -1 +1,2 @@ target_stm32f405xg(SKYSTARSF405HD) +target_stm32f405xg(SKYSTARSF405HD2) \ No newline at end of file diff --git a/src/main/target/SKYSTARSF405HD/target.c b/src/main/target/SKYSTARSF405HD/target.c index 3da0f45db9..cc4ff1c5a8 100644 --- a/src/main/target/SKYSTARSF405HD/target.c +++ b/src/main/target/SKYSTARSF405HD/target.c @@ -28,6 +28,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 0), +#if defined(SKYSTARSF405HD2) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), +#endif DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), }; diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h index c5ab2d49fe..9b9805084f 100644 --- a/src/main/target/SKYSTARSF405HD/target.h +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -156,4 +156,8 @@ #define USE_DSHOT #define USE_ESC_SENSOR +#if defined(SKYSTARSF405HD2) +#define MAX_PWM_OUTPUT_PORTS 6 +#else #define MAX_PWM_OUTPUT_PORTS 4 +#endif From 85ec0a9dc942ee59c2b2428e942ae82dfff55421 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 26 Mar 2024 11:01:14 +0100 Subject: [PATCH 17/20] Revert "Merge pull request #9438 from dronecontrol-ru/baro_alt_vario" This reverts commit 5d77d07cec9d30d0146bfe51e8fe0ff9089f46d4, reversing changes made to 3b218b6f9fcdf6a8d7850dc6bfaa0164815ba428. --- src/main/rx/crsf.h | 2 -- src/main/telemetry/crsf.c | 49 ++++++--------------------------------- 2 files changed, 7 insertions(+), 44 deletions(-) diff --git a/src/main/rx/crsf.h b/src/main/rx/crsf.h index 80e356223f..f3bc793349 100755 --- a/src/main/rx/crsf.h +++ b/src/main/rx/crsf.h @@ -45,7 +45,6 @@ enum { CRSF_FRAME_GPS_PAYLOAD_SIZE = 15, CRSF_FRAME_VARIO_SENSOR_PAYLOAD_SIZE = 2, CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE = 8, - CRSF_FRAME_BAROVARIO_SENSOR_PAYLOAD_SIZE = 4, CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE = 10, CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE = 22, // 11 bits per channel * 16 channels = 22 bytes. CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE = 6, @@ -87,7 +86,6 @@ typedef enum { CRSF_FRAMETYPE_GPS = 0x02, CRSF_FRAMETYPE_VARIO_SENSOR = 0x07, CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08, - CRSF_FRAMETYPE_BAROVARIO_SENSOR = 0x09, CRSF_FRAMETYPE_LINK_STATISTICS = 0x14, CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16, CRSF_FRAMETYPE_ATTITUDE = 0x1E, diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index fd46100387..5ed25de73b 100755 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -57,7 +57,7 @@ #include "sensors/battery.h" #include "sensors/sensors.h" -#include "sensors/barometer.h" + #include "telemetry/crsf.h" #include "telemetry/telemetry.h" #include "telemetry/msp_shared.h" @@ -258,22 +258,6 @@ static void crsfFrameBatterySensor(sbuf_t *dst) crsfSerialize8(dst, batteryRemainingPercentage); } -/* -0x09 Baro+Vario sensor -Payload: -uint16 Altitude -int16 Vertical speed ( cm/s ) -*/ -static void crsfFrameBaroVarioSensor(sbuf_t *dst) -{ - // use sbufWrite since CRC does not include frame length - sbufWriteU8(dst, CRSF_FRAME_BAROVARIO_SENSOR_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC); - crsfSerialize8(dst, CRSF_FRAMETYPE_BAROVARIO_SENSOR); - int32_t altitude = baroGetLatestAltitude() / 10; // Altitude in decimeters - crsfSerialize16(dst, altitude + 10000 < 0x8000 ? altitude + 10000 : 0x8000 + altitude / 10); - crsfSerialize16(dst, lrintf(getEstimatedActualVelocity(Z))); -} - typedef enum { CRSF_ACTIVE_ANTENNA1 = 0, CRSF_ACTIVE_ANTENNA2 = 1 @@ -431,7 +415,6 @@ typedef enum { CRSF_FRAME_FLIGHT_MODE_INDEX, CRSF_FRAME_GPS_INDEX, CRSF_FRAME_VARIO_SENSOR_INDEX, - CRSF_FRAME_BAROVARIO_SENSOR_INDEX, CRSF_SCHEDULE_COUNT_MAX } crsfFrameTypeIndex_e; @@ -491,18 +474,13 @@ static void processCrsf(void) crsfFrameGps(dst); crsfFinalize(dst); } +#endif +#if defined(USE_BARO) || defined(USE_GPS) if (currentSchedule & BV(CRSF_FRAME_VARIO_SENSOR_INDEX)) { crsfInitializeFrame(dst); crsfFrameVarioSensor(dst); crsfFinalize(dst); } -#endif -#if defined(USE_BARO) - if (currentSchedule & BV(CRSF_FRAME_BAROVARIO_SENSOR_INDEX)) { - crsfInitializeFrame(dst); - crsfFrameBaroVarioSensor(dst); - crsfFinalize(dst); - } #endif crsfScheduleIndex = (crsfScheduleIndex + 1) % crsfScheduleCount; } @@ -527,23 +505,14 @@ void initCrsfTelemetry(void) crsfSchedule[index++] = BV(CRSF_FRAME_ATTITUDE_INDEX); crsfSchedule[index++] = BV(CRSF_FRAME_BATTERY_SENSOR_INDEX); crsfSchedule[index++] = BV(CRSF_FRAME_FLIGHT_MODE_INDEX); -#if defined(USE_GPS) +#ifdef USE_GPS if (feature(FEATURE_GPS)) { crsfSchedule[index++] = BV(CRSF_FRAME_GPS_INDEX); - #if !defined(USE_BARO) - crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX); - #endif } #endif -#if defined(USE_BARO) - if (sensors(SENSOR_BARO)) { - crsfSchedule[index++] = BV(CRSF_FRAME_BAROVARIO_SENSOR_INDEX); - } else { - #if defined(USE_GPS) - if (feature(FEATURE_GPS)) { - crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX); - } - #endif +#if defined(USE_BARO) || defined(USE_GPS) + if (sensors(SENSOR_BARO) || (STATE(FIXED_WING_LEGACY) && feature(FEATURE_GPS))) { + crsfSchedule[index++] = BV(CRSF_FRAME_VARIO_SENSOR_INDEX); } #endif crsfScheduleCount = (uint8_t)index; @@ -622,11 +591,7 @@ int getCrsfFrame(uint8_t *frame, crsfFrameType_e frameType) case CRSF_FRAMETYPE_VARIO_SENSOR: crsfFrameVarioSensor(sbuf); break; - case CRSF_FRAMETYPE_BAROVARIO_SENSOR: - crsfFrameBaroVarioSensor(sbuf); - break; } - const int frameSize = crsfFinalizeBuf(sbuf, frame); return frameSize; } From 9c01b83440ea305f4be27c96a38ce6869b6c71b3 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 26 Mar 2024 16:51:55 -0500 Subject: [PATCH 18/20] FOXEERF722DUAL enable 5V power by default --- src/main/target/FOXEERF722DUAL/config.c | 31 +++++++++++++++++++++++++ src/main/target/FOXEERF722DUAL/target.c | 1 + src/main/target/FOXEERF722DUAL/target.h | 10 ++++++++ 3 files changed, 42 insertions(+) create mode 100644 src/main/target/FOXEERF722DUAL/config.c diff --git a/src/main/target/FOXEERF722DUAL/config.c b/src/main/target/FOXEERF722DUAL/config.c new file mode 100644 index 0000000000..38763948c3 --- /dev/null +++ b/src/main/target/FOXEERF722DUAL/config.c @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#if defined(FOXEERF722V2) +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} +#endif diff --git a/src/main/target/FOXEERF722DUAL/target.c b/src/main/target/FOXEERF722DUAL/target.c index fe34e0a45d..e81731651e 100644 --- a/src/main/target/FOXEERF722DUAL/target.c +++ b/src/main/target/FOXEERF722DUAL/target.c @@ -22,6 +22,7 @@ #include "drivers/timer.h" #include "drivers/sensor.h" #include "drivers/pwm_mapping.h" +#include "drivers/pinio.h" BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); #if defined(FOXEERF722DUAL) diff --git a/src/main/target/FOXEERF722DUAL/target.h b/src/main/target/FOXEERF722DUAL/target.h index 250a88a307..1eafd86af9 100644 --- a/src/main/target/FOXEERF722DUAL/target.h +++ b/src/main/target/FOXEERF722DUAL/target.h @@ -147,3 +147,13 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) + +// *************** PINIO *************************** +#if defined(FOXEERF722V2) +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC6 // Enable GPS power +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED +#endif + + From 36f859a46e3649bce9a6d520fd968a064fec93c8 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Fri, 29 Mar 2024 12:10:39 +0000 Subject: [PATCH 19/20] Fixed error introduced when updating from master --- src/main/navigation/navigation.c | 52 ++++++++++++++++---------------- 1 file changed, 26 insertions(+), 26 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 309ba03b89..e7261b068c 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -204,44 +204,44 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, // Fixed wing .fw = { - .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees - .max_manual_climb_rate = SETTING_NAV_FW_MANUAL_CLIMB_RATE_DEFAULT, // 3 m/s - .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees - .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees - .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s + .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees + .max_manual_climb_rate = SETTING_NAV_FW_MANUAL_CLIMB_RATE_DEFAULT, // 3 m/s + .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees + .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees + .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s .control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT, .pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT, .pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT, .minThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT, - .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m + .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m .loiter_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT, //Fixed wing landing - .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default + .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default // Fixed wing launch - .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s - .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) - .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms - .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms - .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms - .launch_wiggle_wake_idle = SETTING_NAV_FW_LAUNCH_WIGGLE_TO_WAKE_IDLE_DEFAULT, // uint8_t - .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to greaually increase throttle from idle to launch - .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode - .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode - .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure - .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended - .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees - .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg - .launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT, // OFF - .launch_abort_deadband = SETTING_NAV_FW_LAUNCH_ABORT_DEADBAND_DEFAULT, // 100 us + .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s + .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G) + .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms + .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms + .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms + .launch_wiggle_wake_idle = SETTING_NAV_FW_LAUNCH_WIGGLE_TO_WAKE_IDLE_DEFAULT, // uint8_t + .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to greaually increase throttle from idle to launch + .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode + .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode + .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure + .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended + .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees + .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg + .launch_manual_throttle = SETTING_NAV_FW_LAUNCH_MANUAL_THROTTLE_DEFAULT, // OFF + .launch_land_abort_deadband = SETTING_NAV_FW_LAUNCH_LAND_ABORT_DEADBAND_DEFAULT, // 100 us .allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT, .useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT, .yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT, - .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT, // pitch angle mode deadband when Saoring mode enabled - .wp_tracking_accuracy = SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT, // 0, improves course tracking accuracy during FW WP missions - .wp_tracking_max_angle = SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT, // 60 degs - .wp_turn_smoothing = SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT, // 0, smooths turns during FW WP mode missions + .soaring_pitch_deadband = SETTING_NAV_FW_SOARING_PITCH_DEADBAND_DEFAULT, // pitch angle mode deadband when Saoring mode enabled + .wp_tracking_accuracy = SETTING_NAV_FW_WP_TRACKING_ACCURACY_DEFAULT, // 0, improves course tracking accuracy during FW WP missions + .wp_tracking_max_angle = SETTING_NAV_FW_WP_TRACKING_MAX_ANGLE_DEFAULT, // 60 degs + .wp_turn_smoothing = SETTING_NAV_FW_WP_TURN_SMOOTHING_DEFAULT, // 0, smooths turns during FW WP mode missions } ); From 91460013c2c56fa9b35efe1434b353a78962f21f Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 31 Mar 2024 23:53:16 -0500 Subject: [PATCH 20/20] fix broken links to modes.md --- build_docs.sh | 3 +-- docs/API/MSP_extensions.md | 6 +++--- docs/Getting Started.md | 2 +- docs/Safety.md | 2 +- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/build_docs.sh b/build_docs.sh index 70c2cc45cf..9711d8775c 100755 --- a/build_docs.sh +++ b/build_docs.sh @@ -21,7 +21,6 @@ doc_files=( 'Buzzer.md' 'Sonar.md' 'Profiles.md' - 'Modes.md' 'Inflight Adjustments.md' 'Controls.md' 'Gtune.md' @@ -49,7 +48,7 @@ if which gimli >/dev/null; then done rm -f ${filename}.pdf gimli -f ${filename}.md -stylesheet override.css \ - -w '--toc --title "Cleanflight Manual" --footer-right "[page]" --toc-depth 1' + -w '--toc --title "INAV Manual" --footer-right "[page]" --toc-depth 1' rm ${filename}.md popd >/dev/null else diff --git a/docs/API/MSP_extensions.md b/docs/API/MSP_extensions.md index 357c6239e8..2ac8dd989f 100644 --- a/docs/API/MSP_extensions.md +++ b/docs/API/MSP_extensions.md @@ -23,7 +23,7 @@ Unassigned slots have rangeStartStep == rangeEndStep. Each element contains the | Data | Type | Notes | |------|------|-------| -| permanentId | uint8 | See Modes.md for a definition of the permanent ids | +| permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids | | auxChannelIndex | uint8 | The Aux switch number (indexed from 0) | | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | @@ -45,7 +45,7 @@ sending this message for all auxiliary slots. | Data | Type | Notes | |------|------|-------| | sequence id | uint8 | A monotonically increasing ID, from 0 to the number of slots -1 | -| permanentId | uint8 | See Modes.md for a definition of the permanent ids | +| permanentId | uint8 | See [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for a definition of the permanent ids | | auxChannelIndex | uint8 | The Aux channel number (indexed from 0) | | rangeStartStep | uint8 | The start value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | | rangeEndStep | uint8 | The end value for this element in 'blocks' of 25 where 0 == 900 and 48 == 2100 | @@ -157,5 +157,5 @@ INAV. See also -------- -Modes.md describes the user visible implementation for the INAV +[The wiki](https://github.com/iNavFlight/inav/wiki/Modes) describes the user visible implementation for the INAV modes extension. diff --git a/docs/Getting Started.md b/docs/Getting Started.md index 2faa8e3323..f49ca32cc4 100644 --- a/docs/Getting Started.md +++ b/docs/Getting Started.md @@ -70,7 +70,7 @@ Now, there are two ways to [configure CF](Configuration.md); via the Configurat * Verify the range of each channel goes from ~1000 to ~2000. See also [controls](Controls.md). and `rx_min_usec` and `rx_max_usec`. * You can also set EXPO here instead of your Tx. * Click Save! -* Modes tab: Setup the desired modes. See the [modes](Modes.md) chapter for what each mode does, but for the beginning you mainly need HORIZON, if any. +* Modes tab: Setup the desired modes. See the [Modes in the wiki](https://github.com/iNavFlight/inav/wiki/Modes) for what each mode does. * Before finishing this section, you should calibrate the ESCs, install the FC to the frame, and connect the RSSI cable, buzzer and battery if you have chosen to use those. diff --git a/docs/Safety.md b/docs/Safety.md index e0b969a78a..ea21424391 100644 --- a/docs/Safety.md +++ b/docs/Safety.md @@ -6,7 +6,7 @@ As many can attest, multirotors and RC models in general can be very dangerous, ## Before Installing -Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](Modes.md) +Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](https://github.com/iNavFlight/inav/wiki/Modes) pages for further important information. You are highly advised to use the Receiver tab in the INAV Configurator, making sure your Rx channel