From d772d8a5a13d24c71d67d4b6a64dbc619639bbcb Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sat, 12 Jun 2021 16:14:27 +0100 Subject: [PATCH 01/12] Updated FM strings for 3.0 Changed the old __3CRS__ to **CRUZ** and __CRS__ to **CRSH**, to reflect the mode changes. --- src/main/telemetry/crsf.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index 439ca8f2d0..079abf95d2 100755 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -332,9 +332,9 @@ static void crsfFrameFlightMode(sbuf_t *dst) } else if (FLIGHT_MODE(NAV_POSHOLD_MODE)) { flightMode = "HOLD"; } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE)) { - flightMode = "3CRS"; + flightMode = "CRUZ"; } else if (FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { - flightMode = "CRS"; + flightMode = "CRSH"; } else if (FLIGHT_MODE(NAV_ALTHOLD_MODE)) { flightMode = "AH"; } else if (FLIGHT_MODE(NAV_WP_MODE)) { From b66caae07af6efc73440a3f4ad9bb8aabb1ee811 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 22 Sep 2021 22:32:56 +0100 Subject: [PATCH 02/12] Adding loiter radius to programming Adding a loiter radius override to the programming. This change allows pilots to change their loiter radius on the fly. The minimum loiter radius will always be that set in Advanced Tuning, for safety. The maximum radius is 100000cm. As part of this change, I increased the min and max constraints of the basic maths conditions. The were set to int16, however operands can be int32. Before the change, this caused clipping of the radius when performing basic calculus on it. --- docs/Programming Framework.md | 6 ++++-- src/main/navigation/navigation_fixedwing.c | 14 ++++++++++--- src/main/programming/logic_condition.c | 24 ++++++++++++++++++---- src/main/programming/logic_condition.h | 6 +++++- 4 files changed, 40 insertions(+), 10 deletions(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index b6f2780870..e23d915c8f 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -74,6 +74,7 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` | | 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. | | 40 | MOD | Divide `Operand A` by `Operand B` and returns the remainder | +| 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. | ### Operands @@ -125,8 +126,9 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 30 | ACTIVE_WAYPOINT_ACTION | See ACTIVE_WAYPOINT_ACTION paragraph | | 31 | 3D HOME_DISTANCE | in `meters`, calculated from HOME_DISTANCE and ALTITUDE using Pythagorean theorem | | 32 | CROSSFIRE LQ | Crossfire Link quality as returned by the CRSF protocol | -| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol | -| 34 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix | +| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol | +| 34 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix | +| 35 | LOITER_RADIUS | The current loiter radius in cm. | #### ACTIVE_WAYPOINT_ACTION diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 9845bde147..d9f6e668be 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -49,6 +49,8 @@ #include "navigation/navigation.h" #include "navigation/navigation_private.h" +#include "programming/logic_condition.h" + #include "rx/rx.h" #include "sensors/battery.h" @@ -271,10 +273,16 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) // Limit minimum forward velocity to 1 m/s float trackingDistance = trackingPeriod * MAX(posControl.actualState.velXY, 100.0f); + uint32_t navLoiterRadius = navConfig()->fw.loiter_radius; + +#ifdef USE_PROGRAMMING_FRAMEWORK + navLoiterRadius = getLoiterRadius(navConfig()->fw.loiter_radius); +#endif + // If angular visibility of a waypoint is less than 30deg, don't calculate circular loiter, go straight to the target #define TAN_15DEG 0.26795f bool needToCalculateCircularLoiter = (isApproachingLastWaypoint() || isWaypointWait()) - && (distanceToActualTarget <= (navConfig()->fw.loiter_radius / TAN_15DEG)) + && (distanceToActualTarget <= (navLoiterRadius / TAN_15DEG)) && (distanceToActualTarget > 50.0f) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE); @@ -283,8 +291,8 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) // We are closing in on a waypoint, calculate circular loiter float loiterAngle = atan2_approx(-posErrorY, -posErrorX) + DEGREES_TO_RADIANS(loiterDirection() * 45.0f); - float loiterTargetX = posControl.desiredState.pos.x + navConfig()->fw.loiter_radius * cos_approx(loiterAngle); - float loiterTargetY = posControl.desiredState.pos.y + navConfig()->fw.loiter_radius * sin_approx(loiterAngle); + float loiterTargetX = posControl.desiredState.pos.x + navLoiterRadius * cos_approx(loiterAngle); + float loiterTargetY = posControl.desiredState.pos.y + navLoiterRadius * sin_approx(loiterAngle); // We have temporary loiter target. Recalculate distance and position error posErrorX = loiterTargetX - navGetCurrentActualPositionAndVelocity()->pos.x; diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 5fa6f92733..44c0d213c6 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -176,20 +176,20 @@ static int logicConditionCompute( break; case LOGIC_CONDITION_ADD: - return constrain(operandA + operandB, INT16_MIN, INT16_MAX); + return constrain(operandA + operandB, INT32_MIN, INT32_MAX); break; case LOGIC_CONDITION_SUB: - return constrain(operandA - operandB, INT16_MIN, INT16_MAX); + return constrain(operandA - operandB, INT32_MIN, INT32_MAX); break; case LOGIC_CONDITION_MUL: - return constrain(operandA * operandB, INT16_MIN, INT16_MAX); + return constrain(operandA * operandB, INT32_MIN, INT32_MAX); break; case LOGIC_CONDITION_DIV: if (operandB != 0) { - return constrain(operandA / operandB, INT16_MIN, INT16_MAX); + return constrain(operandA / operandB, INT32_MIN, INT32_MAX); } else { return operandA; } @@ -333,6 +333,11 @@ static int logicConditionCompute( } break; + case LOGIC_CONDITION_LOITER_OVERRIDE: + logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE] = constrain(operandA, 0, 100000); + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS); + return true; + break; default: return false; break; @@ -533,6 +538,9 @@ static int logicConditionGetFlightOperandValue(int operand) { #endif break; + case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS: + return getLoiterRadius(navConfig()->fw.loiter_radius); + default: return 0; break; @@ -720,3 +728,11 @@ int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue) { return originalValue; } } + +uint32_t getLoiterRadius(uint32_t loiterRadius) { + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS)) { + return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000); + } else { + return loiterRadius; + } +} diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 3b795ba43e..ad0abf90f7 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -70,7 +70,8 @@ typedef enum { LOGIC_CONDITION_RC_CHANNEL_OVERRIDE = 38, LOGIC_CONDITION_SET_HEADING_TARGET = 39, LOGIC_CONDITION_MODULUS = 40, - LOGIC_CONDITION_LAST = 41, + LOGIC_CONDITION_LOITER_OVERRIDE = 41, + LOGIC_CONDITION_LAST = 42, } logicOperation_e; typedef enum logicOperandType_s { @@ -120,6 +121,7 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_CRSF_LQ, // 32 LOGIC_CONDITION_OPERAND_FLIGHT_CRSF_SNR, // 33 LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID, // 0/1 // 34 + LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS // 35 } logicFlightOperands_e; @@ -148,6 +150,7 @@ typedef enum { LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE = (1 << 6), LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7), LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL = (1 << 8), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS = (1 << 9), } logicConditionsGlobalFlags_t; typedef enum { @@ -198,3 +201,4 @@ void logicConditionReset(void); float getThrottleScale(float globalThrottleScale); int16_t getRcCommandOverride(int16_t command[], uint8_t axis); int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue); +uint32_t getLoiterRadius(uint32_t loiterRadius); From 2fec7a0285318d9e3576d56a06d5b88cc840ea6c Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 26 Sep 2021 19:48:04 +0100 Subject: [PATCH 03/12] Added nav mode check The override loiter radius will now only apply to POSHOLD. Tested on the ground. Will not get to test in flight for at least 5 days. --- src/main/programming/logic_condition.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 44c0d213c6..d5f5a9f18b 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -730,7 +730,7 @@ int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue) { } uint32_t getLoiterRadius(uint32_t loiterRadius) { - if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS)) { + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && FLIGHT_MODE(NAV_POSHOLD_MODE)) { return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000); } else { return loiterRadius; From 8d5a0b0b8cab562269cd06b46ceb83d63adb0906 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Mon, 27 Sep 2021 16:47:37 +0100 Subject: [PATCH 04/12] Changed the logic I've changed the logic so that it now explicitly ignores certain modes (RTH, WP, FS, and emergency landing). This way the override radius can be changed without being in POS HOLD, allowing it to be preselected. --- src/main/programming/logic_condition.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index d5f5a9f18b..4326e6e8b8 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -730,7 +730,8 @@ int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue) { } uint32_t getLoiterRadius(uint32_t loiterRadius) { - if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && FLIGHT_MODE(NAV_POSHOLD_MODE)) { + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && + !(FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding())) { return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000); } else { return loiterRadius; From f9d68cea85a358b59a8bfdbac05ebc15ad5abc8a Mon Sep 17 00:00:00 2001 From: Mr D Date: Mon, 18 Oct 2021 18:02:21 +0100 Subject: [PATCH 05/12] Added selectable precision to the OSD RPM I've added selectable precision to the ESC RPM, as shown in the OSD. The default is 3, which is the same as the current RPM display. --- docs/Settings.md | 10 ++++++++++ src/main/fc/settings.yaml | 8 +++++++- src/main/io/osd.c | 33 +++++++++++++++++++++++++++------ src/main/io/osd.h | 1 + 4 files changed, 45 insertions(+), 7 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index d53df0dd7e..f030464717 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4122,6 +4122,16 @@ Value above which to make the OSD distance from home indicator blink (meters) --- +### osd_esc_rpm_precision + +Number of characters used to display the RPM value. + +| Default | Min | Max | +| --- | --- | --- | +| 3 | 3 | 6 | + +--- + ### osd_esc_temp_alarm_max Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 70789c9ead..3becec8c4e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3340,7 +3340,6 @@ groups: description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)" default_value: 0 field: hud_wp_disp - min: 0 max: 3 - name: osd_left_sidebar_scroll @@ -3476,6 +3475,13 @@ groups: min: -36 max: 36 + - name: osd_esc_rpm_precision + description: Number of characters used to display the RPM value. + field: esc_rpm_precision + min: 3 + max: 6 + default_value: 3 + - name: PG_OSD_COMMON_CONFIG type: osdCommonConfig_t headers: ["io/osd_common.h"] diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 268815268f..b6f7c2b37f 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1037,17 +1037,37 @@ static void osdFormatRpm(char *buff, uint32_t rpm) { buff[0] = SYM_RPM; if (rpm) { - if (rpm >= 1000) { - osdFormatCentiNumber(buff + 1, rpm / 10, 0, 1, 1, 2); - buff[3] = 'K'; - buff[4] = '\0'; + if ( digitCount(rpm) > osdConfig()->esc_rpm_precision) { + uint8_t rpmMaxDecimals = (osdConfig()->esc_rpm_precision - 3); + osdFormatCentiNumber(buff + 1, rpm / 10, 0, rpmMaxDecimals, rpmMaxDecimals, osdConfig()->esc_rpm_precision-1); + buff[osdConfig()->esc_rpm_precision] = 'K'; + buff[osdConfig()->esc_rpm_precision+1] = '\0'; } else { - tfp_sprintf(buff + 1, "%3lu", rpm); + switch(osdConfig()->esc_rpm_precision) { + case 6: + tfp_sprintf(buff + 1, "%6lu", rpm); + break; + case 5: + tfp_sprintf(buff + 1, "%5lu", rpm); + break; + case 4: + tfp_sprintf(buff + 1, "%4lu", rpm); + break; + case 3: + default: + tfp_sprintf(buff + 1, "%3lu", rpm); + break; + } + + } } else { - strcpy(buff + 1, "---"); + uint8_t buffPos = 1; + while (buffPos <=( osdConfig()->esc_rpm_precision)) { + strcpy(buff + buffPos++, "-"); + } } } #endif @@ -3148,6 +3168,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT, .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, + .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, .units = SETTING_OSD_UNITS_DEFAULT, .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index e46a3bc0bb..fffdc37bf3 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -383,6 +383,7 @@ typedef struct osdConfig_s { uint8_t crsf_lq_format; uint8_t sidebar_height; // sidebar height in rows, 0 turns off sidebars leaving only level indicator arrows uint8_t telemetry; // use telemetry on displayed pixel line 0 + uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. } osdConfig_t; From af8bc221eb1dda4fbac307f0206493cf58f1c994 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 20 Oct 2021 20:47:11 +0200 Subject: [PATCH 06/12] Simplify dynamic notch setup and set ON by default --- src/main/blackbox/blackbox.c | 1 - src/main/fc/settings.yaml | 12 +++--------- src/main/flight/gyroanalyse.c | 16 +--------------- src/main/flight/gyroanalyse.h | 1 - src/main/sensors/gyro.c | 2 -- src/main/sensors/gyro.h | 1 - 6 files changed, 4 insertions(+), 29 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index ebdec54d68..68f22eadef 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1809,7 +1809,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_hz", "%d", gyroConfig()->gyro_main_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_type", "%d", gyroConfig()->gyro_main_lpf_type); #ifdef USE_DYNAMIC_FILTERS - BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchRange", "%d", gyroConfig()->dynamicGyroNotchRange); BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ); BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz); #endif diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 70789c9ead..a0c5314a7f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -280,16 +280,10 @@ groups: max: 10 - name: dynamic_gyro_notch_enabled description: "Enable/disable dynamic gyro notch also known as Matrix Filter" - default_value: OFF + default_value: ON field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool - - name: dynamic_gyro_notch_range - description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" - default_value: "MEDIUM" - field: dynamicGyroNotchRange - condition: USE_DYNAMIC_FILTERS - table: dynamicFilterRangeTable - name: dynamic_gyro_notch_q description: "Q factor for dynamic notches" default_value: 120 @@ -298,8 +292,8 @@ groups: min: 1 max: 1000 - name: dynamic_gyro_notch_min_hz - description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`" - default_value: 150 + description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirotors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`" + default_value: 50 field: dynamicGyroNotchMinHz condition: USE_DYNAMIC_FILTERS min: 30 diff --git a/src/main/flight/gyroanalyse.c b/src/main/flight/gyroanalyse.c index b85d538a15..7cffd9c0b6 100644 --- a/src/main/flight/gyroanalyse.c +++ b/src/main/flight/gyroanalyse.c @@ -60,25 +60,11 @@ FILE_COMPILE_FOR_SPEED void gyroDataAnalyseStateInit( gyroAnalyseState_t *state, uint16_t minFrequency, - uint8_t range, uint32_t targetLooptimeUs ) { - state->fftSamplingRateHz = DYN_NOTCH_RANGE_HZ_LOW; state->minFrequency = minFrequency; - if (range == DYN_NOTCH_RANGE_HIGH) { - state->fftSamplingRateHz = DYN_NOTCH_RANGE_HZ_HIGH; - } - else if (range == DYN_NOTCH_RANGE_MEDIUM) { - state->fftSamplingRateHz = DYN_NOTCH_RANGE_HZ_MEDIUM; - } - - // If we get at least 3 samples then use the default FFT sample frequency - // otherwise we need to calculate a FFT sample frequency to ensure we get 3 samples (gyro loops < 4K) - const int gyroLoopRateHz = lrintf((1.0f / targetLooptimeUs) * 1e6f); - - state->fftSamplingRateHz = MIN((gyroLoopRateHz / 3), state->fftSamplingRateHz); - + state->fftSamplingRateHz = lrintf(1e6f / targetLooptimeUs / 3); // Looptime divided by 3 state->fftResolution = (float)state->fftSamplingRateHz / FFT_WINDOW_SIZE; state->fftStartBin = state->minFrequency / lrintf(state->fftResolution); diff --git a/src/main/flight/gyroanalyse.h b/src/main/flight/gyroanalyse.h index b6de10e40a..949a9248a5 100644 --- a/src/main/flight/gyroanalyse.h +++ b/src/main/flight/gyroanalyse.h @@ -69,7 +69,6 @@ STATIC_ASSERT(FFT_WINDOW_SIZE <= (uint8_t) -1, window_size_greater_than_underlyi void gyroDataAnalyseStateInit( gyroAnalyseState_t *state, uint16_t minFrequency, - uint8_t range, uint32_t targetLooptimeUs ); void gyroDataAnalysePush(gyroAnalyseState_t *gyroAnalyse, int axis, float sample); diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index e1e12bc4d8..7b90e52292 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -131,7 +131,6 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyroDynamicLpfMaxHz = SETTING_GYRO_DYN_LPF_MAX_HZ_DEFAULT, .gyroDynamicLpfCurveExpo = SETTING_GYRO_DYN_LPF_CURVE_EXPO_DEFAULT, #ifdef USE_DYNAMIC_FILTERS - .dynamicGyroNotchRange = SETTING_DYNAMIC_GYRO_NOTCH_RANGE_DEFAULT, .dynamicGyroNotchQ = SETTING_DYNAMIC_GYRO_NOTCH_Q_DEFAULT, .dynamicGyroNotchMinHz = SETTING_DYNAMIC_GYRO_NOTCH_MIN_HZ_DEFAULT, .dynamicGyroNotchEnabled = SETTING_DYNAMIC_GYRO_NOTCH_ENABLED_DEFAULT, @@ -384,7 +383,6 @@ bool gyroInit(void) gyroDataAnalyseStateInit( &gyroAnalyseState, gyroConfig()->dynamicGyroNotchMinHz, - gyroConfig()->dynamicGyroNotchRange, getLooptime() ); #endif diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 545493763e..db1ec22421 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -78,7 +78,6 @@ typedef struct gyroConfig_s { uint16_t gyroDynamicLpfMaxHz; uint8_t gyroDynamicLpfCurveExpo; #ifdef USE_DYNAMIC_FILTERS - uint8_t dynamicGyroNotchRange; uint16_t dynamicGyroNotchQ; uint16_t dynamicGyroNotchMinHz; uint8_t dynamicGyroNotchEnabled; From 8471a2871824ae1837d6ddb57beaeafcc75caf70 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 20 Oct 2021 21:50:29 +0200 Subject: [PATCH 07/12] Docs update --- docs/Settings.md | 16 +++------------- 1 file changed, 3 insertions(+), 13 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index d53df0dd7e..e65f2f1d0d 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -788,17 +788,17 @@ Enable/disable dynamic gyro notch also known as Matrix Filter | Default | Min | Max | | --- | --- | --- | -| OFF | | | +| ON | | | --- ### dynamic_gyro_notch_min_hz -Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` +Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirotors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | Default | Min | Max | | --- | --- | --- | -| 150 | 30 | 1000 | +| 50 | 30 | 1000 | --- @@ -812,16 +812,6 @@ Q factor for dynamic notches --- -### dynamic_gyro_notch_range - -Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers - -| Default | Min | Max | -| --- | --- | --- | -| MEDIUM | | | - ---- - ### eleres_freq _// TODO_ From e67f1ff197057ef4fca329338f7d2e3e8897c41e Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 20 Oct 2021 22:01:41 +0200 Subject: [PATCH 08/12] Further cleanup --- src/main/fc/settings.yaml | 3 --- src/main/sensors/gyro.h | 10 ---------- 2 files changed, 13 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a0c5314a7f..d585856fb1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -144,9 +144,6 @@ tables: - name: rssi_source values: ["NONE", "AUTO", "ADC", "CHANNEL", "PROTOCOL", "MSP"] enum: rssiSource_e - - name: dynamicFilterRangeTable - values: ["HIGH", "MEDIUM", "LOW"] - enum: dynamicFilterRange_e - name: pidTypeTable values: ["NONE", "PID", "PIFF", "AUTO"] enum: pidType_e diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index db1ec22421..7d76c3b057 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -41,16 +41,6 @@ typedef enum { GYRO_FAKE } gyroSensor_e; -typedef enum { - DYN_NOTCH_RANGE_HIGH = 0, - DYN_NOTCH_RANGE_MEDIUM, - DYN_NOTCH_RANGE_LOW -} dynamicFilterRange_e; - -#define DYN_NOTCH_RANGE_HZ_HIGH 2000 -#define DYN_NOTCH_RANGE_HZ_MEDIUM 1333 -#define DYN_NOTCH_RANGE_HZ_LOW 1000 - typedef struct gyro_s { bool initialized; uint32_t targetLooptime; From 743300c19e8d269cab2cf8703c311adb1d2a0aee Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Wed, 20 Oct 2021 23:01:41 +0100 Subject: [PATCH 09/12] Made requested changes Made changes suggested by Pawel. --- src/main/navigation/navigation_fixedwing.c | 6 +----- src/main/programming/logic_condition.c | 12 ++++++++---- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index d9f6e668be..e711877c60 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -273,11 +273,7 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) // Limit minimum forward velocity to 1 m/s float trackingDistance = trackingPeriod * MAX(posControl.actualState.velXY, 100.0f); - uint32_t navLoiterRadius = navConfig()->fw.loiter_radius; - -#ifdef USE_PROGRAMMING_FRAMEWORK - navLoiterRadius = getLoiterRadius(navConfig()->fw.loiter_radius); -#endif + uint32_t navLoiterRadius = getLoiterRadius(navConfig()->fw.loiter_radius); // If angular visibility of a waypoint is less than 30deg, don't calculate circular loiter, go straight to the target #define TAN_15DEG 0.26795f diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 4326e6e8b8..d9908a5cfe 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -82,10 +82,10 @@ void pgResetFn_logicConditions(logicCondition_t *instance) logicConditionState_t logicConditionStates[MAX_LOGIC_CONDITIONS]; static int logicConditionCompute( - int currentVaue, + int32_t currentVaue, logicOperation_e operation, - int operandA, - int operandB + int32_t operandA, + int32_t operandB ) { int temporaryValue; vtxDeviceCapability_t vtxDeviceCapability; @@ -327,7 +327,7 @@ static int logicConditionCompute( case LOGIC_CONDITION_MODULUS: if (operandB != 0) { - return constrain(operandA % operandB, INT16_MIN, INT16_MAX); + return constrain(operandA % operandB, INT32_MIN, INT32_MAX); } else { return operandA; } @@ -730,10 +730,14 @@ int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue) { } uint32_t getLoiterRadius(uint32_t loiterRadius) { +#ifdef USE_PROGRAMMING_FRAMEWORK if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && !(FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding())) { return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000); } else { return loiterRadius; } +#else + return loiterRadius; +#endif } From 45be762da1660a131bbc8ae66f1e44eba31ecf2c Mon Sep 17 00:00:00 2001 From: Vasily Elkin Date: Fri, 22 Oct 2021 17:58:19 +0300 Subject: [PATCH 10/12] mlx90393 support added --- src/main/CMakeLists.txt | 2 + src/main/drivers/bus.h | 1 + src/main/drivers/compass/compass_mlx90393.c | 176 ++++++++++++++++++++ src/main/drivers/compass/compass_mlx90393.h | 20 +++ src/main/fc/settings.yaml | 2 +- src/main/sensors/compass.c | 14 ++ src/main/sensors/compass.h | 3 +- src/main/target/KAKUTEF7/target.h | 1 + src/main/target/common_hardware.c | 7 + 9 files changed, 224 insertions(+), 2 deletions(-) create mode 100644 src/main/drivers/compass/compass_mlx90393.c create mode 100644 src/main/drivers/compass/compass_mlx90393.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 0eb60439c2..47edcaeee4 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -161,6 +161,8 @@ main_sources(COMMON_SRC drivers/compass/compass_rm3100.h drivers/compass/compass_vcm5883.c drivers/compass/compass_vcm5883.h + drivers/compass/compass_mlx90393.c + drivers/compass/compass_mlx90393.h drivers/compass/compass_msp.c drivers/compass/compass_msp.h diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index e031f4ef4a..bc44825251 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -118,6 +118,7 @@ typedef enum { DEVHW_LIS3MDL, DEVHW_RM3100, DEVHW_VCM5883, + DEVHW_MLX90393, /* Temp sensor chips */ DEVHW_LM75_0, diff --git a/src/main/drivers/compass/compass_mlx90393.c b/src/main/drivers/compass/compass_mlx90393.c new file mode 100644 index 0000000000..a88c290102 --- /dev/null +++ b/src/main/drivers/compass/compass_mlx90393.c @@ -0,0 +1,176 @@ +/* + * 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 "platform.h" + +#ifdef USE_MAG_MLX90393 + +#include +#include + +#include + +#include "build/debug.h" + +#include "common/axis.h" +#include "common/maths.h" +#include "common/utils.h" + +#include "drivers/time.h" +#include "drivers/io.h" +#include "drivers/bus.h" + +#include "drivers/sensor.h" +#include "drivers/compass/compass.h" + +#define MLX90393_MEASURE_3D 0b00001110 + +#define MLX90393_NOP 0b00000000 +#define MLX90393_START_BURST_MODE 0b00010000 //uses with zyxt flags +#define MLX90393_START_WAKE_UP_ON_CHANGE_MODE 0b00100000 //uses with zyxt flags +#define MLX90393_START_SINGLE_MEASUREMENT_MODE 0b00110000 //uses with zyxt flags +#define MLX90393_READ_MEASUREMENT 0b01000000 //uses with zyxt flags +#define MLX90393_READ_REGISTER 0b01010000 +#define MLX90393_WRITE_REGISTER 0b01100000 +#define MLX90393_EXIT_MODE 0b10000000 +#define MLX90393_MEMORY_RECALL 0b11010000 +#define MLX90393_MEMORY_STORE 0b11100000 +#define MLX90393_RESET 0b11110000 + +#define MLX90393_BURST_MODE_FLAG 0b10000000 +#define MLX90393_WAKE_UP_ON_CHANGE_MODE_FLAG 0b01000000 +#define MLX90393_SINGLE_MEASUREMENT_MODE_FLAG 0b00100000 +#define MLX90393_ERROR_FLAG 0b00010000 +#define MLX90393_SINGLE_ERROR_DETECTION_FLAG 0b00001000 +#define MLX90393_RESET_FLAG 0b00000100 +#define MLX90393_D1_FLAG 0b00000010 +#define MLX90393_D0_FLAG 0b00000001 + +#define DETECTION_MAX_RETRY_COUNT 5 + +#define REG_BUF_LEN 3 + +// Register 1 +#define GAIN_SEL_HALLCONF_REG 0x0 //from datasheet 0x0 << 2 = 0x0 +// GAIN - 0b111 +// Hall_conf - 0xC +#define GAIN_SEL_HALLCONF_REG_VALUE 0x007C +// Register 2 +#define TCMP_EN_REG 0x4 //from datasheet 0x1 << 2 = 0x4 +// Burst Data Rate 0b000100 +#define TCMP_EN_REG_VALUE 0x62C4 +// Register 3 +#define RES_XYZ_OSR_FLT_REG 0x8 //from datasheet 0x2 << 2 = 0x8 +// Oversampling 0b01 +// Filtering 0b111 +#define RES_XYZ_OSR_FLT_REG_VALUE 0x001D + + +static void mlx_write_register(magDev_t * mag, uint8_t reg_val, uint16_t value) { + + uint8_t buf[REG_BUF_LEN] = {0}; + + buf[0] = (value >> 8) & 0xFF; + buf[1] = (value >> 0) & 0xFF; + buf[2] = reg_val; + + busWriteBuf(mag->busDev, MLX90393_WRITE_REGISTER, buf, REG_BUF_LEN); + + // PAUSE + delay(20); + // To skip ACK FLAG of Write + uint8_t sig = 0; + busRead(mag->busDev, MLX90393_NOP, &sig); + + return; +} + +// ======================================================================================= +static bool mlx90393Read(magDev_t * mag) +{ + + uint8_t buf[7] = {0}; + + busReadBuf(mag->busDev, MLX90393_READ_MEASUREMENT | MLX90393_MEASURE_3D, buf, 7); + + mag->magADCRaw[X] = ((short)(buf[1] << 8 | buf[2])); + mag->magADCRaw[Y] = ((short)(buf[3] << 8 | buf[4])); + mag->magADCRaw[Z] = ((short)(buf[5] << 8 | buf[6])); + + return true; + +} + +static bool deviceDetect(magDev_t * mag) +{ + for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) { + uint8_t sig = 0; + + bool ack = busRead(mag->busDev, MLX90393_RESET, &sig); + delay(20); + + if (ack && ((sig & MLX90393_RESET_FLAG) == MLX90393_RESET_FLAG)) { // Check Reset Flag -> MLX90393 + return true; + } + } + return false; +} + +//-------------------------------------------------- +static bool mlx90393Init(magDev_t * mag) +{ + uint8_t sig = 0; + + delay(20); + // Remove reset flag + busRead(mag->busDev, MLX90393_NOP, &sig); + // Exit if already in burst mode. (For example when external i2c source power the bus.) + busRead(mag->busDev, MLX90393_EXIT_MODE, &sig); + + // Writing Registers + mlx_write_register(mag, GAIN_SEL_HALLCONF_REG, GAIN_SEL_HALLCONF_REG_VALUE); + mlx_write_register(mag, TCMP_EN_REG, TCMP_EN_REG_VALUE); + mlx_write_register(mag, RES_XYZ_OSR_FLT_REG, RES_XYZ_OSR_FLT_REG_VALUE); + + // Start burst mode + busRead(mag->busDev, MLX90393_START_BURST_MODE | MLX90393_MEASURE_3D, &sig); + + return true; +} + +// ========================================================================== + +bool mlx90393Detect(magDev_t * mag) +{ + mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_MLX90393, mag->magSensorToUse, OWNER_COMPASS); + if (mag->busDev == NULL) { + return false; + } + + if (!deviceDetect(mag)) { + busDeviceDeInit(mag->busDev); + return false; + } + + mag->init = mlx90393Init; + mag->read = mlx90393Read; + + return true; +} + + +#endif diff --git a/src/main/drivers/compass/compass_mlx90393.h b/src/main/drivers/compass/compass_mlx90393.h new file mode 100644 index 0000000000..c23cc61d31 --- /dev/null +++ b/src/main/drivers/compass/compass_mlx90393.h @@ -0,0 +1,20 @@ +/* + * 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 . + */ + +#pragma once + +bool mlx90393Detect(magDev_t* mag); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 876bd16648..c79b4383eb 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -13,7 +13,7 @@ tables: values: ["NONE", "BNO055", "BNO055_SERIAL"] enum: secondaryImuType_e - name: mag_hardware - values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "FAKE"] + values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"] enum: magSensor_e - name: opflow_hardware values: ["NONE", "CXOF", "MSP", "FAKE"] diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index a6ca548dd1..150d716c51 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -42,6 +42,7 @@ #include "drivers/compass/compass_lis3mdl.h" #include "drivers/compass/compass_rm3100.h" #include "drivers/compass/compass_vcm5883.h" +#include "drivers/compass/compass_mlx90393.h" #include "drivers/compass/compass_msp.h" #include "drivers/io.h" #include "drivers/light_led.h" @@ -260,6 +261,19 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse) } FALLTHROUGH; + case MAG_MLX90393: +#ifdef USE_MAG_MLX90393 + if (mlx90393Detect(dev)) { + magHardware = MAG_MLX90393; + break; + } +#endif + /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ + if (magHardwareToUse != MAG_AUTODETECT) { + break; + } + FALLTHROUGH; + case MAG_FAKE: #ifdef USE_FAKE_MAG if (fakeMagDetect(dev)) { diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index 389e516847..9f798f28c5 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -43,7 +43,8 @@ typedef enum { MAG_MSP = 12, MAG_RM3100 = 13, MAG_VCM5883 = 14, - MAG_FAKE = 15, + MAG_MLX90393 = 15, + MAG_FAKE = 16, MAG_MAX = MAG_FAKE } magSensor_e; diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 97764f6e92..1beb8db7ba 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -144,6 +144,7 @@ #define USE_MAG_IST8310 #define USE_MAG_IST8308 #define USE_MAG_LIS3MDL +#define USE_MAG_MLX90393 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index a02d8b683d..072473e596 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -260,6 +260,13 @@ BUSDEV_REGISTER_I2C(busdev_vcm5883, DEVHW_VCM5883, VCM5883_I2C_BUS, 0x0C, NONE, DEVFLAGS_NONE, 0); #endif +#if defined(USE_MAG_MLX90393) + #if !defined(MLX90393_I2C_BUS) + #define MLX90393_I2C_BUS MAG_I2C_BUS + #endif + BUSDEV_REGISTER_I2C(busdev_mlx90393, DEVHW_MLX90393, MLX90393_I2C_BUS, 0x0C, NONE, DEVFLAGS_NONE, 0); +#endif + #endif From ac3bce02cc18c2a6e49a5ae2d8e2dfaf73991067 Mon Sep 17 00:00:00 2001 From: Vasily Elkin Date: Sun, 24 Oct 2021 22:41:53 +0300 Subject: [PATCH 11/12] copyrights changed --- src/main/drivers/compass/compass_mlx90393.c | 8 ++++---- src/main/drivers/compass/compass_mlx90393.h | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/main/drivers/compass/compass_mlx90393.c b/src/main/drivers/compass/compass_mlx90393.c index a88c290102..f98526ca1e 100644 --- a/src/main/drivers/compass/compass_mlx90393.c +++ b/src/main/drivers/compass/compass_mlx90393.c @@ -1,18 +1,18 @@ /* - * This file is part of Cleanflight. + * This file is part of iNav. * - * Cleanflight is free software: you can redistribute it and/or modify + * 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. * - * Cleanflight is distributed in the hope that it will be useful, + * 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 Cleanflight. If not, see . + * along with iNav. If not, see . */ #include "platform.h" diff --git a/src/main/drivers/compass/compass_mlx90393.h b/src/main/drivers/compass/compass_mlx90393.h index c23cc61d31..5d73607294 100644 --- a/src/main/drivers/compass/compass_mlx90393.h +++ b/src/main/drivers/compass/compass_mlx90393.h @@ -1,18 +1,18 @@ /* - * This file is part of Cleanflight. + * This file is part of iNav. * - * Cleanflight is free software: you can redistribute it and/or modify + * 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. * - * Cleanflight is distributed in the hope that it will be useful, + * 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 Cleanflight. If not, see . + * along with iNav. If not, see . */ #pragma once From c926976d35effcd37aa4ebf3c644c2a98cc7502a Mon Sep 17 00:00:00 2001 From: Vasily Elkin Date: Tue, 26 Oct 2021 18:04:16 +0300 Subject: [PATCH 12/12] mlx_write_register renamed to mlx90393WriteRegister --- src/main/drivers/compass/compass_mlx90393.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/compass/compass_mlx90393.c b/src/main/drivers/compass/compass_mlx90393.c index f98526ca1e..c2b5e40114 100644 --- a/src/main/drivers/compass/compass_mlx90393.c +++ b/src/main/drivers/compass/compass_mlx90393.c @@ -80,7 +80,7 @@ #define RES_XYZ_OSR_FLT_REG_VALUE 0x001D -static void mlx_write_register(magDev_t * mag, uint8_t reg_val, uint16_t value) { +static void mlx90393WriteRegister(magDev_t * mag, uint8_t reg_val, uint16_t value) { uint8_t buf[REG_BUF_LEN] = {0}; @@ -142,9 +142,9 @@ static bool mlx90393Init(magDev_t * mag) busRead(mag->busDev, MLX90393_EXIT_MODE, &sig); // Writing Registers - mlx_write_register(mag, GAIN_SEL_HALLCONF_REG, GAIN_SEL_HALLCONF_REG_VALUE); - mlx_write_register(mag, TCMP_EN_REG, TCMP_EN_REG_VALUE); - mlx_write_register(mag, RES_XYZ_OSR_FLT_REG, RES_XYZ_OSR_FLT_REG_VALUE); + mlx90393WriteRegister(mag, GAIN_SEL_HALLCONF_REG, GAIN_SEL_HALLCONF_REG_VALUE); + mlx90393WriteRegister(mag, TCMP_EN_REG, TCMP_EN_REG_VALUE); + mlx90393WriteRegister(mag, RES_XYZ_OSR_FLT_REG, RES_XYZ_OSR_FLT_REG_VALUE); // Start burst mode busRead(mag->busDev, MLX90393_START_BURST_MODE | MLX90393_MEASURE_3D, &sig);