diff --git a/.github/ISSUE_TEMPLATE/Bug_report.md b/.github/ISSUE_TEMPLATE/Bug_report.md index eb7f126be9..ca3482de2d 100644 --- a/.github/ISSUE_TEMPLATE/Bug_report.md +++ b/.github/ISSUE_TEMPLATE/Bug_report.md @@ -9,9 +9,9 @@ assignees: '' **PLEASE MAKE SURE YOU READ AND UNDERSTAND THE SOCIAL MEDIA SUPPORT CHANNELS. QUESTIONS ABOUT FLASHING, CONFIGURING, PILOTING MAY BE CLOSED WITHOUT FURTHER INTERACTION.** -* [Telegram channel](https://t.me/INAVFlight) -* [Facebook group](https://www.facebook.com/groups/INAVOfficial) -* [RC Groups thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-%28navigation-rewrite%29-project) +* [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) **Please double-check that nobody reported the issue before by using search in this bug tracker.** diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index fade190f09..df2a2cc580 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -6,13 +6,13 @@ on: pull_request jobs: build: - runs-on: ubuntu-18.04 + runs-on: ubuntu-latest strategy: matrix: id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Install dependencies run: sudo apt-get update && sudo apt-get -y install ninja-build - name: Setup environment @@ -45,9 +45,9 @@ jobs: test: needs: [build] - runs-on: ubuntu-18.04 + runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Install dependencies run: sudo apt-get update && sudo apt-get -y install ninja-build - name: Run Tests diff --git a/.github/workflows/docs.yml b/.github/workflows/docs.yml index 20f5379c3d..624a129c35 100644 --- a/.github/workflows/docs.yml +++ b/.github/workflows/docs.yml @@ -11,10 +11,10 @@ on: jobs: settings_md: - runs-on: ubuntu-18.04 + runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Install dependencies run: sudo apt-get update && sudo apt-get -y install python3-yaml - name: Check that Settings.md is up to date diff --git a/Dockerfile b/Dockerfile index 96f5c6ce41..34547f51f9 100644 --- a/Dockerfile +++ b/Dockerfile @@ -2,7 +2,9 @@ FROM ubuntu:focal ENV DEBIAN_FRONTEND noninteractive -RUN apt-get update && apt-get install -y git cmake make ruby gcc +RUN apt-get update && apt-get install -y git cmake make ruby gcc python3 python3-pip + +RUN pip install pyyaml RUN useradd inav diff --git a/cmake/docker_docs.sh b/cmake/docker_docs.sh new file mode 100644 index 0000000000..a7effcccb1 --- /dev/null +++ b/cmake/docker_docs.sh @@ -0,0 +1,3 @@ +#!/bin/bash +cd /src/ +python3 src/utils/update_cli_docs.py diff --git a/docs/Battery.md b/docs/Battery.md index 6fc3a12570..48a34a40ea 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -242,7 +242,7 @@ set vbat_min_cell_voltage = 250 #### Simple example with automatic profile switching -In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the iNav defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD. +In this example we want to use two different batteries for the same aircraft and automatically switch between them when the battery is plugged in. The first battery is a Li-Po 2200mAh 3S and the second battery is a LiPo 1500mAh 4S. Since the INAV defaults for the cell detection voltage and max voltage are adequate for standard LiPo batteries they will not be modified. The warning and minimum voltage are not modified either in this example but you can set them to the value you like. Since we are using battery capacities only the warning voltage (kept at default in this example) will be used and only for triggering the battery voltage indicator blinking in the OSD. ``` feature BAT_PROF_AUTOSWITCH @@ -311,6 +311,25 @@ set battery_capacity_warning = 300 set battery_capacity_critical = 150 ``` +#### Change control profile based on battery profile + +You can change the control profile, automatically, based on the battery profile. This allows for fine tuning of each power choice. + +``` +feature BAT_PROF_AUTOSWITCH + + +battery_profile 1 + +set bat_cells = 3 +set controlrate_profile = 1 + +battery_profile 2 + +set bat_cells = 4 +set controlrate_profile = 2 +``` + ## Remaining flight time and flight distance estimation The estimated remaining flight time and flight distance estimations can be displayed on the OSD (for fixed wing only for the moment). They are calculated from the GPS distance from home, remaining battery capacity and average power draw. They are taking into account the requested altitude change and heading to home change after altitude change following the switch to RTH. They are also taking into account the estimated wind if `osd_estimations_wind_compensation` is set to `ON`. When the timer and distance indicator reach 0 they will blink and you need to go home in a straight line manually or by engaging RTH. You should be left with at least `rth_energy_margin`% of battery left when arriving home if the cruise speed and power are set correctly (see bellow). diff --git a/docs/Cli.md b/docs/Cli.md index 9a23568d04..c805fe9250 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -57,6 +57,9 @@ To perform the restore simply paste the saved commands in the Configurator CLI t After restoring it's always a good idea to `dump` or `diff` the settings once again and compare the output with previous one to verify if everything is set as it should be. +## Flight Controller opereration while connected to the CLI + +While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0 onwards). ## CLI Command Reference @@ -86,7 +89,6 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag | `gpspassthrough` | Passthrough gps to serial | | `gvar` | Configure global variables | | `help` | Displays CLI help and command parameters / options | -| `imu2` | Secondary IMU | | `led` | Configure leds | | `logic` | Configure logic conditions | | `map` | Configure rc channel order | @@ -109,7 +111,7 @@ After restoring it's always a good idea to `dump` or `diff` the settings once ag | `servo` | Configure servos | | `set` | Change setting with name=value or blank or * for list | | `smix` | Custom servo mixer | -| `status` | Show status | +| `status` | Show status. Error codes can be looked up [here](https://github.com/iNavFlight/inav/wiki/%22Something%22-is-disabled----Reasons) | | `tasks` | Show task stats | | `temp_sensor` | List or configure temperature sensor(s). See [temperature sensors documentation](Temperature-sensors.md) for more information. | | `version` | Show version | @@ -152,8 +154,8 @@ A shorter form is also supported to enable and disable a single function using ` | DJI_HD_OSD | 21 | 2097152 | | SERVO_SERIAL | 22 | 4194304 | | TELEMETRY_SMARTPORT_MASTER | 23 | 8388608 | -| IMU2 | 24 | 16777216 | -| HDZERO | 25 | 33554432 | +| UNUSED | 24 | 16777216 | +| MSP_DISPLAYPORT | 25 | 33554432 | Thus, to enable MSP and LTM on a port, one would use the function **value** of 17 (1 << 0)+(1<<4), aka 1+16, aka 17. diff --git a/docs/Controls.md b/docs/Controls.md index 6a3600f0ca..f4013cbaff 100644 --- a/docs/Controls.md +++ b/docs/Controls.md @@ -4,7 +4,7 @@ When armed, the aircraft is ready to fly and the motors will spin when throttle is applied. With multirotors, the motors will spin at a slow speed when armed (this feature may be disabled by setting MOTOR_STOP, but for safety reasons, that is not recommended). -Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in iNav 2.2) +Arming and disarming is done using a switch, set up on the modes page. (NOTE: Stick arming was removed in INAV 2.2) **YAW STICK ARMING OVERRIDE:** Arming is disabled when Nav modes are configured and no GPS lock is available or if a WP mission is loaded but the first WP is farther than the `nav_wp_safe_distance` setting. This Arming block can be bypassed if need be by setting `nav_extra_arming_safety` to `ALLOW_BYPASS` and moving the Yaw stick to the high position when the Arm switch is used. This bypasses GPS Arm blocking pre INAV 4.0.0 and both GPS and "First WP too far" Arm blocking from INAV 4.0.0. @@ -80,7 +80,7 @@ For tricopters, you may want to retain the ability to yaw while on the ground, s ## Throttle settings and their interaction -*Terminology. After iNav 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.* +*Terminology. After INAV 2.3, the setting `min_throttle` was replaced with `throttle_idle` which is more appropriate to modern hardware. In this document `min_throttle` may be taken as either the older `min_throttle` value, or the throttle value calculated from the modern `throttle_idle` setting. The way that `throttle_idle` generates a throttle value is described in `Cli.md`.* `min_command` - With motor stop enabled this is the command sent to the esc's when the throttle is below min_check or disarmed. With motor stop disabled, this is the command sent only when the copter is disarmed. This must be set well below motors spinning for safety. diff --git a/docs/Display.md b/docs/Display.md index f65b6b88c6..952f9b0866 100755 --- a/docs/Display.md +++ b/docs/Display.md @@ -1,6 +1,6 @@ # Display -INAV supports displays to provide information to you about your aircraft and iNav state. +INAV supports displays to provide information to you about your aircraft and INAV state. When the aircraft is armed, an "Armed" message is displayed. When it is disarmed, a summary page is displayed. Page cycling has been removed and no other information is currently available diff --git a/docs/GPS_fix_estimation.md b/docs/GPS_fix_estimation.md index cfe943fda5..6bd11a9fd4 100644 --- a/docs/GPS_fix_estimation.md +++ b/docs/GPS_fix_estimation.md @@ -71,9 +71,9 @@ Example: 100 km/h = 100 * 27.77 = 2777 m/s # Disabling GPS sensor from RC controller -![](Screenshots/gps_off_box.png) +![](Screenshots/programming_disable_gps_sensor_fix.png) -For testing purpoces, it is now possible to disable GPS sensor from RC controller: +For testing purpoces, it is possible to disable GPS sensor fix from RC controller in programming tab: *GPS can be disabled only after 1) initial GPS fix is acquired 2) in ARMED mode.* diff --git a/docs/Navigation.md b/docs/Navigation.md index a4ce90aa85..a3bc6b7645 100755 --- a/docs/Navigation.md +++ b/docs/Navigation.md @@ -23,7 +23,7 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co ## NAV POSHOLD mode - position hold Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated. -When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From inav 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically. +When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From INAV 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically. ### CLI parameters affecting POSHOLD mode: * *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own. @@ -59,11 +59,11 @@ NAV WP allows the craft to autonomously navigate a set route defined by waypoint `wp load` - Load list of waypoints from EEPROM to FC. -`wp ` - Set parameters of waypoint with index ``. Note that prior to inav 2.5, the `p2` and `p3` parameters were not required. From 2.5, inav will accept either version but always saves and lists the later full version. +`wp ` - Set parameters of waypoint with index ``. Note that prior to INAV 2.5, the `p2` and `p3` parameters were not required. From 2.5, INAV will accept either version but always saves and lists the later full version. Parameters: - * `` - The action to be taken at the WP. The following are enumerations are available in inav 2.6 and later: + * `` - The action to be taken at the WP. The following are enumerations are available in INAV 2.6 and later: * 0 - Unused / Unassigned * 1 - WAYPOINT * 3 - POSHOLD_TIME @@ -77,13 +77,24 @@ Parameters: * `` - Longitude. - * `` - Altitude in cm. + * `` - Altitude in cm. See `p3` bit 0 for datum definition. * `` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI. * `` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP. - * `` - Reserved for future use. If `p2` is provided, then `p3` is also required. + * `` - A bitfield with four bits reserved for user specified actions. It is anticipated that these actions will be exposed through the logic conditions. + * Bit 0 - Altitude (`alt`) : Relative (to home altitude) (0) or Absolute (AMSL) (1). + * Bit 1 - WP Action 1 + * Bit 2 - WP Action 2 + * Bit 3 - WP Action 3 + * Bit 4 - WP Action 4 + * Bits 5 - 15 : undefined / reserved. + + Note: + + * If `p2` is specified, then `p3` is also required. + * `p3` is only defined for navigable WP types (WAYPOINT, POSHOLD_TIME, LAND). The affect of specifying a non-zero `p3` for other WP types is undefined. * `` - Last waypoint must have `flag` set to 165 (0xA5). @@ -116,7 +127,8 @@ wp 59 0 0 0 0 0 0 0 0 Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers. -**Multi-missions**\ +## Multi-missions + Multi-missions allows up to 9 missions to be stored in the FC at the same time. It is possible to load them into the FC using the CLI. This is acheived by entering single missions into the CLI followed by `wp save` **after** the final mission has been entered (the single missions can be entered one after the other or as a single block entry, it doesn't matter). All missions will then be saved as a Multi Mission in the FC. Saved multi missions display consecutive WP indices from 0 to the last WP in the last mission when displayed using the `wp` command. E.g. to enter 3 missions in the CLI enter each mission as a single mission (start WP index for each mission must be 0). @@ -156,4 +168,4 @@ wp 11 0 0 0 0 0 0 0 0 wp 12 0 0 0 0 0 0 0 0 ... wp 59 0 0 0 0 0 0 0 0 -``` \ No newline at end of file +``` diff --git a/docs/PID tuning.md b/docs/PID tuning.md index 2ed25a11f3..ecd2ffde33 100644 --- a/docs/PID tuning.md +++ b/docs/PID tuning.md @@ -19,7 +19,7 @@ the actual one measured by the gyroscopes, and the controller tries to bring thi Note that: * For fixed wing, a PIFF controller is used. Some documentation is available in the wiki and legacy release notes. -* The iNav Configurator provides conservative example PID settings for various aircraft types. These will require tuning to a particular machine. +* The INAV Configurator provides conservative example PID settings for various aircraft types. These will require tuning to a particular machine. ## PIDs diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index f51f841bb9..9f8352c26b 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -80,6 +80,12 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 44 | MAX | Finds the highest value of `Operand A` and `Operand B` | | 45 | FLIGHT_AXIS_ANGLE_OVERRIDE | Sets the target attitude angle for axis. In other words, when active, it enforces Angle mode (Heading Hold for Yaw) on this axis (Angle mode does not have to be active). `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the angle in degrees | | 46 | FLIGHT_AXIS_RATE_OVERRIDE | Sets the target rate (rotation speed) for axis. `Operand A` defines the axis: `0` - Roll, `1` - Pitch, `2` - Yaw. `Operand B` defines the rate in degrees per second | +| 47 | EDGE | `Operand A` is activation operator [`boolean`], `Operand B` _(Optional)_ is the time for the edge to stay active [ms]. After activation, operator will return `true` until the time in Operand B is reached. If a pure momentary edge is wanted. Just leave `Operand B` as the default `Value: 0` setting. | +| 48 | DELAY | This will return `true` when `Operand A` is true, and the delay time in `Operand B` [ms] has been exceeded. | +| 49 | TIMER | `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. | +| 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater. | +| 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. | + ### Operands | Operand Type | Name | Notes | diff --git a/docs/Rangefinder.md b/docs/Rangefinder.md index 66fcb91345..b7910b0fa6 100644 --- a/docs/Rangefinder.md +++ b/docs/Rangefinder.md @@ -27,4 +27,4 @@ I2C solutions like `VL53L0X` or `INAV_I2C` can be connected to I2C port and used #### Constraints -iNav does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`. \ No newline at end of file +INAV does not support `HC-SR04` and `US-100`. No constrains for I2C like `VL53L0X` or `INAV_I2C`. \ No newline at end of file diff --git a/docs/Rx.md b/docs/Rx.md index df1ed532a3..ee600ce56c 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -9,7 +9,7 @@ There are 2 basic types of receivers: ## PPM Receivers -**Only supported in inav 3.x and below** +**Only supported in INAV 3.x and below** PPM is sometimes known as PPM SUM or CPPM. @@ -47,7 +47,7 @@ http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118 #### Spektrum pesudo RSSI -As of iNav 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal iNav RSSI (0-1023 range). In order to use this feature, the following is necessary: +As of INAV 1.6, a pseudo RSSI, based on satellite fade count is supported and reported as normal INAV RSSI (0-1023 range). In order to use this feature, the following is necessary: * Bind the satellite receiver using a physical RX; the bind function provided by the flight controller is not sufficient. * The CLI variable `rssi_channel` is set to channel 9: @@ -154,7 +154,7 @@ It is possible to use IBUS RX and IBUS telemetry on only one port of the hardwar ### SRXL2 -SRXL2 is a newer Spektrum protocol that provides a bidirectional link between the FC and the receiver, allowing the user to get FC telemetry data and basic settings on Spektrum Gen 2 airware TX. SRXL2 is supported in inav 2.6 and later. It offers improved performance and features compared to earlier Spektrum RX. +SRXL2 is a newer Spektrum protocol that provides a bidirectional link between the FC and the receiver, allowing the user to get FC telemetry data and basic settings on Spektrum Gen 2 airware TX. SRXL2 is supported in INAV 2.6 and later. It offers improved performance and features compared to earlier Spektrum RX. #### Wiring @@ -162,7 +162,7 @@ Signal pin on receiver (labeled "S") must be wired to a **UART TX** pin on the F #### Configuration -Selection of SXRL2 is provided in the inav 2.6 and later configurators. It is necessary to complete the configuration via the CLI; the following settings are recommended: +Selection of SXRL2 is provided in the INAV 2.6 and later configurators. It is necessary to complete the configuration via the CLI; the following settings are recommended: ``` feature TELEMETRY diff --git a/docs/Safehomes.md b/docs/Safehomes.md index e805659518..b5b5a22be8 100644 --- a/docs/Safehomes.md +++ b/docs/Safehomes.md @@ -20,7 +20,7 @@ The safehome operating mode is set using ```safehome_usage_mode```. If ```OFF`` If you frequently use RTH to return back to the arming point, you may not want the aircraft to fly to the safehome. Let it do this at least once to confirm safehomes is working as expected. Afterward, `set safehome_usage_mode = RTH_FS` and the safehome will only be used for failsafe. -When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the iNav failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions. +When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the INAV failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions. When you are choosing safehome locations, ensure that the location is clear of obstructions for a radius more than 50m (`nav_fw_loiter_radius`). As the plane descends, the circles aren't always symmetrical, as wind direction could result in some wider or tighter turns. Also, the direction and length of the final landing stage is also unknown. You want to choose a point that has provides a margin for variation and the final landing. diff --git a/docs/Safety.md b/docs/Safety.md index 96bafe7c3d..e0b969a78a 100644 --- a/docs/Safety.md +++ b/docs/Safety.md @@ -9,7 +9,7 @@ As many can attest, multirotors and RC models in general can be very dangerous, Please consult the [Cli](Cli.md), [Controls](Controls.md), [Failsafe](Failsafe.md) and [Modes](Modes.md) pages for further important information. -You are highly advised to use the Receiver tab in the CleanFlight Configurator, making sure your Rx channel +You are highly advised to use the Receiver tab in the INAV Configurator, making sure your Rx channel values are centered at 1500 (1520 for Futaba RC) with minimum & maximums of 1000 and 2000 (respectively) are reached when controls are operated. Failure to configure these ranges properly can create problems, such as inability to arm (because you can't reach the endpoints) or immediate activation of diff --git a/docs/Screenshots/gps_off_box.png b/docs/Screenshots/gps_off_box.png deleted file mode 100644 index 1c912492d2..0000000000 Binary files a/docs/Screenshots/gps_off_box.png and /dev/null differ diff --git a/docs/Screenshots/programming_disable_gps_sensor_fix.png b/docs/Screenshots/programming_disable_gps_sensor_fix.png new file mode 100644 index 0000000000..ba4ccd2be1 Binary files /dev/null and b/docs/Screenshots/programming_disable_gps_sensor_fix.png differ diff --git a/docs/Settings.md b/docs/Settings.md index b28c5a1e25..d1d339bfd6 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -338,7 +338,7 @@ Internal (configurator) hint. Should not be changed manually | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 4 | +| 0 | 0 | 99 | --- @@ -902,13 +902,13 @@ What failsafe procedure to initiate in Stage 2 when craft is closer to home than --- -### failsafe_mission +### failsafe_mission_delay -If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode +Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end. | Default | Min | Max | | --- | --- | --- | -| ON | OFF | ON | +| 0 | -1 | 600 | --- @@ -1622,163 +1622,13 @@ Power draw at zero throttle used for remaining flight time/distance estimation i --- -### imu2_align_pitch - -Pitch alignment for Secondary IMU. 1/10 of a degree - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -1800 | 3600 | - ---- - -### imu2_align_roll - -Roll alignment for Secondary IMU. 1/10 of a degree - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -1800 | 3600 | - ---- - -### imu2_align_yaw - -Yaw alignment for Secondary IMU. 1/10 of a degree - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -1800 | 3600 | - ---- - -### imu2_gain_acc_x - -Secondary IMU ACC calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_gain_acc_y - -Secondary IMU ACC calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_gain_acc_z - -Secondary IMU ACC calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_gain_mag_x - -Secondary IMU MAG calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_gain_mag_y - -Secondary IMU MAG calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_gain_mag_z - -Secondary IMU MAG calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_hardware - -Selection of a Secondary IMU hardware type. NONE disables this functionality - -| Default | Min | Max | -| --- | --- | --- | -| NONE | | | - ---- - -### imu2_radius_acc - -Secondary IMU MAG calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_radius_mag - -Secondary IMU MAG calibration data - -| Default | Min | Max | -| --- | --- | --- | -| 0 | -32768 | 32767 | - ---- - -### imu2_use_for_osd_ahi - -If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - -### imu2_use_for_osd_heading - -If set to ON, Secondary IMU data will be used for Analog OSD heading - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - -### imu2_use_for_stabilized - -If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH) - -| Default | Min | Max | -| --- | --- | --- | -| OFF | OFF | ON | - ---- - ### imu_acc_ignore_rate -Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes +Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 20 | +| 15 | 0 | 30 | --- @@ -1788,7 +1638,7 @@ Half-width of the interval to gradually reduce accelerometer weight. Centered at | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 5 | +| 5 | 0 | 10 | --- @@ -1808,7 +1658,7 @@ Inertial Measurement Unit KI Gain for compass measurements | Default | Min | Max | | --- | --- | --- | -| 0 | | 65535 | +| 50 | | 65535 | --- @@ -1818,7 +1668,7 @@ Inertial Measurement Unit KP Gain for accelerometer measurements | Default | Min | Max | | --- | --- | --- | -| 1000 | | 65535 | +| 2000 | | 65535 | --- @@ -1828,13 +1678,33 @@ Inertial Measurement Unit KP Gain for compass measurements | Default | Min | Max | | --- | --- | --- | -| 5000 | | 65535 | +| 2000 | | 65535 | + +--- + +### imu_gps_yaw_windcomp + +Wind compensation in heading estimation from gps groundcourse(fixed wing only) + +| Default | Min | Max | +| --- | --- | --- | +| ON | OFF | ON | + +--- + +### imu_inertia_comp_method + +Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop + +| Default | Min | Max | +| --- | --- | --- | +| VELNED | | | --- ### inav_allow_dead_reckoning -Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation +Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation | Default | Min | Max | | --- | --- | --- | @@ -1934,7 +1804,7 @@ _// TODO_ ### inav_use_gps_velned -Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. +Defined if INAV should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF INAV will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. | Default | Min | Max | | --- | --- | --- | @@ -2822,6 +2692,16 @@ Maximum climb/descent rate that UAV is allowed to reach during navigation modes. --- +### nav_auto_disarm_delay + +Delay before craft disarms when `nav_disarm_on_landing` is set (ms) + +| Default | Min | Max | +| --- | --- | --- | +| 2000 | 100 | 10000 | + +--- + ### nav_auto_speed Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only] @@ -2834,7 +2714,7 @@ Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no speci ### nav_disarm_on_landing -If set to ON, iNav disarms the FC after landing +If set to ON, INAV disarms the FC after landing | Default | Min | Max | | --- | --- | --- | @@ -2872,16 +2752,6 @@ Enable the possibility to manually increase the throttle in auto throttle contro --- -### nav_fw_auto_disarm_delay - -Delay before plane disarms when `nav_disarm_on_landing` is set (ms) - -| Default | Min | Max | -| --- | --- | --- | -| 2000 | 100 | 10000 | - ---- - ### nav_fw_bank_angle Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll @@ -3352,6 +3222,16 @@ Deadband for heading trajectory PID controller. When heading error is below the --- +### nav_land_detect_sensitivity + +Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases. + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 1 | 15 | + +--- + ### nav_land_maxalt_vspd Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s] @@ -3442,16 +3322,6 @@ Max allowed above the ground altitude for terrain following mode --- -### nav_mc_auto_disarm_delay - -Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (ms) - -| Default | Min | Max | -| --- | --- | --- | -| 2000 | 100 | 10000 | - ---- - ### nav_mc_bank_angle Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude @@ -3942,6 +3812,16 @@ If set to ON, waypoints will be automatically loaded from EEPROM to the FC durin --- +### nav_wp_max_safe_distance + +First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check. + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 1500 | + +--- + ### nav_wp_mission_restart Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint. @@ -3954,11 +3834,11 @@ Sets restart behaviour for a WP mission when interrupted mid mission. START from ### nav_wp_multi_mission_index -Index of mission selected from multi mission WP entry loaded in flight controller. 1 is the first useable WP mission in the entry. Limited to a maximum of 9 missions. Set index to 0 to display current active WP count in OSD Mission field. +Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions. | Default | Min | Max | | --- | --- | --- | -| 1 | 0 | 9 | +| 1 | 1 | 9 | --- @@ -3972,16 +3852,6 @@ Waypoint radius [cm]. Waypoint would be considered reached if machine is within --- -### nav_wp_safe_distance - -First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. - -| Default | Min | Max | -| --- | --- | --- | -| 10000 | | 65000 | - ---- - ### opflow_hardware Selection of OPFLOW hardware. @@ -4042,6 +3912,16 @@ Max pitch, in degrees, for OSD artificial horizon --- +### osd_ahi_pitch_interval + +Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 30 | + +--- + ### osd_ahi_reverse_roll Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement. @@ -4834,7 +4714,7 @@ IMPERIAL, METRIC, UK ### osd_video_system -Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, and `HD` +Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO` and 'DJIWTF' | Default | Min | Max | | --- | --- | --- | @@ -5944,7 +5824,7 @@ VTX RF power level to use. The exact number of mw depends on the VTX hardware. ### vtx_smartaudio_alternate_softserial_method -Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier. +Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier. | Default | Min | Max | | --- | --- | --- | diff --git a/docs/Telemetry.md b/docs/Telemetry.md index 930e9bf9ae..b4c64ba1d2 100644 --- a/docs/Telemetry.md +++ b/docs/Telemetry.md @@ -212,7 +212,7 @@ The INAV implementation of LTM implements the following frames: * S-FRAME: Status (voltage, current+, RSSI, airspeed+, status). Item suffixed '+' not implemented in INAV. * O-FRAME: Origin (home position, lat, long, altitude, fix) -In addition, in iNav: +In addition, in INAV: * N-FRAME: Navigation information (GPS mode, Nav mode, Nav action, Waypoint number, Nav Error, Nav Flags). * X-FRAME: Extra information. Currently HDOP is reported. diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md index 93a9bba4d4..9a2eddea3a 100644 --- a/docs/USB_Mass_Storage_(MSC)_mode.md +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -1,6 +1,6 @@ ## Overview -iNav (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card). +INAV (after 2.3.0) offers USB MSC (mass storage device class) SD card and internal flash access, meaning you can mount the FC (SD card / internal flash) as an OS file system via USB to read BB logs (and delete them from an SD card). When MSC mode is used with **internal flash** there are a few differences compared to **SD card** as it's a virtual file system: @@ -62,7 +62,7 @@ $ md5sum /tmp/{msc,sdc}logs/LOG00035.TXT 7cd259777ba4f29ecbde2f76882b1840 /tmp/msclogs/LOG00035.TXT 7cd259777ba4f29ecbde2f76882b1840 /tmp/sdclogs/LOG00035.TXT ``` -You should also be able to run blackbox utilities (e.g. the iNav specific `blackbox_decode`) without errors on the files, e.g. +You should also be able to run blackbox utilities (e.g. the INAV specific `blackbox_decode`) without errors on the files, e.g. ``` $ blackbox_decode --stdout --merge-gps > /dev/null /tmp/msclogs/LOG00035.TXT diff --git a/docs/Wireless Connections (BLE, TCP and UDP).md b/docs/Wireless Connections (BLE, TCP and UDP).md index e0c4189b0d..8d635e1d1e 100644 --- a/docs/Wireless Connections (BLE, TCP and UDP).md +++ b/docs/Wireless Connections (BLE, TCP and UDP).md @@ -1,6 +1,6 @@ # Wireless connections -From iNav 5 onwards, the Configurator supports wireless connections via Bluetooth Low Energy (BLE) and Wifi (UDP and TCP). +From INAV 5 onwards, the Configurator supports wireless connections via Bluetooth Low Energy (BLE) and Wifi (UDP and TCP). ## BLE @@ -13,7 +13,7 @@ The following adapters are supported: Flightcontrollers with BLE should also work, if you have an adapter/FC that doesn't work, open an issue here on Github and we will add it. ### Configuring the BLE modules -Activate MSP in iNav on a free UART port and set the Bluetooth module to the appropriate baud rate. +Activate MSP in INAV on a free UART port and set the Bluetooth module to the appropriate baud rate. Example for a HM-10 module: @@ -22,7 +22,7 @@ Standard baud rate is 115200 baud, CR+LF ``` AT+BAUD4 -AT+NAMEiNav +AT+NAMEINAV ``` The baud rate values: @@ -46,8 +46,8 @@ Allows connections via Wifi. Hardware: - DIY, ESP8266 based: - This project can be used to make iNav Wifi enabled: https://github.com/Scavanger/MSPWifiBridge + This project can be used to make INAV Wifi enabled: https://github.com/Scavanger/MSPWifiBridge A small ESP01S module should still fit anywhere. - ExpressLRS Wifi: - Should work (via TCP, port 5761), but untested due to lack of hardware from the developer. CLI and presets do not work here, problem in ELRS, not in iNav. + Should work (via TCP, port 5761), but untested due to lack of hardware from the developer. CLI and presets do not work here, problem in ELRS, not in INAV. diff --git a/docs/boards/Matek F722PX-WPX-HD.md b/docs/boards/Matek F722PX-WPX-HD.md new file mode 100644 index 0000000000..961ea06323 --- /dev/null +++ b/docs/boards/Matek F722PX-WPX-HD.md @@ -0,0 +1,16 @@ +# Board - MATEKSYS F722-PX/WPX/HD + +## Vendor Information / specification +http://www.mateksys.com/?portfolio=f722-px +http://www.mateksys.com/?portfolio=f722-wpx +http://www.mateksys.com/?portfolio=f722-hd + +## Firmware + +Three firmware variants are available. + +* `inav_x.y.z_MATEKF722PX.hex` +* `inav_x.y.z_MATEKF722WPX.hex` +* `inav_x.y.z_MATEKF722PX_PINIO.hex` + +The WPX vairant is for the MATEK F722-WPX wing flight controller. The PX variants are for the MATEK F722-PX and MATEK F722-HD flight controllers. The PINIO variant adds USER 3 PINIO as a replacement to UART 5 TX and USER 4 PINIO as a replacement to UART 5 RX. \ No newline at end of file diff --git a/docs/boards/MatekF405 Wing.md b/docs/boards/MatekF405 Wing.md index 5a92ce0d89..2a9cc34d74 100644 --- a/docs/boards/MatekF405 Wing.md +++ b/docs/boards/MatekF405 Wing.md @@ -18,6 +18,11 @@ * SBUS pin is connected to UART2 * SmartPort telemetry can be setup with `SoftwareSerial` feature turned on, SmartPort configured in SoftwareSerial1 and receiver connected to UART2 TX pad +### Alternate targets + +#### MATEKF045SE_PINIO +`MATEKF045SE_PINIO` replaces UART 6 with a PINIO interface. TX6 for PINIO USER 1 and RX6 for PINIO USER 2 + ## Where to buy: * [Banggood](https://inavflight.com/shop/p/MATEKF405WING) diff --git a/docs/boards/MatekF405.md b/docs/boards/MatekF405.md index 6d98c20adb..9326922845 100644 --- a/docs/boards/MatekF405.md +++ b/docs/boards/MatekF405.md @@ -44,7 +44,7 @@ Due to differences on the board (I2C - see below), there are two firmware varian ### I2C The F405-AIO, STD, CTR boards expose dedicated I2C pads. -The F405-OSD does not expose I2C. For iNav there is a software I2C provision using the USART3 pads, as: +The F405-OSD does not expose I2C. For INAV there is a software I2C provision using the USART3 pads, as: * SDA => RX3, SCL => TX3 * Do not assign any serial function to USART3 diff --git a/docs/boards/Omnibus F4.md b/docs/boards/Omnibus F4.md index 3c6b78f10a..6a4a4de910 100644 --- a/docs/boards/Omnibus F4.md +++ b/docs/boards/Omnibus F4.md @@ -71,7 +71,6 @@ More target options: * Integrated current meter * Uses target **OMNIBUSF4PRO** * Omnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_LEDSTRIPM5** target (LED strip on M5 pin instead of incorrectly wired dedicated connection) -* If you want to power your servos from the servo rail you will have to bridge the 5v to another 5v pad from the board or take it from the esc ### Omnibus F4 Pro Corner @@ -195,9 +194,24 @@ SmartPort / FPort is possible without a hardware inverter by using one of the OM * [Omnibus F4 Pro](https://inavflight.com/shop/p/OMNIBUSF4PRO) * [Omnibus F4 Nano V6](https://inavflight.com/shop/s/bg/1320256) +## Powering servos and FC (fixed wing) +These boards have a set of diodes which allow you to power servos +and the flight controller in three different ways, without back EMF +from the servos damaging the electronics. Most commonly an ESC +connected to the servo rail provides 5V power for the servos. + +If your opto-isolated ESC doesn't provide 5V and you have servos, +connect a 5 BEC to the servo rail (any of the servo outputs 1-4). + +The BEC can also power the board electronics, through a protective diode. + +Do NOT bridge any other 5V pad to the servo rail, or connect servos +to any other 5V pad on the board. The back EMF from a a servo can +destroy the chips on the board. + # Wiring diagrams for Omnibus F4 Pro -Following diagrams applies to _Pro_ version with integrated current meter and JST connectors only +Following diagrams apply to _Pro_ version with integrated current meter and JST connectors only ## Board layout diff --git a/docs/boards/PixRacer R14.md b/docs/boards/PixRacer R14.md index f686127f2f..48e7322230 100644 --- a/docs/boards/PixRacer R14.md +++ b/docs/boards/PixRacer R14.md @@ -31,7 +31,7 @@ Then follow this : https://pixhawk.org/dev/bootloader_update ### Interface and Ports -Total UARTS Recognized by iNav -> 8 +Total UARTS Recognized by INAV -> 8 #### USART1 * Location : Top diff --git a/docs/boards/SPEEDYBEEF405V3.md b/docs/boards/SPEEDYBEEF405V3.md new file mode 100644 index 0000000000..8dd310c385 --- /dev/null +++ b/docs/boards/SPEEDYBEEF405V3.md @@ -0,0 +1,3 @@ +# SpeedyBee F405 V3 + +> Notice: At the moment, DSHOT is not supported on SpeedyBe F405 V3. Use Multishot instead \ No newline at end of file diff --git a/docs/development/Blackbox Internals.md b/docs/development/Blackbox Internals.md index aeac820589..bf7991c704 100644 --- a/docs/development/Blackbox Internals.md +++ b/docs/development/Blackbox Internals.md @@ -1,11 +1,8 @@ # Blackbox logging internals -The Blackbox is designed to record the raw internal state of the flight controller at near-maximum rate. By logging the -raw inputs and outputs of key flight systems, the Blackbox log aims to allow the offline bench-top simulation, debugging, -and testing of flight control algorithms using data collected from real flights. +The Blackbox is designed to record the raw internal state of the flight controller at near-maximum rate. By logging the raw inputs and outputs of key flight systems, the Blackbox log aims to allow the offline bench-top simulation, debugging, and testing of flight control algorithms using data collected from real flights. -A typical logging regime might capture 30 different state variables (for an average of 28 bytes per frame) at a sample -rate of 900Hz. That's about 25,000 bytes per second, which is 250,000 baud with a typical 8-N-1 serial encoding. +A typical logging regime might capture 30 different state variables (for an average of 28 bytes per frame) at a sample rate of 900Hz. That's about 25,000 bytes per second, which is 250,000 baud with a typical 8-N-1 serial encoding. ## References @@ -14,163 +11,118 @@ Please refer to the source code to clarify anything this document leaves unclear * INAV's Blackbox logger: [blackbox.c](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox.c), [blackbox_io.c](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox_io.c), [blackbox_fielddefs.h](https://github.com/iNavFlight/inav/blob/master/src/main/blackbox/blackbox_fielddefs.h) -* [C implementation of the Blackbox log decoder](https://github.com/cleanflight/blackbox-tools/blob/master/src/parser.c) -* [JavaScript implementation of the Blackbox log decoder](https://github.com/cleanflight/blackbox-log-viewer/blob/master/js/flightlog_parser.js) +* [C implementation of the Blackbox log decoder](https://github.com/iNavFlight/blackbox-tools) +* [JavaScript implementation of the Blackbox log decoder](https://github.com/iNavFlight/blackbox-log-viewer) ## Logging cycle -Blackbox is designed for flight controllers that are based around the concept of a "main loop". During each main loop -iteration, the flight controller will read some state from sensors, run some flight control algorithms, and produce some -outputs. For each of these loop iterations, a Blackbox "logging iteration" will be executed. This will read data that -was stored during the execution of the main loop and log this data to an attached logging device. The data will include -algorithm inputs such as sensor and RC data, intermediate results from flight control algorithms, and algorithm outputs -such as motor commands. + +Blackbox is designed for flight controllers that are based around the concept of a "main loop". During each main loop iteration, the flight controller will read some state from sensors, run some flight control algorithms, and produce some outputs. For each of these loop iterations, a Blackbox "logging iteration" will be executed. This will read data that was stored during the execution of the main loop and log this data to an attached logging device. The data will include +algorithm inputs such as sensor and RC data, intermediate results from flight control algorithms, and algorithm outputs such as motor commands. ## Log frame types -Each event which is recorded to the log is packaged as a "log frame". Blackbox only uses a handful of different types of -log frames. Each frame type is identified by a single capital letter. + +Each event which is recorded to the log is packaged as a "log frame". Blackbox only uses a handful of different types of log frames. Each frame type is identified by a single capital letter. ### Main frames: I, P -The most basic kind of logged frames are the "main frames". These record the primary state of the flight controller (RC -input, gyroscopes, flight control algorithm intermediates, motor outputs), and are logged during every logging -iteration. -Each main frame must contain at least two fields, "loopIteration" which records the index of the current main loop -iteration (starting at zero for the first logged iteration), and "time" which records the timestamp of the beginning of -the main loop in microseconds (this needn't start at zero, on INAV it represents the system uptime). +The most basic kind of logged frames are the "main frames". These record the primary state of the flight controller (RC input, gyroscopes, flight control algorithm intermediates, motor outputs), and are logged during every logging iteration. -There are two kinds of main frames, "I" and "P". "I", or "intra" frames are like video keyframes. They can be decoded -without reference to any previous frame, so they allow log decoding to be resynchronized in the event of log damage. "P" -or "inter" frames use an encoding which references previously logged frames in order to reduce the required datarate. -When one interframe fails to decode, all following interframes will be undecodable up until the next intraframe. +Each main frame must contain at least two fields, "loopIteration" which records the index of the current main loop iteration (starting at zero for the first logged iteration), and "time" which records the timestamp of the beginning of the main loop in microseconds (this needn't start at zero, on INAV it represents the system uptime). + +There are two kinds of main frames, "I" and "P". "I", or "intra" frames are like video keyframes. They can be decoded without reference to any previous frame, so they allow log decoding to be resynchronized in the event of log damage. "P" or "inter" frames use an encoding which references previously logged frames in order to reduce the required datarate. When one interframe fails to decode, all following interframes will be undecodable up until the next intraframe. ### GPS frames: G, H -Because the GPS is updated so infrequently, GPS data is logged in its own dedicated frames. These are recorded whenever -the GPS data changes (not necessarily alongside every main frame). Like the main frames, the GPS frames have their own -intra/inter encoding system. -The "H" or "home" frame records the lat/lon of a reference point. The "G" or "GPS" frame records the current state of -the GPS system (current position, altitude etc.) based on the reference point. The reference point can be updated -(infrequently) during the flight, and is logged whenever it changes. +Because the GPS is updated so infrequently, GPS data is logged in its own dedicated frames. These are recorded whenever the GPS data changes (not necessarily alongside every main frame). Like the main frames, the GPS frames have their own intra/inter encoding system. -To allow "G" frames to continue be decoded in the event that an "H" update is dropped from the log, the "H" frame is -logged periodically even if it has not changed (say, every 10 seconds). This caps the duration of unreadble "G" frames -that will result from a single missed "H" change. +The "H" or "home" frame records the lat/lon of a reference point. The "G" or "GPS" frame records the current state of the GPS system (current position, altitude etc.) based on the reference point. The reference point can be updated (infrequently) during the flight, and is logged whenever it changes. + +To allow "G" frames to continue be decoded in the event that an "H" update is dropped from the log, the "H" frame is logged periodically even if it has not changed (say, every 10 seconds). This caps the duration of unreadble "G" frames that will result from a single missed "H" change. ### Slow frames: S -Some flight controller state is updated very infrequently (on the order of once or twice a minute). Logging the fact -that this data had not been updated during every single logging iteration would be a waste of bandwidth, so these frames -are only logged when the "slow" state actually changes. -All Slow frames are logged as intraframes. An interframe encoding scheme can't be used for Slow frames, because one -damaged frame causes all subsequent interframes to be undecodable. Because Slow frames are written so infrequently, one -missing Slow frame could invalidate minutes worth of Slow state. +Some flight controller state is updated very infrequently (on the order of once or twice a minute). Logging the fact that this data had not been updated during every single logging iteration would be a waste of bandwidth, so these frames are only logged when the "slow" state actually changes. -On INAV, Slow frames are currently used to log data like the user-chosen flight mode and the current failsafe -state. +All Slow frames are logged as intraframes. An interframe encoding scheme can't be used for Slow frames, because one damaged frame causes all subsequent interframes to be undecodable. Because Slow frames are written so infrequently, one missing Slow frame could invalidate minutes worth of Slow state. + +On INAV, Slow frames are currently used to log data like the user-chosen flight mode and the current failsafe state. ### Event frames: E -Some flight controller data is updated so infrequently or exists so transiently that we do not log it as a flight -controller "state". Instead, we log it as a state *transition* . This data is logged in "E" or "event" frames. Each event -frame payload begins with a single byte "event type" field. The format of the rest of the payload is not encoded in the + +Some flight controller data is updated so infrequently or exists so transiently that we do not log it as a flight controller "state". Instead, we log it as a state *transition* . This data is logged in "E" or "event" frames. Each event frame payload begins with a single byte "event type" field. The format of the rest of the payload is not encoded in the flight log, so its interpretation is left up to an agreement of the writer and the decoder. -For example, one event that INAV logs is that the user has adjusted a system setting (such as a PID setting) -using INAV's inflight adjustments feature. The event payload notes which setting was adjusted and the new value -for the setting. +For example, one event that INAV logs is that the user has adjusted a system setting (such as a PID setting) using INAV's inflight adjustments feature. The event payload notes which setting was adjusted and the new value for the setting. -Because these setting updates are so rare, it would be wasteful to treat the settings as "state" and log the fact that -the setting had not been changed during every logging iteration. It would be infeasible to periodically log the system -settings using an intra/interframe scheme, because the intraframes would be so large. Instead we only log the -transitions as events, accept the small probability that any one of those events will be damaged/absent in the log, and -leave it up to log readers to decide the extent to which they are willing to assume that the state of the setting -between successfully-decoded transition events was truly unchanged. +Because these setting updates are so rare, it would be wasteful to treat the settings as "state" and log the fact that the setting had not been changed during every logging iteration. It would be infeasible to periodically log the system settings using an intra/interframe scheme, because the intraframes would be so large. Instead we only log the transitions as events, accept the small probability that any one of those events will be damaged/absent in the log, and leave it up to log readers to decide the extent to which they are willing to assume that the state of the setting between successfully-decoded transition events was truly unchanged. ## Log field format + For every field in a given frame type, there is an associated name, predictor, and encoding. -When a field is written, the chosen predictor is computed for the field, then this predictor value is subtracted from -the raw field value. Finally, the encoder is used to transform the value into bytes to be written to the logging device. +When a field is written, the chosen predictor is computed for the field, then this predictor value is subtracted from the raw field value. Finally, the encoder is used to transform the value into bytes to be written to the logging device. ### Field predictors -The job of the predictor is to bring the value to be encoded as close to zero as possible. The predictor may be based -on the values seen for the field in a previous frame, or some other value such as a fixed value or a value recorded in -the log headers. For example, the battery voltage values in "I" intraframes in INAV use a reference voltage that -is logged as part of the headers as a predictor. This assumes that battery voltages will be broadly similar to the -initial pack voltage of the flight (e.g. 4S battery voltages are likely to lie within a small range for the whole -flight). In "P" interframes, the battery voltage will instead use the previously-logged voltage as a predictor, because -the correlation between successive voltage readings is high. + +The job of the predictor is to bring the value to be encoded as close to zero as possible. The predictor may be based on the values seen for the field in a previous frame, or some other value such as a fixed value or a value recorded in the log headers. For example, the battery voltage values in "I" intraframes in INAV use a reference voltage that is logged as part of the headers as a predictor. This assumes that battery voltages will be broadly similar to the initial pack voltage of the flight (e.g. 4S battery voltages are likely to lie within a small range for the whole flight). In "P" interframes, the battery voltage will instead use the previously-logged voltage as a predictor, because the correlation between successive voltage readings is high. These predictors are presently available: #### Predict zero (0) -This predictor is the null-predictor which doesn't modify the field value at all. It is a common choice for fields -which are already close to zero, or where no better history is available (e.g. in intraframes which may not rely on the -previous value of fields). + +This predictor is the null-predictor which doesn't modify the field value at all. It is a common choice for fields which are already close to zero, or where no better history is available (e.g. in intraframes which may not rely on the previous value of fields). #### Predict last value (1) -This is the most common predictor in interframes. The last-logged value of the field will be used as the predictor, and -subtracted from the raw field value. For fields which don't change very often, this will make their encoded value be -normally zero. Most fields have some time-correlation, so this predictor should reduce the magnitude of all but the -noisiest fields. + +This is the most common predictor in interframes. The last-logged value of the field will be used as the predictor, and subtracted from the raw field value. For fields which don't change very often, this will make their encoded value be normally zero. Most fields have some time-correlation, so this predictor should reduce the magnitude of all but the noisiest fields. #### Predict straight line (2) -This predictor assumes that the slope between the current measurement and the previous one will be similar to the -slope between the previous measurement and the one before that. This is common for fields which increase at a steady rate, -such as the "time" field. The predictor is `history_age_2 - 2 * history_age_1`. + +This predictor assumes that the slope between the current measurement and the previous one will be similar to the slope between the previous measurement and the one before that. This is common for fields which increase at a steady rate, such as the "time" field. The predictor is `history_age_2 - 2 * history_age_1`. #### Predict average 2 (3) -This predictor is the average of the two previously logged values of the field (i.e. `(history_age_1 + history_age_2) / 2` -). It is used when there is significant random noise involved in the field, which means that the average of the recent -history is a better predictor of the next value than the previous value on its own would be (for example, in gyroscope -or motor measurements). + +This predictor is the average of the two previously logged values of the field (i.e. `(history_age_1 + history_age_2) / 2` ). It is used when there is significant random noise involved in the field, which means that the average of the recent history is a better predictor of the next value than the previous value on its own would be (for example, in gyroscope or motor measurements). #### Predict minthrottle (4) -This predictor subtracts the value of "minthrottle" which is included in the log header. In INAV, motors always -lie in the range of `[minthrottle ... maxthrottle]` when the craft is armed, so this predictor is used for the first -motor value in intraframes. + +This predictor subtracts the value of "minthrottle" which is included in the log header. In INAV, motors always lie in the range of `[minthrottle ... maxthrottle]` when the craft is armed, so this predictor is used for the first motor value in intraframes. #### Predict motor[0] (5) -This predictor is set to the value of `motor[0]` which was decoded earlier within the current frame. It is used in -intraframes for every motor after the first one, because the motor commands typically lie in a tight grouping. + +This predictor is set to the value of `motor[0]` which was decoded earlier within the current frame. It is used in intraframes for every motor after the first one, because the motor commands typically lie in a tight grouping. #### Predict increment (6) -This predictor assumes that the field will be incremented by 1 unit for every main loop iteration. This is used to -predict the `loopIteration` field, which increases by 1 for every loop iteration. + +This predictor assumes that the field will be incremented by 1 unit for every main loop iteration. This is used to predict the `loopIteration` field, which increases by 1 for every loop iteration. #### Predict home-coord (7) -This predictor is set to the corresponding latitude or longitude field from the GPS home coordinate (which was logged in -a preceding "H" frame). If no preceding "H" frame exists, the value is marked as invalid. + +This predictor is set to the corresponding latitude or longitude field from the GPS home coordinate (which was logged in a preceding "H" frame). If no preceding "H" frame exists, the value is marked as invalid. #### Predict 1500 (8) -This predictor is set to a fixed value of 1500. It is preferred for logging servo values in intraframes, since these -typically lie close to the midpoint of 1500us. + +This predictor is set to a fixed value of 1500. It is preferred for logging servo values in intraframes, since these typically lie close to the midpoint of 1500us. #### Predict vbatref (9) -This predictor is set to the "vbatref" field written in the log header. It is used when logging intraframe battery -voltages in INAV, since these are expected to be broadly similar to the first battery voltage seen during + +This predictor is set to the "vbatref" field written in the log header. It is used when logging intraframe battery voltages in INAV, since these are expected to be broadly similar to the first battery voltage seen during arming. #### Predict last main-frame time (10) -This predictor is set to the last logged `time` field from the main frame. This is used when predicting timestamps of -non-main frames (e.g. that might be logging the timing of an event that happened during the main loop cycle, like a GPS + +This predictor is set to the last logged `time` field from the main frame. This is used when predicting timestamps of non-main frames (e.g. that might be logging the timing of an event that happened during the main loop cycle, like a GPS reading). ### Field encoders -The field encoder's job is to use fewer bits to represent values which are closer to zero than for values that are -further from zero. Blackbox supports a range of different encoders, which should be chosen on a per-field basis in order -to minimize the encoded data size. The choice of best encoder is based on the probability distribution of the values -which are to be encoded. For example, if a field is almost always zero, then an encoding should be chosen for it which -can encode that case into a very small number of bits, such as one. Conversely, if a field is normally 8-16 bits large, -it would be wasteful to use an encoder which provided a special short encoded representation for zero values, because -this will increase the encoded length of larger values. + +The field encoder's job is to use fewer bits to represent values which are closer to zero than for values that are further from zero. Blackbox supports a range of different encoders, which should be chosen on a per-field basis in order to minimize the encoded data size. The choice of best encoder is based on the probability distribution of the values which are to be encoded. For example, if a field is almost always zero, then an encoding should be chosen for it which can encode that case into a very small number of bits, such as one. Conversely, if a field is normally 8-16 bits large, it would be wasteful to use an encoder which provided a special short encoded representation for zero values, because this will increase the encoded length of larger values. These encoders are presently available: #### Unsigned variable byte (1) -This is the most straightforward encoding. This encoding uses the lower 7 bits of an encoded byte to store the lower 7 -bits of the field's value. The high bit of that encoded byte is set to one if more than 7 bits are required to store the -value. If the value did exceed 7 bits, the lower 7 bits of the value (which were written to the log) are removed from -the value (by right shift), and the encoding process begins again with the new value. + +This is the most straightforward encoding. This encoding uses the lower 7 bits of an encoded byte to store the lower 7 bits of the field's value. The high bit of that encoded byte is set to one if more than 7 bits are required to store the value. If the value did exceed 7 bits, the lower 7 bits of the value (which were written to the log) are removed from the value (by right shift), and the encoding process begins again with the new value. This can be represented by the following algorithm: @@ -194,17 +146,14 @@ Here are some example values encoded using variable-byte encoding: | 23456 | 0xA0 0xB7 0x01 | #### Signed variable byte (0) -This encoding applies a pre-processing step to fold negative values into positive ones, then the resulting unsigned -number is encoded using unsigned variable byte encoding. The folding is accomplished by "ZigZag" encoding, which is -represented by: + +This encoding applies a pre-processing step to fold negative values into positive ones, then the resulting unsigned number is encoded using unsigned variable byte encoding. The folding is accomplished by "ZigZag" encoding, which is represented by: ```c unsigned32 = (signed32 << 1) ^ (signed32 >> 31) ``` -ZigZag encoding is preferred against simply casting the signed integer to unsigned, because casting would cause small -negative quantities to appear to be very large unsigned integers, causing the encoded length to be similarly large. -ZigZag encoding ensures that values near zero are still near zero after encoding. +ZigZag encoding is preferred against simply casting the signed integer to unsigned, because casting would cause small negative quantities to appear to be very large unsigned integers, causing the encoded length to be similarly large. ZigZag encoding ensures that values near zero are still near zero after encoding. Here are some example integers encoded using ZigZag encoding: @@ -218,26 +167,18 @@ Here are some example integers encoded using ZigZag encoding: | -2147483648 | 4294967295 | #### Neg 14-bit (3) -The value is negated, treated as an unsigned 14 bit integer, then encoded using unsigned variable byte encoding. This -bizarre encoding is used in INAV for battery pack voltages. This is because battery voltages are measured using a -14-bit ADC, with a predictor which is set to the battery voltage during arming, which is expected to be higher than any -voltage experienced during flight. After the predictor is subtracted, the battery voltage will almost certainly be below -zero. -This results in small encoded values when the voltage is closely below the initial one, at the expense of very large -encoded values if the voltage rises higher than the initial one. +The value is negated, treated as an unsigned 14 bit integer, then encoded using unsigned variable byte encoding. This bizarre encoding is used in INAV for battery pack voltages. This is because battery voltages are measured using a 14-bit ADC, with a predictor which is set to the battery voltage during arming, which is expected to be higher than any voltage experienced during flight. After the predictor is subtracted, the battery voltage will almost certainly be below zero. + +This results in small encoded values when the voltage is closely below the initial one, at the expense of very large encoded values if the voltage rises higher than the initial one. #### Elias delta unsigned 32-bit (4) -Because this encoding produces a bitstream, this is the only encoding for which the encoded value might not be a whole -number of bytes. If the bitstream isn't aligned on a byte boundary by the time the next non-Elias Delta field arrives, -or the end of the frame is reached, the final byte is padded with zeros byte-align the stream. This encoding requires -more CPU time than the other encodings because of the bit juggling involved in writing the bitstream. -When this encoder is chosen to encode all of the values in INAV interframes, it saves about 10% bandwidth -compared to using a mixture of the other encodings, but uses too much CPU time to be practical. +Because this encoding produces a bitstream, this is the only encoding for which the encoded value might not be a whole number of bytes. If the bitstream isn't aligned on a byte boundary by the time the next non-Elias Delta field arrives, or the end of the frame is reached, the final byte is padded with zeros byte-align the stream. This encoding requires more CPU time than the other encodings because of the bit juggling involved in writing the bitstream. -[The basic encoding algorithm is defined on Wikipedia](https://en.wikipedia.org/wiki/Elias_delta_coding). Given these -utility functions: +When this encoder is chosen to encode all of the values in INAV interframes, it saves about 10% bandwidth compared to using a mixture of the other encodings, but uses too much CPU time to be practical. + +[The basic encoding algorithm is defined on Wikipedia](https://en.wikipedia.org/wiki/Elias_delta_coding). Given these utility functions: ```c /* Write `bitCount` bits from the least-significant end of the `bits` integer to the bitstream. The most-significant bit @@ -318,23 +259,17 @@ Here are some reference encoded bit patterns produced by writeU32EliasDelta: | 4294967294 | 0000010000011111111111111111111111111111110 | | 4294967295 | 0000010000011111111111111111111111111111111 | -Note that the very common value of zero encodes to a single bit, medium-sized values like 225 encode to 14 bits (an -overhead of 4 bits over writing a plain 8 bit value), and typical 32-bit values like 4294967293 encode into 42 bits, an -overhead of 10 bits. +Note that the very common value of zero encodes to a single bit, medium-sized values like 225 encode to 14 bits (an overhead of 4 bits over writing a plain 8 bit value), and typical 32-bit values like 4294967293 encode into 42 bits, an overhead of 10 bits. #### Elias delta signed 32-bit (5) + The value is first converted to unsigned using ZigZag encoding, then unsigned Elias-delta encoding is applied. #### TAG8_8SVB (6) -First, an 8-bit (one byte) header is written. This header has its bits set to zero when the corresponding field (from a -maximum of 8 fields) is set to zero, otherwise the bit is set to one. The least-signficant bit in the header corresponds -to the first field to be written. This header is followed by the values of only the fields which are non-zero, written -using signed variable byte encoding. -This encoding is preferred for groups of fields in interframes which are infrequently updated by the flight controller. -This will mean that their predictions are usually perfect, and so the value to be encoded for each field will normally -be zero. This is common for values like RC inputs and barometer readings, which are updated in only a fraction of main -loop iterations. +First, an 8-bit (one byte) header is written. This header has its bits set to zero when the corresponding field (from a maximum of 8 fields) is set to zero, otherwise the bit is set to one. The least-signficant bit in the header corresponds to the first field to be written. This header is followed by the values of only the fields which are non-zero, written using signed variable byte encoding. + +This encoding is preferred for groups of fields in interframes which are infrequently updated by the flight controller. This will mean that their predictions are usually perfect, and so the value to be encoded for each field will normally be zero. This is common for values like RC inputs and barometer readings, which are updated in only a fraction of main loop iterations. For example, given these field values to encode: @@ -349,8 +284,8 @@ This would be encoded: ``` #### TAG2_3S32 (7) -A 2-bit header is written, followed by 3 signed field values of up to 32 bits each. The header value is based on the -maximum size in bits of the three values to be encoded as follows: + +A 2-bit header is written, followed by 3 signed field values of up to 32 bits each. The header value is based on the maximum size in bits of the three values to be encoded as follows: | Header value | Maximum field value size | Field range | | ------------ | ------------------------ | -------------------------- | @@ -359,9 +294,7 @@ maximum size in bits of the three values to be encoded as follows: | 2 | 6 bits | [-32...31] | | 3 | Up to 32 bits | [-2147483648...2147483647] | -If any of the three values requires more than 6 bits to encode, a second, 6-bit header value is written in the lower -bits of the initial header byte. This second header has 2 bits for each of the encoded values which represents how many -bytes are required to encode that value. The least-significant bits of the header represent the first field which is +If any of the three values requires more than 6 bits to encode, a second, 6-bit header value is written in the lower bits of the initial header byte. This second header has 2 bits for each of the encoded values which represents how many bytes are required to encode that value. The least-significant bits of the header represent the first field which is encoded. The values for each possibility are as follows: | Header value | Field size | Field range | @@ -371,12 +304,9 @@ encoded. The values for each possibility are as follows: | 2 | 3 bytes | [-8388608...8388607] | | 3 | 4 bytes | [-2147483648...2147483647] | -This header is followed by the actual field values in order, written least-significant byte first, using the byte -lengths specified in the header. +This header is followed by the actual field values in order, written least-significant byte first, using the byte lengths specified in the header. -So bringing it all together, these encoded bit patterns are possible, where "0" and "1" mean bits fixed to be those -values, "A", "B", and "C" represent the first, second and third fields, and "s" represents the bits of the secondary -header in the case that any field is larger than 6 bits: +So bringing it all together, these encoded bit patterns are possible, where "0" and "1" mean bits fixed to be those values, "A", "B", and "C" represent the first, second and third fields, and "s" represents the bits of the secondary header in the case that any field is larger than 6 bits: ``` 00AA BBCC, @@ -385,13 +315,11 @@ header in the case that any field is larger than 6 bits: 11ss ssss (followed by fields of byte lengths specified in the "s" header) ``` -This encoding is useful for fields like 3-axis gyroscopes, which are frequently small and typically have similar -magnitudes. +This encoding is useful for fields like 3-axis gyroscopes, which are frequently small and typically have similar magnitudes. #### TAG8_4S16 (8) -An 8-bit header is written, followed by 4 signed field values of up to 16 bits each. The 8-bit header value has 2 bits -for each of the encoded fields (the least-significant bits represent the first field) which represent the -number of bits required to encode that field as follows: + +An 8-bit header is written, followed by 4 signed field values of up to 16 bits each. The 8-bit header value has 2 bits for each of the encoded fields (the least-significant bits represent the first field) which represent the number of bits required to encode that field as follows: | Header value | Field value size | Field range | | ------------ | ---------------- | ---------------- | @@ -400,9 +328,7 @@ number of bits required to encode that field as follows: | 2 | 8 bits | [-128...127] | | 3 | 16 bits | [-32768...32767] | -This header is followed by the actual field values in order, written as if the output stream was a bit-stream, with the -most-significant bit of the first field ending up in the most-significant bits of the first written byte. If the number -of nibbles written is odd, the final byte has its least-significant nibble set to zero. +This header is followed by the actual field values in order, written as if the output stream was a bit-stream, with the most-significant bit of the first field ending up in the most-significant bits of the first written byte. If the number of nibbles written is odd, the final byte has its least-significant nibble set to zero. For example, given these field values: @@ -429,72 +355,58 @@ So the header and fields would be encoded together as: ``` #### NULL (9) -This encoding does not write any bytes to the file. It is used when the predictor will always perfectly predict the -value of the field, so the remainder is always zero. In practice this is only used for the "loopIteration" field in -interframes, which is always perfectly predictable based on the logged frame's position in the sequence of frames and -the "P interval" setting from the header. + +This encoding does not write any bytes to the file. It is used when the predictor will always perfectly predict the value of the field, so the remainder is always zero. In practice this is only used for the "loopIteration" field in interframes, which is always perfectly predictable based on the logged frame's position in the sequence of frames and the "P interval" setting from the header. ## Log file structure -A logging session begins with a log start marker, then a header section which describes the format of the log, then the -log payload data, and finally an optional "log end" event ("E" frame). -A single log file can be comprised of one or more logging sessions. Each session may be preceded and followed by any -amount of non-Blackbox data. This data is ignored by the Blackbox log decoding tools. This allows for the logging device -to be alternately used by the Blackbox and some other system (such as MSP) without requiring the ability to begin a -separate log file for each separate activity. +A logging session begins with a log start marker, then a header section which describes the format of the log, then the log payload data, and finally an optional "log end" event ("E" frame). + +A single log file can be comprised of one or more logging sessions. Each session may be preceded and followed by any amount of non-Blackbox data. This data is ignored by the Blackbox log decoding tools. This allows for the logging device to be alternately used by the Blackbox and some other system (such as MSP) without requiring the ability to begin a separate log file for each separate activity. ### Log start marker -The log start marker is "H Product:Blackbox flight data recorder by Nicholas Sherlock\n". This marker is -used to discover the beginning of the flight log if the log begins partway through a file. Because it is such a long -string, it is not expected to occur by accident in any sequence of random bytes from other log device users. + +The log start marker is `H Product:Blackbox flight data recorder by Nicholas Sherlock\n`. This marker is used to discover the beginning of the flight log if the log begins partway through a file. Because it is such a long string, it is not expected to occur by accident in any sequence of random bytes from other log device users. ### Log header -The header is comprised of a sequence of lines of plain ASCII text. Each header line has the format `H fieldname:value` -and ends with a '\n'. The overall header does not have a terminator to separate it from the log payload -(the header implicitly ends when a line does not begin with an 'H' character). + +The header is comprised of a sequence of lines of plain ASCII text. Each header line has the format `H fieldname:value` and ends with a `'\n'`. The overall header does not have a terminator to separate it from the log payload (the header implicitly ends when a line does not begin with an 'H' character). The header can contain some of these fields: #### Data version (required) -When the interpretation of the Blackbox header changes due to Blackbox specification updates, the log version is -incremented to allow backwards-compatibility in the decoder: + +When the interpretation of the Blackbox header changes due to Blackbox specification updates, the log version is incremented to allow backwards-compatibility in the decoder: ``` H Data version:2 ``` #### Logging interval -Not every main loop iteration needs to result in a Blackbox logging iteration. When a loop iteration is not logged, -Blackbox is not called, no state is read from the flight controller, and nothing is written to the log. Two header lines -are included to note which main loop iterations will be logged: + +Not every main loop iteration needs to result in a Blackbox logging iteration. When a loop iteration is not logged, Blackbox is not called, no state is read from the flight controller, and nothing is written to the log. Two header lines are included to note which main loop iterations will be logged: ##### I interval -This header notes which of the main loop iterations will record an "I" intraframe to the log. If main loop iterations -with indexes divisible by 32 will be logged as "I" frames, the header will be: + +This header notes which of the main loop iterations will record an "I" intraframe to the log. If main loop iterations with indexes divisible by 32 will be logged as "I" frames, the header will be: ``` H I interval: 32 ``` -The first main loop iteration seen by Blackbox will be numbered with index 0, so the first main loop iteration will -always be logged as an intraframe. +The first main loop iteration seen by Blackbox will be numbered with index 0, so the first main loop iteration will always be logged as an intraframe. ##### P interval -Not every "P" interframe needs to be logged. Blackbox will log a portion of iterations in order to bring the total -portion of logged main frames to a user-chosen fraction. This fraction is called the logging rate. The smallest possible -logging rate is `(1/I interval)` which corresponds to logging only "I" frames at the "I" interval and discarding all -other loop iterations. The maximum logging rate is `1/1`, where every main loop iteration that is not an "I" frame is -logged as a "P" frame. The header records the logging rate fraction in `numerator/denominator` format like so: + +Not every "P" interframe needs to be logged. Blackbox will log a portion of iterations in order to bring the total portion of logged main frames to a user-chosen fraction. This fraction is called the logging rate. The smallest possible logging rate is `(1/I interval)` which corresponds to logging only "I" frames at the "I" interval and discarding all other loop iterations. The maximum logging rate is `1/1`, where every main loop iteration that is not an "I" frame is logged as a "P" frame. The header records the logging rate fraction in `numerator/denominator` format like so: ``` H P interval:1/2 ``` -The logging fraction given by `num/denom` should be simplified (i.e. rather than 2/6, a logging rate of 1/3 should -be used). +The logging fraction given by `num/denom` should be simplified (i.e. rather than 2/6, a logging rate of 1/3 should be used). -Given a logging rate of `num/denom` and an I-frame interval of `I_INTERVAL`, the frame type to log for an iteration -of index `iteration` is given by: +Given a logging rate of `num/denom` and an I-frame interval of `I_INTERVAL`, the frame type to log for an iteration of index `iteration` is given by: ```c if (iteration % I_INTERVAL == 0) @@ -520,8 +432,8 @@ For an I-interval of 32, these are the resulting logging patterns at some differ #### Firmware type (optional) -Because Blackbox records the internal flight controller state, the interpretation of the logged data will depend -on knowing which flight controller recorded it. To accomodate this, the name of the flight controller should be recorded: + +Because Blackbox records the internal flight controller state, the interpretation of the logged data will depend on knowing which flight controller recorded it. To accommodate this, the name of the flight controller should be recorded: ``` H Firmware type:INAV @@ -535,24 +447,25 @@ H Firmware date:Aug 28 2015 16:49:11 ``` #### Field X name (required) + This header is a comma-separated list of the names for the fields in the 'X' frame type: ``` H Field I name:loopIteration,time,axisP[0],axisP[1]... ``` -The decoder assumes that the fields in the 'P' frame type will all have the same names as those in the 'I' frame, so -a "Field P name" header does not need to be supplied. +The decoder assumes that the fields in the 'P' frame type will all have the same names as those in the 'I' frame, so a "Field P name" header does not need to be supplied. #### Field X signed (optional) -This is a comma-separated list of integers which are set to '1' when their corresponding field's value should be -interpreted as signed after decoding, or '0' otherwise: + +This is a comma-separated list of integers which are set to '1' when their corresponding field's value should be interpreted as signed after decoding, or '0' otherwise: ``` H Field I signed:0,0,1,1... ``` #### Field X predictor (required) + This is a comma-separated list of integers which specify the predictors for each field in the specified frame type: ``` @@ -560,6 +473,7 @@ H Field I predictor:0,0,0,0... ``` #### Field X encoding (required) + This is a comma-separated list of integers which specify the encoding used for each field in the specified frame type: ``` @@ -567,19 +481,18 @@ H Field X encoding:1,1,0,0... ``` #### vbatref + This header provides the reference voltage that will be used by predictor #9. #### minthrottle + This header provides the minimum value sent by INAV to the ESCs when armed, it is used by predictor #4. #### Additional headers -The decoder ignores headers that it does not understand, so you can freely add any headers that you require in order to -properly interpret the meaning of the logged values. -For example, to create a graphical displays of RC sticks and motor percentages, the Blackbox rendering tool requires -the additional headers "rcRate" and "maxthrottle". In order to convert raw gyroscope, accelerometer and voltage readings -into real-world units, the Blackbox decoder requires the calibration constants "gyro.scale", "acc_1G" and "vbatscale". -These headers might look like: +The decoder ignores headers that it does not understand, so you can freely add any headers that you require in order to properly interpret the meaning of the logged values. + +For example, to create a graphical displays of RC sticks and motor percentages, the Blackbox rendering tool requires the additional headers "rcRate" and "maxthrottle". In order to convert raw gyroscope, accelerometer and voltage readings into real-world units, the Blackbox decoder requires the calibration constants "gyro.scale", "acc_1G" and "vbatscale". These headers might look like: ``` H rcRate:100 @@ -591,16 +504,11 @@ H vbatscale:110 ### Log payload -The log payload is a concatenated sequence of logged frames. Each frame type which is present in the log payload must -have been previously described in the log header (with Frame X name, etc. headers). Each frame begins with a single -capital letter to specify the type of frame (I, P, etc), which is immediately followed by the frame's field data. There -is no frame length field, checksum, or trailer. +The log payload is a concatenated sequence of logged frames. Each frame type which is present in the log payload must have been previously described in the log header (with Frame X name, etc. headers). Each frame begins with a single capital letter to specify the type of frame (I, P, etc), which is immediately followed by the frame's field data. There is no frame length field, checksum, or trailer. -The field data is encoded by taking an array of raw field data, computing the predictor for each field, subtrating this -predictor from the field, then applying the field encoders to each field in sequence to serialize them to the log. +The field data is encoded by taking an array of raw field data, computing the predictor for each field, subtracting this predictor from the field, then applying the field encoders to each field in sequence to serialize them to the log. -For example, imagine that we are encoding three fields in an intraframe, are using zero-predictors for each field (#0), -and are encoding the values using the unsigned variable byte encoding (#1). For these field values: +For example, imagine that we are encoding three fields in an intraframe, are using zero-predictors for each field (#0), and are encoding the values using the unsigned variable byte encoding (#1). For these field values: ``` 1, 2, 3 @@ -612,9 +520,7 @@ We would encode a frame: 'I', 0x01, 0x02, 0x03 ``` -Imagine that we are encoding an array of motor commands in an interframe. We will use the previous motor commands as a -predictor, and encode the resulting values using signed variable byte encoding. The motor command values seen in the -previous logged iteration were: +Imagine that we are encoding an array of motor commands in an interframe. We will use the previous motor commands as a predictor, and encode the resulting values using signed variable byte encoding. The motor command values seen in the previous logged iteration were: ``` 1430, 1500, 1470, 1490 @@ -645,30 +551,31 @@ We will use unsigned variable byte encoding to write the resulting values to the ``` ### Log end marker -The log end marker is an optional Event ("E") frame of type 0xFF whose payload is the string "End of log\0". The -payload ensures that random data does not look like an end-of-log marker by chance. This event signals the tidy ending -of the log. All following bytes until the next log-begin marker (or end of file) should be ignored by the log -decoder. + +The log end marker is an optional Event ("E") frame of type 0xFF whose payload is the string `End of log\0` or more recently, `End of log (disarm reason:X)\0` (X is a number, see below). The payload ensures that random data does not look like an end-of-log marker by chance. This event signals the tidy ending of the log. All following bytes until the next log-begin marker (or end of file) should be ignored by the log decoder. ``` -'E', 0xFF, "End of log", 0x00 +'E', 0xFF, "End of log (disarm reason:4)\0", 0x00 ``` +#### Disarm Reasons + +
    +
  1. None
  2. +
  3. Timeout
  4. +
  5. Sticks
  6. +
  7. Switch_3D
  8. +
  9. Switch
  10. +
  11. Killswitch
  12. +
  13. Failsafe
  14. +
  15. Navigation
  16. +
+ ## Log validation -Any damage experienced to the log during recording is overwhelmingly due to subsequences of bytes being dropped by the -logging device due to overflowing buffers. Accordingly, Blackbox logs do not bother to include any checksums (bytes are -not expected to be damaged by the logging device without changing the length of the message). Because of the tight -bandwidth requirements of logging, neither a frame length field nor frame trailer is recorded that would allow for the + +Any damage experienced to the log during recording is overwhelmingly due to sub-sequences of bytes being dropped by the logging device due to overflowing buffers. Accordingly, Blackbox logs do not bother to include any checksums (bytes are not expected to be damaged by the logging device without changing the length of the message). Because of the tight bandwidth requirements of logging, neither a frame length field nor frame trailer is recorded that would allow for the detection of missing bytes. -Instead, the decoder uses a heuristic in order to detect damaged frames. The decoder reads an entire frame from the log -(using the decoder for each field which is the counterpart of the encoder specified in the header), then it checks to -see if the byte immediately following the frame, which should be the beginning of a next frame, is a recognized -frame-type byte (e.g. 'I', 'P', 'E', etc). If that following byte represents a valid frame type, it is assumed that the -decoded frame was the correct length (so was unlikely to have had random ranges of bytes removed from it, which would -have likely altered the frame length). Otherwise, the frame is rejected, and a valid frame-type byte is looked for -immediately after the frame-start byte of the frame that was rejected. A rejected frame causes all subsequent -interframes to be rejected as well, up until the next intraframe. +Instead, the decoder uses a heuristic in order to detect damaged frames. The decoder reads an entire frame from the log (using the decoder for each field which is the counterpart of the encoder specified in the header), then it checks to see if the byte immediately following the frame, which should be the beginning of a next frame, is a recognized frame-type byte (e.g. 'I', 'P', 'E', etc). If that following byte represents a valid frame type, it is assumed that the decoded frame was the correct length (so was unlikely to have had random ranges of bytes removed from it, which would have likely altered the frame length). Otherwise, the frame is rejected, and a valid frame-type byte is looked for immediately after the frame-start byte of the frame that was rejected. A rejected frame causes all subsequent interframes to be rejected as well, up until the next intraframe. -A frame is also rejected if the "loopIteration" or "time" fields have made unreasonable leaps forward, or moved at -all backwards. This suffices to detect almost all log corruption. +A frame is also rejected if the "loopIteration" or "time" fields have made unreasonable leaps forward, or moved at all backwards. This suffices to detect almost all log corruption. diff --git a/docs/development/Building in Docker.md b/docs/development/Building in Docker.md index eafb9b5e63..80d661ecf3 100755 --- a/docs/development/Building in Docker.md +++ b/docs/development/Building in Docker.md @@ -39,4 +39,6 @@ You'll have to manually execute the same steps that the build script does: + Where `` must be replaced with the absolute path of where you cloned this repo (see above), and `` with the name of the target that you want to build. + Note that on Windows/WSL 2 mounted /src folder is writeable for root user only. You have to run build under root user. You can achieve this by using `-u root` option in the command line above, or by removing "USER inav" line from the .\DockerFile before building image. -Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details. \ No newline at end of file +3. If you need to update `Settings.md`, run `docker run --entrypoint /src/cmake/docker_docs.sh --rm -it -u root -v :/src inav-build` + +Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details. diff --git a/docs/development/Building in Linux.md b/docs/development/Building in Linux.md index 4d73573cf3..a2729cff2c 100644 --- a/docs/development/Building in Linux.md +++ b/docs/development/Building in Linux.md @@ -1,17 +1,17 @@ # Generic Linux development tools ## Overview -This article endeavours to provide a generic guide for compiling inav on Linux for inav 2.6 and later. +This article endeavours to provide a generic guide for compiling INAV on Linux for INAV 2.6 and later. -inav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux). +INAV requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux). -In order to provide a uniform and reasonably modern cross compiler, inav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The inav approach of providing a recommended compiler is however both sound and justified: +In order to provide a uniform and reasonably modern cross compiler, INAV provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The INAV approach of providing a recommended compiler is however both sound and justified: * The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our flight controllers) -* Disto cross-compilers are often older than the recommended inav compiler -* The installed cross-compiler is only used to build inav and it not obviously / generally available outside of the inav build environment. +* Disto cross-compilers are often older than the recommended INAV compiler +* The installed cross-compiler is only used to build INAV and it not obviously / generally available outside of the INAV build environment. -There are a however some specific cases for using the distro cross-compiler in preference to that installed by inav: +There are a however some specific cases for using the distro cross-compiler in preference to that installed by INAV: * You are using a distro that installs a more modern compiler (Arch) * You are using a host platform for which ARM does not provide a compiler (e.g. Linux ia32). @@ -20,13 +20,13 @@ There are a however some specific cases for using the distro cross-compiler in p In addition to a cross-compiler, it is necessary to install some other tools: -* `git` : clone and manage the inav code repository +* `git` : clone and manage the INAV code repository * `cmake` : generate the build environment * `make` : run the firmware compilation * `ruby` : build some generated source files from JSON definitions * `gcc` : native compiler used to generate settings and run tests -Note that inav requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools. +Note that INAV requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools. Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is recommended that you upgrade to Ubuntu 20.04 LTS which does. @@ -67,7 +67,7 @@ The `git clone` creates an `inav` directory; we can enter this directory, config ## Build tooling -For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplifies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build environment with `cmake` before we can build any firmware. +For 2.6 and later, INAV uses `cmake` as its primary build tool. `cmake` simplifies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build environment with `cmake` before we can build any firmware. ## Using `cmake` @@ -82,7 +82,7 @@ cmake .. # note the "..", this is required as it tells cmake where to find its ruleset ``` -`cmake` will check for the presence of an inav-embedded cross-compiler; if this cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler. +`cmake` will check for the presence of an INAV-embedded cross-compiler; if this cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler. Note. If you want to use your own cross-compiler, either because you're running a distro (e.g. Arch Linux) that ships a more recent cross-compiler, or you're on a platform for which ARM doesn't provide a cross-compiler (e.g. 32bit Linux), the you should run the `cmake` command as: @@ -94,7 +94,7 @@ cmake -DCOMPILER_VERSION_CHECK=OFF .. ## Bulding the firmware -Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the inav cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler. +Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the INAV cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler. The generated `Makefile` uses different a target selection mechanism from the older (pre 2.6) top level `Makefile`; you can generate a list of targets with `make help` (or, as the list is extremely long), pipe this into a pager, e.g. `make help | less`. @@ -142,7 +142,7 @@ It is unlikely that the typical user will need to employ these options, other th ## Building with ninja -`cmake` is not a build system, rather it generates build files for a build manager. The examples above use `make` as the build manager; this has been the legacy way of building inav. It is also possible to use other build systems; one popular cross-platform tool is [ninja](https://ninja-build.org/) which is both lightweight and executes parallel builds by default. +`cmake` is not a build system, rather it generates build files for a build manager. The examples above use `make` as the build manager; this has been the legacy way of building INAV. It is also possible to use other build systems; one popular cross-platform tool is [ninja](https://ninja-build.org/) which is both lightweight and executes parallel builds by default. * Install `ninja` from the distro tool (apt, dnf, pacman as appropriate) * Configure `cmake` to use `ninja` as the build system @@ -163,8 +163,8 @@ It is unlikely that the typical user will need to employ these options, other th In order to update your local firmware build: -* Navigate to the local inav repository -* Use the following steps to pull the latest changes and rebuild your local version of inav firmware from the `build` directory: +* Navigate to the local INAV repository +* Use the following steps to pull the latest changes and rebuild your local version of INAV firmware from the `build` directory: ``` $ cd inav diff --git a/docs/development/Building in Mac OS X.md b/docs/development/Building in Mac OS X.md index ecc1d8ab4a..bd60a1f186 100755 --- a/docs/development/Building in Mac OS X.md +++ b/docs/development/Building in Mac OS X.md @@ -74,13 +74,13 @@ This will download the entire INAV repository for you into a new folder called " ## Build the code Assuming you've just cloned the source code, you can switch your current -directory to inav's source try by typing: +directory to INAV's source try by typing: ```sh cd inav ``` -Inside the inav directory, create a new directory to store the built files. This +Inside the INAV directory, create a new directory to store the built files. This helps keeping everything nice and tidy, separating source code from artifacts. By convention this directory is usually called `build`, but any name would work. Enter the following command to create it and switch your working directory to it: @@ -95,7 +95,7 @@ Now we need to configure the build by using the following command: cmake .. ``` -This will automatically download the required compiler for inav, so it +This will automatically download the required compiler for INAV, so it might take a few minutes. Once it's finished without errors, you can build the target that you want by typing `make target-name`. e.g.: @@ -119,7 +119,7 @@ INAV Configurator. ## Updating to the latest source If you want to erase your local changes and update to the latest version of the INAV source, enter your -inav directory and run these commands to first erase your local changes, fetch and merge the latest +INAV directory and run these commands to first erase your local changes, fetch and merge the latest changes from the repository, then rebuild the firmware: ```sh diff --git a/docs/development/Building in Vagrant.md b/docs/development/Building in Vagrant.md index 817fc5371a..1673a83312 100644 --- a/docs/development/Building in Vagrant.md +++ b/docs/development/Building in Vagrant.md @@ -14,7 +14,7 @@ Download and install Vagrant for you OS from here: https://www.vagrantup.com/downloads.html ``` -## Cloning iNav repository +## Cloning INAV repository Using git (The preferred way!) ``` git clone https://github.com/iNavFlight/inav.git @@ -28,7 +28,7 @@ and extract it to folder of your choosing. ## Running the virtual machine Open up a terminal or command line interface (In windows search for CMD.exe and run it as administrator!) -Navigate in to the directory of your cloned/unzipped iNav repository. (Where the "Vagrantfile" is located.) and start the virtual machine. +Navigate in to the directory of your cloned/unzipped INAV repository. (Where the "Vagrantfile" is located.) and start the virtual machine. ``` vagrant up ``` diff --git a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md index 0b12a48c12..cf5cc08c06 100644 --- a/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 or 11 with Linux Subsystem.md @@ -32,9 +32,9 @@ Install python and python-yaml to allow updates to settings.md To run `cmake` in the latest version you will need to update from Ubuntu `18_04` to `20_04`. The fastest way to do it is to uninstall current version and install `20_04` for Microsoft Store [https://www.microsoft.com/store/productId/9N6SVWS3RX71](https://www.microsoft.com/store/productId/9N6SVWS3RX71) -## Downloading the iNav repository (example): +## Downloading the INAV repository (example): -Mount MS windows C drive and clone iNav +Mount MS windows C drive and clone INAV 1. `cd /mnt/c` 1. `git clone https://github.com/iNavFlight/inav.git` diff --git a/docs/development/IDE - Visual Studio Code with Windows 10.md b/docs/development/IDE - Visual Studio Code with Windows 10.md index bcd5cd243e..ffd0383c55 100644 --- a/docs/development/IDE - Visual Studio Code with Windows 10.md +++ b/docs/development/IDE - Visual Studio Code with Windows 10.md @@ -54,8 +54,6 @@ Edit file `./.vscode/c_cpp_properties.json` to setup enabled `defines` "USE_RPM_FILTER", "USE_GLOBAL_FUNCTIONS", "USE_DYNAMIC_FILTERS", - "USE_IMU_BNO055", - "USE_SECONDARY_IMU", "USE_DSHOT", "FLASH_SIZE 480", "USE_I2C_IO_EXPANDER", diff --git a/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md b/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md index 1f3a129c4f..80b794e8dd 100644 --- a/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md +++ b/docs/development/Windows 11 - VS Code - WSL2 - Hardware Debugging.md @@ -249,8 +249,6 @@ sudo udevadm control --reload-rules "USE_RPM_FILTER", "USE_GLOBAL_FUNCTIONS", "USE_DYNAMIC_FILTERS", - "USE_IMU_BNO055", - "USE_SECONDARY_IMU", "USE_DSHOT", "FLASH_SIZE 480", "USE_I2C_IO_EXPANDER", diff --git a/docs/development/serial_printf_debugging.md b/docs/development/serial_printf_debugging.md index 7aa4e919a0..29b3813cb6 100644 --- a/docs/development/serial_printf_debugging.md +++ b/docs/development/serial_printf_debugging.md @@ -2,7 +2,7 @@ ## Overview -inav offers a function to use serial `printf` style debugging. +INAV offers a function to use serial `printf` style debugging. This provides a simple and intuitive debugging facility. This facility is only available after the serial sub-system has been initialised, which should be adequate for all but the most hard-core debugging requirements. @@ -44,7 +44,7 @@ Log levels are defined in `src/main/common/log.h`, at the time of writing these These are used at both compile time and run time. -At compile time, a maximum level may be defined. As of inav 2.3, for F3 targets the maximum level is ERROR, for F4/F7 the maximum level is DEBUG. +At compile time, a maximum level may be defined. As of INAV 2.3, for F3 targets the maximum level is ERROR, for F4/F7 the maximum level is DEBUG. At run time, the level defines the level that will be displayed, so for a F4 or F7 target that has compile time suport for all log levels, if the CLI sets ``` @@ -98,7 +98,7 @@ Log messages are transmitted through the `FUNCTION_LOG` serial port as MSP messa * msp-tool https://github.com/fiam/msp-tool * mwp https://github.com/stronnag/mwptools -* inav Configurator +* INAV Configurator For example, with the final lines of `src/main/fc/fc_init.c` set to: diff --git a/docs/development/wp_mission_schema/README.md b/docs/development/wp_mission_schema/README.md index 4c458632ae..d54716635f 100644 --- a/docs/development/wp_mission_schema/README.md +++ b/docs/development/wp_mission_schema/README.md @@ -2,13 +2,13 @@ ## Overview -Historically, mission planners interoperating with inav (and multiwii) missions have used the XML mission file format defined by EOSBandi for MultiWii 2.3 (2013). +Historically, mission planners interoperating with INAV (and multiwii) missions have used the XML mission file format defined by EOSBandi for MultiWii 2.3 (2013). The format is defined the XSD schema here. -* Lower case tags are preferred by inav. Older tools may prefer uppercase (the original MW usage). -* For inav 4.0 and later, the `missionitem/flags` attribute is required for "fly-by home" waypoints and multi-mission files. -* For inav 4.0 and later, multi-mission files; mission segments are delimited by a flag value of `165` (the MSP protocol 'last WP' value). +* Lower case tags are preferred by INAV. Older tools may prefer uppercase (the original MW usage). +* For INAV 4.0 and later, the `missionitem/flags` attribute is required for "fly-by home" waypoints and multi-mission files. +* For INAV 4.0 and later, multi-mission files; mission segments are delimited by a flag value of `165` (the MSP protocol 'last WP' value). * For multi-mission files, the waypoints may be numbered either sequentially across the whole file, or "reset-numbering" within each mission segment. The latter may (or not) be considered to be more "human readable", particularly where `JUMP` is used. * The `mwp` tag was introduced by the eponymous mission planner. Other mission planners may consider that reusing some of the tags (`cx`, `cy` - centre location, `zoom` TMS zoom level, `home-x`, `home-y` - home location) is useful. * `meta` may be used as a synonym for `mwp`. diff --git a/docs/development/wp_mission_schema/mw-mission.xsd b/docs/development/wp_mission_schema/mw-mission.xsd index acc34b2049..cb799f3bf3 100644 --- a/docs/development/wp_mission_schema/mw-mission.xsd +++ b/docs/development/wp_mission_schema/mw-mission.xsd @@ -1,6 +1,6 @@ - diff --git a/docs/policies/CONTRIBUTING.md b/docs/policies/CONTRIBUTING.md index 14de0a9c03..2cbf358882 100644 --- a/docs/policies/CONTRIBUTING.md +++ b/docs/policies/CONTRIBUTING.md @@ -10,7 +10,7 @@ Please search for existing issues *before* creating new ones. When submitting an issue the general rule is to include: -1. What is your setup and a detailed explanation of the issue, also include last working version of iNav. +1. What is your setup and a detailed explanation of the issue, also include last working version of INAV. 1. status dump from cli. 1. bootlog dump from cli. 1. dump dump from cli. diff --git a/README.md b/readme.md similarity index 98% rename from README.md rename to readme.md index cdaf5489fb..7399a4fb08 100644 --- a/README.md +++ b/readme.md @@ -48,7 +48,7 @@ Users of OpenTX radios (Taranis, Horus, Jumper, Radiomaster, Nirvana) can use IN ### 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. +[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. ## Installation diff --git a/src/bl/bl_main.c b/src/bl/bl_main.c index b83495ac59..de86285628 100644 --- a/src/bl/bl_main.c +++ b/src/bl/bl_main.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute this software + * INAV is free software. You can redistribute this software * and/or modify this software 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 they will be + * INAV is distributed in the hope that they 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. diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 595ac4cbb1..9f78997cad 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -92,8 +92,6 @@ main_sources(COMMON_SRC drivers/accgyro/accgyro_mpu6500.h drivers/accgyro/accgyro_mpu9250.c drivers/accgyro/accgyro_mpu9250.h - drivers/accgyro/accgyro_bno055_serial.c - drivers/accgyro/accgyro_bno055_serial.h drivers/adc.c drivers/adc.h @@ -302,8 +300,6 @@ main_sources(COMMON_SRC flight/failsafe.c flight/failsafe.h - flight/hil.c - flight/hil.h flight/imu.c flight/imu.h flight/kalman.c @@ -335,8 +331,6 @@ main_sources(COMMON_SRC flight/secondary_dynamic_gyro_notch.h flight/dynamic_lpf.c flight/dynamic_lpf.h - flight/secondary_imu.c - flight/secondary_imu.h io/beeper.c io/beeper.h @@ -484,8 +478,8 @@ main_sources(COMMON_SRC io/displayport_msp.h io/displayport_oled.c io/displayport_oled.h - io/displayport_hdzero_osd.c - io/displayport_hdzero_osd.h + io/displayport_msp_osd.c + io/displayport_msp_osd.h io/displayport_srxl.c io/displayport_srxl.h io/displayport_hott.c diff --git a/src/main/build/debug.h b/src/main/build/debug.h index a75fb15ac0..3a09da50da 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -66,11 +66,11 @@ typedef enum { DEBUG_PCF8574, DEBUG_DYNAMIC_GYRO_LPF, DEBUG_AUTOLEVEL, - DEBUG_IMU2, DEBUG_ALTITUDE, DEBUG_AUTOTRIM, DEBUG_AUTOTUNE, DEBUG_RATE_DYNAMICS, DEBUG_LANDING, + DEBUG_POS_EST, DEBUG_COUNT } debugType_e; diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index aaf9e581b5..8341cda584 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -167,8 +167,10 @@ displayPort_t *cmsDisplayPortGetCurrent(void) // 30 cols x 13 rows // HoTT Telemetry Screen // 21 cols x 8 rows -// HD +// HDZERO // 50 cols x 18 rows +// DJIWTF +// 60 cols x 22 rows // #define NORMAL_SCREEN_MIN_COLS 18 // Less is a small screen diff --git a/src/main/cms/cms_menu_navigation.c b/src/main/cms/cms_menu_navigation.c index 40ad55c2f8..33978f0118 100644 --- a/src/main/cms/cms_menu_navigation.c +++ b/src/main/cms/cms_menu_navigation.c @@ -191,11 +191,11 @@ static const OSD_Entry cmsx_menuMissionSettingsEntries[] = OSD_LABEL_ENTRY("-- MISSIONS --"), OSD_SETTING_ENTRY("MC WP SLOWDOWN", SETTING_NAV_MC_WP_SLOWDOWN), - OSD_SETTING_ENTRY("MISSION FAILSAFE", SETTING_FAILSAFE_MISSION), + OSD_SETTING_ENTRY("WP FAILSAFE DELAY", SETTING_FAILSAFE_MISSION_DELAY), OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT), OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS), OSD_SETTING_ENTRY("WP ENFORCE ALTITUDE", SETTING_NAV_WP_ENFORCE_ALTITUDE), - OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_SAFE_DISTANCE), + OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_MAX_SAFE_DISTANCE), #ifdef USE_MULTI_MISSION OSD_SETTING_ENTRY("MULTI MISSION NUMBER", SETTING_NAV_WP_MULTI_MISSION_INDEX), #endif diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 1a23da040d..d482635db2 100644 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -215,6 +215,8 @@ static const OSD_Entry menuOsdElemsEntries[] = OSD_ELEMENT_ENTRY("3D SPEED", OSD_3D_SPEED), OSD_ELEMENT_ENTRY("PLUS CODE", OSD_PLUS_CODE), OSD_ELEMENT_ENTRY("AZIMUTH", OSD_AZIMUTH), + OSD_ELEMENT_ENTRY("GRD COURSE", OSD_GROUND_COURSE), + OSD_ELEMENT_ENTRY("X TRACK ERR", OSD_CROSS_TRACK_ERROR), #endif // GPS OSD_ELEMENT_ENTRY("HEADING", OSD_HEADING), OSD_ELEMENT_ENTRY("HEADING GR.", OSD_HEADING_GRAPH), diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 6738169fc2..d79ea48e33 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -27,6 +27,7 @@ FILE_COMPILE_FOR_SPEED #include "common/filter.h" #include "common/maths.h" #include "common/utils.h" +#include "common/time.h" // NULL filter float nullFilterApply(void *filter, float input) @@ -319,7 +320,7 @@ FAST_CODE void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint FUNCTION_COMPILE_FOR_SIZE void initFilter(const uint8_t filterType, filter_t *filter, const float cutoffFrequency, const uint32_t refreshRate) { - const float dT = refreshRate * 1e-6f; + const float dT = US2S(refreshRate); if (cutoffFrequency) { if (filterType == FILTER_PT1) { diff --git a/src/main/common/log.c b/src/main/common/log.c index 24093c6595..20faa4a53d 100644 --- a/src/main/common/log.c +++ b/src/main/common/log.c @@ -96,7 +96,7 @@ void logInit(void) } } // Initialization done - LOG_I(SYSTEM, "%s/%s %s %s / %s (%s)", + LOG_INFO(SYSTEM, "%s/%s %s %s / %s (%s)", FC_FIRMWARE_NAME, targetName, FC_VERSION_STRING, diff --git a/src/main/common/log.h b/src/main/common/log.h index 3bbc074409..bc6795e5dd 100644 --- a/src/main/common/log.h +++ b/src/main/common/log.h @@ -48,41 +48,41 @@ void _logf(logTopic_e topic, unsigned level, const char *fmt, ...) __attribute__ void _logBufferHex(logTopic_e topic, unsigned level, const void *buffer, size_t size); #if defined(USE_LOG) -#define LOG_E(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, fmt, ##__VA_ARGS__) -#define LOG_BUFFER_E(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, buf, size) +#define LOG_ERROR(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, fmt, ##__VA_ARGS__) +#define LOG_BUFFER_ERROR(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_ERROR, buf, size) #else -#define LOG_E(...) -#define LOG_BUFFER_E(...) +#define LOG_ERROR(...) +#define LOG_BUFFER_ERROR(...) #endif #if defined(USE_LOG) -#define LOG_W(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, fmt, ##__VA_ARGS__) -#define LOG_BUF_W(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, buf, size) +#define LOG_WARNING(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, fmt, ##__VA_ARGS__) +#define LOG_BUF_WARNING(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_WARNING, buf, size) #else -#define LOG_W(...) -#define LOG_BUF_W(...) +#define LOG_WARNING(...) +#define LOG_BUF_WARNING(...) #endif #if defined(USE_LOG) -#define LOG_I(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, fmt, ##__VA_ARGS__) -#define LOG_BUF_I(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, buf, size) +#define LOG_INFO(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, fmt, ##__VA_ARGS__) +#define LOG_BUF_INFO(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_INFO, buf, size) #else -#define LOG_I(...) -#define LOG_BUF_I(...) +#define LOG_INFO(...) +#define LOG_BUF_INFO(...) #endif #if defined(USE_LOG) -#define LOG_V(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, fmt, ##__VA_ARGS__) -#define LOG_BUF_V(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, buf, size) +#define LOG_VERBOSE(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, fmt, ##__VA_ARGS__) +#define LOG_BUF_VERBOSE(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_VERBOSE, buf, size) #else -#define LOG_V(...) -#define LOG_BUF_V(...) +#define LOG_VERBOSE(...) +#define LOG_BUF_VERBOSE(...) #endif #if defined(USE_LOG) -#define LOG_D(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, fmt, ##__VA_ARGS__) -#define LOG_BUF_D(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, buf, size) +#define LOG_DEBUG(topic, fmt, ...) _logf(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, fmt, ##__VA_ARGS__) +#define LOG_BUF_DEBUG(topic, buf, size) _logBufferHex(LOG_TOPIC_ ## topic, LOG_LEVEL_DEBUG, buf, size) #else -#define LOG_D(...) -#define LOG_BUF_D(...) +#define LOG_DEBUG(...) +#define LOG_BUF_DEBUG(...) #endif diff --git a/src/main/common/memory.c b/src/main/common/memory.c index 45817ca9f6..97a87e7a83 100644 --- a/src/main/common/memory.c +++ b/src/main/common/memory.c @@ -52,11 +52,11 @@ void * memAllocate(size_t wantedSize, resourceOwner_e owner) retPointer = &dynHeap[dynHeapFreeWord]; dynHeapFreeWord += wantedWords; dynHeapUsage[owner] += wantedWords * sizeof(uint32_t); - LOG_D(SYSTEM, "Memory allocated. Free memory = %d", memGetAvailableBytes()); + LOG_DEBUG(SYSTEM, "Memory allocated. Free memory = %d", memGetAvailableBytes()); } else { // OOM - LOG_E(SYSTEM, "Out of memory"); + LOG_ERROR(SYSTEM, "Out of memory"); ENABLE_ARMING_FLAG(ARMING_DISABLED_OOM); } diff --git a/src/main/common/tristate.h b/src/main/common/tristate.h index 4215814e86..a54f6c00c5 100644 --- a/src/main/common/tristate.h +++ b/src/main/common/tristate.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute this software + * INAV is free software. You can redistribute this software * and/or modify this software 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 they will be + * INAV is distributed in the hope that they 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. diff --git a/src/main/common/utils.h b/src/main/common/utils.h index e585d96277..468e42f6b0 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -22,6 +22,7 @@ #define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0])) #define ARRAYEND(x) (&(x)[ARRAYLEN(x)]) +#define ZERO_FARRAY(a) memset(a, 0, sizeof(a)) #define CONST_CAST(type, value) ((type)(value)) @@ -92,9 +93,9 @@ static inline int32_t cmp32(uint32_t a, uint32_t b) { return a-b; } #ifdef UNIT_TEST // Call memcpy when building unittest - this is easier that asm symbol name mangling (symbols start with _underscore on win32) #include -static inline void memcpy_fn ( void * destination, const void * source, size_t num ) { memcpy(destination, source, num); }; +static inline void memcpy_fn(void *destination, const void *source, size_t num) { memcpy(destination, source, num); }; #else -void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("memcpy"); +void *memcpy_fn(void *destination, const void *source, size_t num) asm("memcpy"); #endif #if __GNUC__ > 6 diff --git a/src/main/config/config_streamer_ram.c b/src/main/config/config_streamer_ram.c index 9a7e8578ab..420e2a0e6c 100644 --- a/src/main/config/config_streamer_ram.c +++ b/src/main/config/config_streamer_ram.c @@ -41,7 +41,7 @@ int config_streamer_impl_write_word(config_streamer_t *c, config_streamer_buffer } if (c->address == (uintptr_t)&eepromData[0]) { - memset(eepromData, 0, sizeof(eepromData)); + ZERO_FARRAY(eepromData); } config_streamer_buffer_align_type_t *destAddr = (config_streamer_buffer_align_type_t *)c->address; diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 8cfd120596..46293524b1 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -23,9 +23,9 @@ #define PG_MOTOR_MIXER 4 #define PG_BLACKBOX_CONFIG 5 #define PG_MOTOR_CONFIG 6 -//#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in iNav -//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in iNav -//#define PG_SENSOR_TRIMS 9 -- NOT USED in iNav +//#define PG_SENSOR_SELECTION_CONFIG 7 -- NOT USED in INAV +//#define PG_SENSOR_ALIGNMENT_CONFIG 8 -- NOT USED in INAV +//#define PG_SENSOR_TRIMS 9 -- NOT USED in INAV #define PG_GYRO_CONFIG 10 #define PG_BATTERY_PROFILES 11 #define PG_CONTROL_RATE_PROFILES 12 @@ -85,7 +85,7 @@ // cleanflight v2 specific parameter group ids start at 256 #define PG_VTX_SETTINGS_CONFIG 259 -// iNav specific parameter group ids start at 1000 +// INAV specific parameter group ids start at 1000 #define PG_INAV_START 1000 #define PG_PITOTMETER_CONFIG 1000 #define PG_POSITION_ESTIMATION_CONFIG 1001 @@ -116,7 +116,7 @@ #define PG_SAFE_HOME_CONFIG 1026 #define PG_DJI_OSD_CONFIG 1027 #define PG_PROGRAMMING_PID 1028 -#define PG_SECONDARY_IMU 1029 +#define PG_UNUSED_1 1029 #define PG_POWER_LIMITS_CONFIG 1030 #define PG_OSD_COMMON_CONFIG 1031 #define PG_INAV_END 1031 diff --git a/src/main/drivers/accgyro/accgyro.c b/src/main/drivers/accgyro/accgyro.c index 99c69a5c80..6ed99cba2f 100644 --- a/src/main/drivers/accgyro/accgyro.c +++ b/src/main/drivers/accgyro/accgyro.c @@ -30,9 +30,7 @@ #include "common/utils.h" #include "drivers/bus.h" -#include "drivers/exti.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/nvic.h" #include "drivers/sensor.h" #include "drivers/system.h" @@ -62,7 +60,7 @@ const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t } } - LOG_V(GYRO, "GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X", + LOG_VERBOSE(GYRO, "GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X", desiredLpf, desiredRateHz, candidate->gyroLpf, candidate->gyroRateHz, candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]); @@ -70,50 +68,6 @@ const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t return candidate; } -/* - * Gyro interrupt service routine - */ -#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) -static void gyroIntExtiHandler(extiCallbackRec_t *cb) -{ - gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); - gyro->dataReady = true; - if (gyro->updateFn) { - gyro->updateFn(gyro); - } -} -#endif - -void gyroIntExtiInit(gyroDev_t *gyro) -{ - if (!gyro->busDev->irqPin) { - return; - } - -#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) -#ifdef ENSURE_MPU_DATA_READY_IS_LOW - uint8_t status = IORead(gyro->busDev->irqPin); - if (status) { - return; - } -#endif - -#if defined (STM32F7) || defined (STM32H7) - IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0); - - EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler); - EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ? -#else - IOInit(gyro->busDev->irqPin, OWNER_MPU, RESOURCE_EXTI, 0); - IOConfigGPIO(gyro->busDev->irqPin, IOCFG_IN_FLOATING); - - EXTIHandlerInit(&gyro->exti, gyroIntExtiHandler); - EXTIConfig(gyro->busDev->irqPin, &gyro->exti, NVIC_PRIO_GYRO_INT_EXTI, EXTI_Trigger_Rising); - EXTIEnable(gyro->busDev->irqPin, true); -#endif -#endif -} - bool gyroCheckDataReady(gyroDev_t* gyro) { bool ret; diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h index bb5c5d3fbb..ec9846144d 100644 --- a/src/main/drivers/accgyro/accgyro.h +++ b/src/main/drivers/accgyro/accgyro.h @@ -19,7 +19,6 @@ #include "platform.h" #include "common/axis.h" -#include "drivers/exti.h" #include "drivers/sensor.h" #define GYRO_LPF_256HZ 0 @@ -44,7 +43,6 @@ typedef struct gyroDev_s { sensorGyroReadDataFuncPtr temperatureFn; // read temperature if available sensorGyroInterruptStatusFuncPtr intStatusFn; sensorGyroUpdateFuncPtr updateFn; - extiCallbackRec_t exti; float scale; // scalefactor int16_t gyroADCRaw[XYZ_AXIS_COUNT]; int16_t gyroZero[XYZ_AXIS_COUNT]; @@ -67,5 +65,4 @@ typedef struct accDev_s { } accDev_t; const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t desiredRateHz, const gyroFilterAndRateConfig_t * configs, int count); -void gyroIntExtiInit(struct gyroDev_s *gyro); bool gyroCheckDataReady(struct gyroDev_s *gyro); diff --git a/src/main/drivers/accgyro/accgyro_bmi088.c b/src/main/drivers/accgyro/accgyro_bmi088.c index abe89af1df..6376289dea 100644 --- a/src/main/drivers/accgyro/accgyro_bmi088.c +++ b/src/main/drivers/accgyro/accgyro_bmi088.c @@ -35,7 +35,6 @@ #include "drivers/system.h" #include "drivers/time.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/sensor.h" @@ -86,8 +85,6 @@ static void bmi088GyroInit(gyroDev_t *gyro) { - gyroIntExtiInit(gyro); - busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION); // Soft reset diff --git a/src/main/drivers/accgyro/accgyro_bmi160.c b/src/main/drivers/accgyro/accgyro_bmi160.c index 60b54f7f8c..34b708f08e 100644 --- a/src/main/drivers/accgyro/accgyro_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_bmi160.c @@ -35,7 +35,6 @@ #include "drivers/system.h" #include "drivers/time.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/sensor.h" @@ -106,8 +105,8 @@ typedef struct __attribute__ ((__packed__)) bmi160ContextData_s { STATIC_ASSERT(sizeof(bmi160ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small); static const gyroFilterAndRateConfig_t gyroConfigs[] = { - { GYRO_LPF_256HZ, 3200, { BMI160_BWP_NORMAL | BMI160_ODR_3200_Hz} }, - { GYRO_LPF_256HZ, 1600, { BMI160_BWP_NORMAL | BMI160_ODR_1600_Hz} }, + { GYRO_LPF_256HZ, 3200, { BMI160_BWP_OSR4 | BMI160_ODR_3200_Hz} }, + { GYRO_LPF_256HZ, 1600, { BMI160_BWP_OSR2 | BMI160_ODR_1600_Hz} }, { GYRO_LPF_256HZ, 800, { BMI160_BWP_NORMAL | BMI160_ODR_800_Hz } }, { GYRO_LPF_188HZ, 800, { BMI160_BWP_OSR2 | BMI160_ODR_800_Hz } }, // ODR = 800 Hz, LPF = 128 Hz @@ -123,8 +122,7 @@ static const gyroFilterAndRateConfig_t gyroConfigs[] = { static void bmi160AccAndGyroInit(gyroDev_t *gyro) { uint8_t value; - gyroIntExtiInit(gyro); - + busSetSpeed(gyro->busDev, BUS_SPEED_INITIALIZATION); // Normal power mode, can take up to 80+3.8ms diff --git a/src/main/drivers/accgyro/accgyro_bmi270.c b/src/main/drivers/accgyro/accgyro_bmi270.c index b8d8247a8b..9f8bc21aca 100644 --- a/src/main/drivers/accgyro/accgyro_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_bmi270.c @@ -34,7 +34,6 @@ #include "drivers/system.h" #include "drivers/time.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/sensor.h" @@ -132,8 +131,8 @@ typedef struct __attribute__ ((__packed__)) bmi270ContextData_s { STATIC_ASSERT(sizeof(bmi270ContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small); static const gyroFilterAndRateConfig_t gyroConfigs[] = { - { GYRO_LPF_256HZ, 3200, { BMI270_BWP_NORM | BMI270_ODR_3200} }, - { GYRO_LPF_256HZ, 1600, { BMI270_BWP_NORM | BMI270_ODR_1600} }, + { GYRO_LPF_256HZ, 3200, { BMI270_BWP_OSR4 | BMI270_ODR_3200} }, + { GYRO_LPF_256HZ, 1600, { BMI270_BWP_OSR2 | BMI270_ODR_1600} }, { GYRO_LPF_256HZ, 800, { BMI270_BWP_NORM | BMI270_ODR_800 } }, { GYRO_LPF_188HZ, 800, { BMI270_BWP_OSR2 | BMI270_ODR_800 } }, @@ -197,8 +196,6 @@ static void bmi270AccAndGyroInit(gyroDev_t *gyro) { busDevice_t * busDev = gyro->busDev; - gyroIntExtiInit(gyro); - // Perform a soft reset to set all configuration to default // Delay 100ms before continuing configuration busWrite(busDev, BMI270_REG_CMD, BMI270_CMD_SOFTRESET); @@ -234,10 +231,8 @@ static void bmi270AccAndGyroInit(gyroDev_t *gyro) delay(1); // Configure the gyro data ready interrupt -#ifdef USE_MPU_DATA_READY_SIGNAL busWrite(busDev, BMI270_REG_INT_MAP_DATA, BMI270_INT_MAP_DATA_DRDY_INT1); delay(1); -#endif // Configure the behavior of the INT1 pin busWrite(busDev, BMI270_REG_INT1_IO_CTRL, BMI270_INT1_IO_CTRL_ACTIVE_HIGH | BMI270_INT1_IO_CTRL_OUTPUT_EN); diff --git a/src/main/drivers/accgyro/accgyro_bno055.c b/src/main/drivers/accgyro/accgyro_bno055.c deleted file mode 100644 index cefa3a5e04..0000000000 --- a/src/main/drivers/accgyro/accgyro_bno055.c +++ /dev/null @@ -1,180 +0,0 @@ -/* - * This file is part of INAV. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute 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. - * - * This file 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 this program. If not, see http://www.gnu.org/licenses/. - */ - -#include -#include -#include "drivers/bus.h" -#include "drivers/time.h" -#include "build/debug.h" -#include "common/vector.h" - -#ifdef USE_IMU_BNO055 - -static busDevice_t *busDev; - -static bool deviceDetect(busDevice_t *busDev) -{ - for (int retry = 0; retry < 5; retry++) - { - uint8_t sig; - - delay(150); - - bool ack = busRead(busDev, 0x00, &sig); - if (ack) - { - return true; - } - }; - - return false; -} - -static void bno055SetMode(uint8_t mode) -{ - busWrite(busDev, BNO055_ADDR_OPR_MODE, mode); - delay(25); -} - -static void bno055SetCalibrationData(bno055CalibrationData_t data) -{ - uint8_t buf[12]; - - //Prepare gains - //We do not restore gyro offsets, they are quickly calibrated at startup - uint8_t bufferBit = 0; - for (uint8_t sensorIndex = 0; sensorIndex < 2; sensorIndex++) - { - for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++) - { - buf[bufferBit] = (uint8_t)(data.offset[sensorIndex][axisIndex] & 0xff); - buf[bufferBit + 1] = (uint8_t)((data.offset[sensorIndex][axisIndex] >> 8 ) & 0xff); - bufferBit += 2; - } - } - - busWriteBuf(busDev, BNO055_ADDR_ACC_OFFSET_X_LSB, buf, 12); - - //Prepare radius - buf[0] = (uint8_t)(data.radius[ACC] & 0xff); - buf[1] = (uint8_t)((data.radius[ACC] >> 8 ) & 0xff); - buf[2] = (uint8_t)(data.radius[MAG] & 0xff); - buf[3] = (uint8_t)((data.radius[MAG] >> 8 ) & 0xff); - - //Write to the device - busWriteBuf(busDev, BNO055_ADDR_ACC_RADIUS_LSB, buf, 4); -} - -bool bno055Init(bno055CalibrationData_t calibrationData, bool setCalibration) -{ - busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_BNO055, 0, 0); - if (busDev == NULL) - { - return false; - } - - if (!deviceDetect(busDev)) - { - busDeviceDeInit(busDev); - return false; - } - - busWrite(busDev, BNO055_ADDR_PWR_MODE, BNO055_PWR_MODE_NORMAL); //Set power mode NORMAL - delay(25); - if (setCalibration) { - bno055SetMode(BNO055_OPR_MODE_CONFIG); - bno055SetCalibrationData(calibrationData); - } - bno055SetMode(BNO055_OPR_MODE_NDOF); - - return true; -} - -void bno055FetchEulerAngles(int16_t *buffer) -{ - uint8_t buf[6]; - busReadBuf(busDev, BNO055_ADDR_EUL_YAW_LSB, buf, 6); - - buffer[0] = ((int16_t)((buf[3] << 8) | buf[2])) / 1.6f; - buffer[1] = ((int16_t)((buf[5] << 8) | buf[4])) / -1.6f; //Pitch has to be reversed to match INAV notation - buffer[2] = ((int16_t)((buf[1] << 8) | buf[0])) / 1.6f; -} - -fpVector3_t bno055GetEurlerAngles(void) -{ - fpVector3_t eurlerAngles; - - uint8_t buf[6]; - busReadBuf(busDev, BNO055_ADDR_EUL_YAW_LSB, buf, 6); - - eurlerAngles.x = ((int16_t)((buf[3] << 8) | buf[2])) / 16; - eurlerAngles.y = ((int16_t)((buf[5] << 8) | buf[4])) / 16; - eurlerAngles.z = ((int16_t)((buf[1] << 8) | buf[0])) / 16; - - return eurlerAngles; -} - -bno055CalibStat_t bno055GetCalibStat(void) -{ - bno055CalibStat_t stats; - uint8_t buf; - - busRead(busDev, BNO055_ADDR_CALIB_STAT, &buf); - - stats.mag = buf & 0b00000011; - stats.acc = (buf >> 2) & 0b00000011; - stats.gyr = (buf >> 4) & 0b00000011; - stats.sys = (buf >> 6) & 0b00000011; - - return stats; -} - -bno055CalibrationData_t bno055GetCalibrationData(void) -{ - bno055CalibrationData_t data; - uint8_t buf[22]; - - bno055SetMode(BNO055_OPR_MODE_CONFIG); - - busReadBuf(busDev, BNO055_ADDR_ACC_OFFSET_X_LSB, buf, 22); - - bno055SetMode(BNO055_OPR_MODE_NDOF); - - uint8_t bufferBit = 0; - for (uint8_t sensorIndex = 0; sensorIndex < 3; sensorIndex++) - { - for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++) - { - data.offset[sensorIndex][axisIndex] = (int16_t)((buf[bufferBit + 1] << 8) | buf[bufferBit]); - bufferBit += 2; - } - } - - data.radius[ACC] = (int16_t)((buf[19] << 8) | buf[18]); - data.radius[MAG] = (int16_t)((buf[21] << 8) | buf[20]); - - return data; -} - -#endif \ No newline at end of file diff --git a/src/main/drivers/accgyro/accgyro_bno055_serial.c b/src/main/drivers/accgyro/accgyro_bno055_serial.c deleted file mode 100644 index e95a85a5c2..0000000000 --- a/src/main/drivers/accgyro/accgyro_bno055_serial.c +++ /dev/null @@ -1,270 +0,0 @@ -/* - * This file is part of INAV. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute 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. - * - * This file 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 this program. If not, see http://www.gnu.org/licenses/. - */ -#include "platform.h" -#ifdef USE_IMU_BNO055 - -#define BNO055_BAUD_RATE 115200 -#define BNO055_FRAME_MAX_TIME_MS 10 - -#include -#include -#include "io/serial.h" -#include "build/debug.h" -#include "drivers/time.h" -#include "flight/secondary_imu.h" - -static serialPort_t * bno055SerialPort = NULL; -static uint8_t receiveBuffer[22]; - -typedef enum { - BNO055_RECEIVE_IDLE, - BNO055_RECEIVE_HEADER, - BNO055_RECEIVE_LENGTH, - BNO055_RECEIVE_PAYLOAD, - BNO055_RECEIVE_ACK, -} bno055ReceiveState_e; - -typedef enum { - BNO055_FRAME_ACK, - BNO055_FRAME_DATA, -} bno055FrameType_e; - -typedef enum { - BNO055_DATA_TYPE_NONE, - BNO055_DATA_TYPE_EULER, - BNO055_DATA_TYPE_CALIBRATION_STATS, -} bno055DataType_e; - -static uint8_t bno055ProtocolState = BNO055_RECEIVE_IDLE; -static uint8_t bno055FrameType; -static uint8_t bno055FrameLength; -static uint8_t bno055FrameIndex; -static timeMs_t bno055FrameStartAtMs = 0; -static uint8_t bno055DataType = BNO055_DATA_TYPE_NONE; - - -static void bno055SerialWriteBuffer(const uint8_t reg, const uint8_t *data, const uint8_t count) { - - bno055ProtocolState = BNO055_RECEIVE_IDLE; - serialWrite(bno055SerialPort, 0xAA); // Start Byte - serialWrite(bno055SerialPort, 0x00); // Write command - serialWrite(bno055SerialPort, reg); - serialWrite(bno055SerialPort, count); - for (uint8_t i = 0; i < count; i++) { - serialWrite(bno055SerialPort, data[i]); - } -} - -static void bno055SerialWrite(const uint8_t reg, const uint8_t data) { - uint8_t buff[1]; - buff[0] = data; - - bno055SerialWriteBuffer(reg, buff, 1); -} - -static void bno055SerialRead(const uint8_t reg, const uint8_t len) { - bno055ProtocolState = BNO055_RECEIVE_IDLE; - serialWrite(bno055SerialPort, 0xAA); // Start Byte - serialWrite(bno055SerialPort, 0x01); // Read command - serialWrite(bno055SerialPort, reg); - serialWrite(bno055SerialPort, len); -} - -void bno055SerialDataReceive(uint16_t c, void *data) { - - UNUSED(data); - - const uint8_t incoming = (uint8_t) c; - - //Failsafe for stuck frames - if (bno055ProtocolState != BNO055_RECEIVE_IDLE && millis() - bno055FrameStartAtMs > BNO055_FRAME_MAX_TIME_MS) { - bno055ProtocolState = BNO055_RECEIVE_IDLE; - } - - if (bno055ProtocolState == BNO055_RECEIVE_IDLE && incoming == 0xEE) { - bno055FrameStartAtMs = millis(); - bno055ProtocolState = BNO055_RECEIVE_HEADER; - bno055FrameType = BNO055_FRAME_ACK; - } else if (bno055ProtocolState == BNO055_RECEIVE_IDLE && incoming == 0xBB) { - bno055FrameStartAtMs = millis(); - bno055ProtocolState = BNO055_RECEIVE_HEADER; - bno055FrameType = BNO055_FRAME_DATA; - } else if (bno055ProtocolState == BNO055_RECEIVE_HEADER && bno055FrameType == BNO055_FRAME_ACK) { - receiveBuffer[0] = incoming; - bno055ProtocolState = BNO055_RECEIVE_IDLE; - } else if (bno055ProtocolState == BNO055_RECEIVE_HEADER && bno055FrameType == BNO055_FRAME_DATA) { - bno055FrameLength = incoming; - bno055FrameIndex = 0; - bno055ProtocolState = BNO055_RECEIVE_LENGTH; - } else if (bno055ProtocolState == BNO055_RECEIVE_LENGTH) { - receiveBuffer[bno055FrameIndex] = incoming; - bno055FrameIndex++; - - if (bno055FrameIndex == bno055FrameLength) { - bno055ProtocolState = BNO055_RECEIVE_IDLE; - - if (bno055DataType == BNO055_DATA_TYPE_EULER) { - secondaryImuState.eulerAngles.raw[0] = ((int16_t)((receiveBuffer[3] << 8) | receiveBuffer[2])) / 1.6f; - secondaryImuState.eulerAngles.raw[1] = ((int16_t)((receiveBuffer[5] << 8) | receiveBuffer[4])) / -1.6f; //Pitch has to be reversed to match INAV notation - secondaryImuState.eulerAngles.raw[2] = ((int16_t)((receiveBuffer[1] << 8) | receiveBuffer[0])) / 1.6f; - secondaryImuProcess(); - } else if (bno055DataType == BNO055_DATA_TYPE_CALIBRATION_STATS) { - secondaryImuState.calibrationStatus.mag = receiveBuffer[0] & 0b00000011; - secondaryImuState.calibrationStatus.acc = (receiveBuffer[0] >> 2) & 0b00000011; - secondaryImuState.calibrationStatus.gyr = (receiveBuffer[0] >> 4) & 0b00000011; - secondaryImuState.calibrationStatus.sys = (receiveBuffer[0] >> 6) & 0b00000011; - } - - bno055DataType = BNO055_DATA_TYPE_NONE; - } - } - -} - -static void bno055SerialSetCalibrationData(bno055CalibrationData_t data) -{ - uint8_t buf[12]; - - //Prepare gains - //We do not restore gyro offsets, they are quickly calibrated at startup - uint8_t bufferBit = 0; - for (uint8_t sensorIndex = 0; sensorIndex < 2; sensorIndex++) - { - for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++) - { - buf[bufferBit] = (uint8_t)(data.offset[sensorIndex][axisIndex] & 0xff); - buf[bufferBit + 1] = (uint8_t)((data.offset[sensorIndex][axisIndex] >> 8 ) & 0xff); - bufferBit += 2; - } - } - - bno055SerialWriteBuffer(BNO055_ADDR_ACC_OFFSET_X_LSB, buf, 12); - delay(25); - - //Prepare radius - buf[0] = (uint8_t)(data.radius[ACC] & 0xff); - buf[1] = (uint8_t)((data.radius[ACC] >> 8 ) & 0xff); - buf[2] = (uint8_t)(data.radius[MAG] & 0xff); - buf[3] = (uint8_t)((data.radius[MAG] >> 8 ) & 0xff); - - //Write to the device - bno055SerialWriteBuffer(BNO055_ADDR_ACC_RADIUS_LSB, buf, 4); - delay(25); -} - -bool bno055SerialInit(bno055CalibrationData_t calibrationData, bool setCalibration) { - bno055SerialPort = NULL; - - serialPortConfig_t * portConfig = findSerialPortConfig(FUNCTION_IMU2); - if (!portConfig) { - return false; - } - - bno055SerialPort = openSerialPort( - portConfig->identifier, - FUNCTION_IMU2, - bno055SerialDataReceive, - NULL, - BNO055_BAUD_RATE, - MODE_RXTX, - SERIAL_NOT_INVERTED | SERIAL_UNIDIR | SERIAL_STOPBITS_1 | SERIAL_PARITY_NO - ); - - if (!bno055SerialPort) { - return false; - } - - bno055SerialRead(0x00, 1); // Read ChipID - delay(5); - - //Check ident - if (bno055FrameType != BNO055_FRAME_DATA || receiveBuffer[0] != 0xA0 || bno055ProtocolState != BNO055_RECEIVE_IDLE) { - return false; // Ident does not match, leave - } - - bno055SerialWrite(BNO055_ADDR_PWR_MODE, BNO055_PWR_MODE_NORMAL); //Set power mode NORMAL - delay(25); - - if (setCalibration) { - bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_CONFIG); - delay(25); - - bno055SerialSetCalibrationData(calibrationData); - } - - bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_NDOF); - delay(25); - - return true; -} - -/* - * This function is non-blocking and response will be processed by bno055SerialDataReceive - */ -void bno055SerialFetchEulerAngles() { - bno055DataType = BNO055_DATA_TYPE_EULER; - bno055SerialRead(BNO055_ADDR_EUL_YAW_LSB, 6); -} - -/* - * This function is non-blocking and response will be processed by bno055SerialDataReceive - */ -void bno055SerialGetCalibStat(void) { - bno055DataType = BNO055_DATA_TYPE_CALIBRATION_STATS; - bno055SerialRead(BNO055_ADDR_CALIB_STAT, 1); -} - -/* - * This function is blocking and should not be used during flight conditions! - */ -bno055CalibrationData_t bno055SerialGetCalibrationData(void) { - - bno055CalibrationData_t data; - - bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_CONFIG); - delay(25); - - bno055SerialRead(BNO055_ADDR_ACC_OFFSET_X_LSB, 22); - delay(50); - - uint8_t bufferBit = 0; - for (uint8_t sensorIndex = 0; sensorIndex < 3; sensorIndex++) - { - for (uint8_t axisIndex = 0; axisIndex < 3; axisIndex++) - { - data.offset[sensorIndex][axisIndex] = (int16_t)((receiveBuffer[bufferBit + 1] << 8) | receiveBuffer[bufferBit]); - bufferBit += 2; - } - } - - data.radius[ACC] = (int16_t)((receiveBuffer[19] << 8) | receiveBuffer[18]); - data.radius[MAG] = (int16_t)((receiveBuffer[21] << 8) | receiveBuffer[20]); - - bno055SerialWrite(BNO055_ADDR_OPR_MODE, BNO055_OPR_MODE_NDOF); - delay(25); - - return data; -} - -#endif \ No newline at end of file diff --git a/src/main/drivers/accgyro/accgyro_bno055_serial.h b/src/main/drivers/accgyro/accgyro_bno055_serial.h deleted file mode 100644 index 42693b3dd3..0000000000 --- a/src/main/drivers/accgyro/accgyro_bno055_serial.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * This file is part of INAV. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute 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. - * - * This file 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 this program. If not, see http://www.gnu.org/licenses/. - */ - -#pragma once - -#include "common/vector.h" - -#define BNO055_ADDR_PWR_MODE 0x3E -#define BNO055_ADDR_OPR_MODE 0x3D -#define BNO055_ADDR_CALIB_STAT 0x35 - -#define BNO055_PWR_MODE_NORMAL 0x00 -#define BNO055_OPR_MODE_CONFIG 0x00 -#define BNO055_OPR_MODE_NDOF 0x0C - -#define BNO055_ADDR_EUL_YAW_LSB 0x1A -#define BNO055_ADDR_EUL_YAW_MSB 0x1B -#define BNO055_ADDR_EUL_ROLL_LSB 0x1C -#define BNO055_ADDR_EUL_ROLL_MSB 0x1D -#define BNO055_ADDR_EUL_PITCH_LSB 0x1E -#define BNO055_ADDR_EUL_PITCH_MSB 0x1F - -#define BNO055_ADDR_MAG_RADIUS_MSB 0x6A -#define BNO055_ADDR_MAG_RADIUS_LSB 0x69 -#define BNO055_ADDR_ACC_RADIUS_MSB 0x68 -#define BNO055_ADDR_ACC_RADIUS_LSB 0x67 - -#define BNO055_ADDR_GYR_OFFSET_Z_MSB 0x66 -#define BNO055_ADDR_GYR_OFFSET_Z_LSB 0x65 -#define BNO055_ADDR_GYR_OFFSET_Y_MSB 0x64 -#define BNO055_ADDR_GYR_OFFSET_Y_LSB 0x63 -#define BNO055_ADDR_GYR_OFFSET_X_MSB 0x62 -#define BNO055_ADDR_GYR_OFFSET_X_LSB 0x61 - -#define BNO055_ADDR_MAG_OFFSET_Z_MSB 0x60 -#define BNO055_ADDR_MAG_OFFSET_Z_LSB 0x5F -#define BNO055_ADDR_MAG_OFFSET_Y_MSB 0x5E -#define BNO055_ADDR_MAG_OFFSET_Y_LSB 0x5D -#define BNO055_ADDR_MAG_OFFSET_X_MSB 0x5C -#define BNO055_ADDR_MAG_OFFSET_X_LSB 0x5B - -#define BNO055_ADDR_ACC_OFFSET_Z_MSB 0x5A -#define BNO055_ADDR_ACC_OFFSET_Z_LSB 0x59 -#define BNO055_ADDR_ACC_OFFSET_Y_MSB 0x58 -#define BNO055_ADDR_ACC_OFFSET_Y_LSB 0x57 -#define BNO055_ADDR_ACC_OFFSET_X_MSB 0x56 -#define BNO055_ADDR_ACC_OFFSET_X_LSB 0x55 - -typedef enum { - ACC = 0, - MAG = 1, - GYRO = 2 -} bno055Sensor_e; - -typedef struct { - uint8_t sys; - uint8_t gyr; - uint8_t acc; - uint8_t mag; -} bno055CalibStat_t; - -typedef struct { - int16_t radius[2]; - int16_t offset[3][3]; -} bno055CalibrationData_t; - -bool bno055SerialInit(bno055CalibrationData_t calibrationData, bool setCalibration); -void bno055SerialFetchEulerAngles(void); -void bno055SerialGetCalibStat(void); -bno055CalibrationData_t bno055SerialGetCalibrationData(void); \ No newline at end of file diff --git a/src/main/drivers/accgyro/accgyro_icm20689.c b/src/main/drivers/accgyro/accgyro_icm20689.c index 291cb91626..bd78f16133 100644 --- a/src/main/drivers/accgyro/accgyro_icm20689.c +++ b/src/main/drivers/accgyro/accgyro_icm20689.c @@ -31,7 +31,6 @@ #include "drivers/system.h" #include "drivers/time.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/accgyro/accgyro.h" @@ -93,8 +92,6 @@ static void icm20689AccAndGyroInit(gyroDev_t *gyro) const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; - gyroIntExtiInit(gyro); - busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); busWrite(busDev, MPU_RA_PWR_MGMT_1, ICM20689_BIT_RESET); @@ -112,15 +109,6 @@ static void icm20689AccAndGyroInit(gyroDev_t *gyro) busWrite(busDev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); // Get Divider Drops delay(100); - // Data ready interrupt configuration - busWrite(busDev, MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR, BYPASS_EN - - delay(15); - -#ifdef USE_MPU_DATA_READY_SIGNAL - busWrite(busDev, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable -#endif - // Switch SPI to fast speed busSetSpeed(busDev, BUS_SPEED_FAST); } diff --git a/src/main/drivers/accgyro/accgyro_icm42605.c b/src/main/drivers/accgyro/accgyro_icm42605.c index 5bf61e0760..05ebbfbbdd 100644 --- a/src/main/drivers/accgyro/accgyro_icm42605.c +++ b/src/main/drivers/accgyro/accgyro_icm42605.c @@ -29,7 +29,6 @@ #include "drivers/system.h" #include "drivers/time.h" -#include "drivers/exti.h" #include "drivers/sensor.h" #include "drivers/accgyro/accgyro.h" @@ -156,8 +155,6 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro) &icm42605GyroConfigs[0], ARRAYLEN(icm42605GyroConfigs)); gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; - gyroIntExtiInit(gyro); - busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busWrite(dev, ICM42605_RA_PWR_MGMT0, ICM42605_PWR_MGMT0_TEMP_DISABLE_OFF | ICM42605_PWR_MGMT0_ACCEL_MODE_LN | ICM42605_PWR_MGMT0_GYRO_MODE_LN); @@ -180,7 +177,6 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro) busWrite(dev, ICM42605_RA_INT_CONFIG0, ICM42605_UI_DRDY_INT_CLEAR_ON_SBR); delay(100); -#ifdef USE_MPU_DATA_READY_SIGNAL uint8_t intConfig1Value; busWrite(dev, ICM42605_RA_INT_SOURCE0, ICM42605_UI_DRDY_INT1_EN_ENABLED); @@ -193,7 +189,6 @@ static void icm42605AccAndGyroInit(gyroDev_t *gyro) busWrite(dev, ICM42605_RA_INT_CONFIG1, intConfig1Value); delay(15); -#endif busSetSpeed(dev, BUS_SPEED_FAST); } diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 320aa9f0ae..c12a684d0c 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -30,9 +30,7 @@ #include "common/utils.h" #include "drivers/bus.h" -#include "drivers/exti.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/nvic.h" #include "drivers/sensor.h" #include "drivers/system.h" @@ -45,12 +43,14 @@ // Check busDevice scratchpad memory size STATIC_ASSERT(sizeof(mpuContextData_t) < BUS_SCRATCHPAD_MEMORY_SIZE, busDevice_scratchpad_memory_too_small); +#define int16_val(v, idx) ((int16_t)(((uint8_t)v[2 * idx] << 8) | v[2 * idx + 1])) + static const gyroFilterAndRateConfig_t mpuGyroConfigs[] = { { GYRO_LPF_256HZ, 8000, { MPU_DLPF_256HZ, 0 } }, { GYRO_LPF_256HZ, 4000, { MPU_DLPF_256HZ, 1 } }, { GYRO_LPF_256HZ, 2000, { MPU_DLPF_256HZ, 3 } }, { GYRO_LPF_256HZ, 1000, { MPU_DLPF_256HZ, 7 } }, - { GYRO_LPF_256HZ, 666, { MPU_DLPF_256HZ, 11 } }, + { GYRO_LPF_256HZ, 666, { MPU_DLPF_256HZ, 11 } }, { GYRO_LPF_256HZ, 500, { MPU_DLPF_256HZ, 15 } }, { GYRO_LPF_188HZ, 1000, { MPU_DLPF_188HZ, 0 } }, @@ -83,9 +83,9 @@ bool mpuGyroRead(gyroDev_t *gyro) return false; } - gyro->gyroADCRaw[X] = (int16_t)((data[0] << 8) | data[1]); - gyro->gyroADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]); - gyro->gyroADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]); + gyro->gyroADCRaw[X] = int16_val(data, 0); + gyro->gyroADCRaw[Y] = int16_val(data, 1); + gyro->gyroADCRaw[Z] = int16_val(data, 2); return true; } @@ -102,9 +102,9 @@ bool mpuGyroReadScratchpad(gyroDev_t *gyro) mpuContextData_t * ctx = busDeviceGetScratchpadMemory(busDev); if (mpuUpdateSensorContext(busDev, ctx)) { - gyro->gyroADCRaw[X] = (int16_t)((ctx->gyroRaw[0] << 8) | ctx->gyroRaw[1]); - gyro->gyroADCRaw[Y] = (int16_t)((ctx->gyroRaw[2] << 8) | ctx->gyroRaw[3]); - gyro->gyroADCRaw[Z] = (int16_t)((ctx->gyroRaw[4] << 8) | ctx->gyroRaw[5]); + gyro->gyroADCRaw[X] = int16_val(ctx->gyroRaw, 0); + gyro->gyroADCRaw[Y] = int16_val(ctx->gyroRaw, 1); + gyro->gyroADCRaw[Z] = int16_val(ctx->gyroRaw, 2); return true; } @@ -116,9 +116,9 @@ bool mpuAccReadScratchpad(accDev_t *acc) mpuContextData_t * ctx = busDeviceGetScratchpadMemory(acc->busDev); if (ctx->lastReadStatus) { - acc->ADCRaw[X] = (int16_t)((ctx->accRaw[0] << 8) | ctx->accRaw[1]); - acc->ADCRaw[Y] = (int16_t)((ctx->accRaw[2] << 8) | ctx->accRaw[3]); - acc->ADCRaw[Z] = (int16_t)((ctx->accRaw[4] << 8) | ctx->accRaw[5]); + acc->ADCRaw[X] = int16_val(ctx->accRaw, 0); + acc->ADCRaw[Y] = int16_val(ctx->accRaw, 1); + acc->ADCRaw[Z] = int16_val(ctx->accRaw, 2); return true; } @@ -131,7 +131,7 @@ bool mpuTemperatureReadScratchpad(gyroDev_t *gyro, int16_t * data) if (ctx->lastReadStatus) { // Convert to degC*10: degC = raw / 340 + 36.53 - *data = (int16_t)((ctx->tempRaw[0] << 8) | ctx->tempRaw[1]) / 34 + 365; + *data = int16_val(ctx->tempRaw, 0) / 34 + 365; return true; } diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h index 90f7094521..62c2778b45 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.h +++ b/src/main/drivers/accgyro/accgyro_mpu.h @@ -17,7 +17,6 @@ #pragma once -#include "drivers/exti.h" #include "drivers/sensor.h" #include "drivers/accgyro/accgyro.h" diff --git a/src/main/drivers/accgyro/accgyro_mpu6000.c b/src/main/drivers/accgyro/accgyro_mpu6000.c index 6f8555c0b3..4ad6d99b5d 100644 --- a/src/main/drivers/accgyro/accgyro_mpu6000.c +++ b/src/main/drivers/accgyro/accgyro_mpu6000.c @@ -34,7 +34,6 @@ #include "drivers/system.h" #include "drivers/time.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/sensor.h" @@ -75,8 +74,6 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro) const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; - gyroIntExtiInit(gyro); - busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); // Device Reset @@ -110,14 +107,6 @@ static void mpu6000AccAndGyroInit(gyroDev_t *gyro) busWrite(busDev, MPU_RA_ACCEL_CONFIG, INV_FSR_16G << 3); delayMicroseconds(15); - busWrite(busDev, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 0 << 1 | 0 << 0); // INT_ANYRD_2CLEAR - delayMicroseconds(15); - -#ifdef USE_MPU_DATA_READY_SIGNAL - busWrite(busDev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN); - delayMicroseconds(15); -#endif - // Accel and Gyro DLPF Setting busWrite(busDev, MPU_RA_CONFIG, config->gyroConfigValues[0]); delayMicroseconds(1); diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.c b/src/main/drivers/accgyro/accgyro_mpu6500.c index 5d381acbab..5a2207a498 100755 --- a/src/main/drivers/accgyro/accgyro_mpu6500.c +++ b/src/main/drivers/accgyro/accgyro_mpu6500.c @@ -26,7 +26,6 @@ #include "drivers/system.h" #include "drivers/time.h" -#include "drivers/exti.h" #include "drivers/sensor.h" #include "drivers/accgyro/accgyro.h" @@ -71,8 +70,6 @@ static void mpu6500AccAndGyroInit(gyroDev_t *gyro) const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; - gyroIntExtiInit(gyro); - busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET); @@ -99,15 +96,6 @@ static void mpu6500AccAndGyroInit(gyroDev_t *gyro) busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); delay(100); - // Data ready interrupt configuration - busWrite(dev, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN - delay(15); - -#ifdef USE_MPU_DATA_READY_SIGNAL - busWrite(dev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN); - delay(15); -#endif - busSetSpeed(dev, BUS_SPEED_FAST); } diff --git a/src/main/drivers/accgyro/accgyro_mpu9250.c b/src/main/drivers/accgyro/accgyro_mpu9250.c index 32d7d5e7a2..45d116c1e0 100755 --- a/src/main/drivers/accgyro/accgyro_mpu9250.c +++ b/src/main/drivers/accgyro/accgyro_mpu9250.c @@ -26,7 +26,6 @@ #include "drivers/system.h" #include "drivers/time.h" -#include "drivers/exti.h" #include "drivers/sensor.h" #include "drivers/accgyro/accgyro.h" @@ -71,8 +70,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) const gyroFilterAndRateConfig_t * config = mpuChooseGyroConfig(gyro->lpf, 1000000 / gyro->requestedSampleIntervalUs); gyro->sampleRateIntervalUs = 1000000 / config->gyroRateHz; - gyroIntExtiInit(gyro); - busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busWrite(dev, MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); @@ -99,15 +96,6 @@ static void mpu9250AccAndGyroInit(gyroDev_t *gyro) busWrite(dev, MPU_RA_SMPLRT_DIV, config->gyroConfigValues[1]); delay(100); - // Data ready interrupt configuration - busWrite(dev, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN - delay(15); - -#ifdef USE_MPU_DATA_READY_SIGNAL - busWrite(dev, MPU_RA_INT_ENABLE, MPU_RF_DATA_RDY_EN); - delay(15); -#endif - busSetSpeed(dev, BUS_SPEED_FAST); } diff --git a/src/main/drivers/barometer/barometer_2smpb_02b.c b/src/main/drivers/barometer/barometer_2smpb_02b.c index 0c975bca2b..833f4a1ebc 100644 --- a/src/main/drivers/barometer/barometer_2smpb_02b.c +++ b/src/main/drivers/barometer/barometer_2smpb_02b.c @@ -20,8 +20,6 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see http://www.gnu.org/licenses/. - * - * Copyright: INAVFLIGHT OU */ #include diff --git a/src/main/drivers/barometer/barometer_2smpb_02b.h b/src/main/drivers/barometer/barometer_2smpb_02b.h index 5496991873..6270415708 100644 --- a/src/main/drivers/barometer/barometer_2smpb_02b.h +++ b/src/main/drivers/barometer/barometer_2smpb_02b.h @@ -20,8 +20,6 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see http://www.gnu.org/licenses/. - * - * Copyright: INAVFLIGHT OU */ #pragma once diff --git a/src/main/drivers/barometer/barometer_bmp085.c b/src/main/drivers/barometer/barometer_bmp085.c index c6c14c1a02..70065b85c1 100644 --- a/src/main/drivers/barometer/barometer_bmp085.c +++ b/src/main/drivers/barometer/barometer_bmp085.c @@ -28,7 +28,6 @@ #include "drivers/time.h" #include "drivers/bus.h" #include "drivers/nvic.h" -#include "drivers/exti.h" #include "drivers/io.h" #include "drivers/barometer/barometer_bmp085.h" diff --git a/src/main/drivers/barometer/barometer_bmp388.c b/src/main/drivers/barometer/barometer_bmp388.c index 000058534c..0abdc6ab7b 100644 --- a/src/main/drivers/barometer/barometer_bmp388.c +++ b/src/main/drivers/barometer/barometer_bmp388.c @@ -1,5 +1,5 @@ /* - * This file is part of iNav. + * This file is part of INAV. * * Cleanflight and Betaflight are free software. You can redistribute * this software and/or modify this software under the terms of the @@ -18,7 +18,7 @@ * If not, see . * * BMP388 Driver author: Dominic Clifton - * iNav port: Michel Pastor + * INAV port: Michel Pastor */ #include diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c index 5fbe12fc69..51e18eb12b 100644 --- a/src/main/drivers/barometer/barometer_dps310.c +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -20,8 +20,6 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see http://www.gnu.org/licenses/. - * - * Copyright: INAVFLIGHT OU */ #include @@ -40,6 +38,8 @@ #include "drivers/barometer/barometer.h" #include "drivers/barometer/barometer_dps310.h" +// See datasheet at https://www.infineon.com/dgdl/Infineon-DPS310-DataSheet-v01_02-EN.pdf?fileId=5546d462576f34750157750826c42242 + #if defined(USE_BARO) && defined(USE_BARO_DPS310) #define DPS310_REG_PSR_B2 0x00 @@ -77,7 +77,7 @@ #define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. #define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard). -#define DPS310_TMP_CFG_BIT_TMP_EXT (0x80) // +#define DPS310_TMP_CFG_BIT_TMP_EXT (0x80) #define DPS310_TMP_CFG_BIT_TMP_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. #define DPS310_TMP_CFG_BIT_TMP_PRC_16 (0x04) // 0100 - 16 times (Standard). @@ -188,7 +188,7 @@ static bool deviceConfigure(busDevice_t * busDev) baroState.calib.c01 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); // 0x1A c11 [15:8] + 0x1B c11 [7:0] - baroState.calib.c11 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); + baroState.calib.c11 = getTwosComplement(((uint32_t)coef[10] << 8) | (uint32_t)coef[11], 16); // 0x1C c20 [15:8] + 0x1D c20 [7:0] baroState.calib.c20 = getTwosComplement(((uint32_t)coef[12] << 8) | (uint32_t)coef[13], 16); @@ -266,10 +266,13 @@ static bool deviceReadMeasurement(baroDev_t *baro) const float c21 = baroState.calib.c21; const float c30 = baroState.calib.c30; + // See section 4.9.1, How to Calculate Compensated Pressure Values, of datasheet + baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21); + const float c0 = baroState.calib.c0; const float c1 = baroState.calib.c1; - - baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21); + + // See section 4.9.2, How to Calculate Compensated Temperature Values, of datasheet baroState.temperature = c0 * 0.5f + c1 * Traw_sc; return true; diff --git a/src/main/drivers/barometer/barometer_dps310.h b/src/main/drivers/barometer/barometer_dps310.h index 314c282c5c..28ec6d59dd 100644 --- a/src/main/drivers/barometer/barometer_dps310.h +++ b/src/main/drivers/barometer/barometer_dps310.h @@ -20,8 +20,6 @@ * * You should have received a copy of the GNU General Public License * along with this program. If not, see http://www.gnu.org/licenses/. - * - * Copyright: INAVFLIGHT OU */ #pragma once diff --git a/src/main/drivers/barometer/barometer_spl06.c b/src/main/drivers/barometer/barometer_spl06.c index 38b5743d16..99870dcaee 100644 --- a/src/main/drivers/barometer/barometer_spl06.c +++ b/src/main/drivers/barometer/barometer_spl06.c @@ -1,5 +1,5 @@ /* - * This file is part of iNav. + * This file is part of INAV. * * Cleanflight is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/src/main/drivers/barometer/barometer_spl06.h b/src/main/drivers/barometer/barometer_spl06.h index 691a0d1b0e..096cdb7a9e 100644 --- a/src/main/drivers/barometer/barometer_spl06.h +++ b/src/main/drivers/barometer/barometer_spl06.h @@ -1,5 +1,5 @@ /* - * This file is part of iNav. + * This file is part of INAV. * * Cleanflight is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/src/main/drivers/compass/compass_hmc5883l.c b/src/main/drivers/compass/compass_hmc5883l.c index efef08a0ac..6bbd20c189 100644 --- a/src/main/drivers/compass/compass_hmc5883l.c +++ b/src/main/drivers/compass/compass_hmc5883l.c @@ -32,7 +32,6 @@ #include "drivers/time.h" #include "drivers/nvic.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/light_led.h" diff --git a/src/main/drivers/compass/compass_ist8308.c b/src/main/drivers/compass/compass_ist8308.c index 11e21f2079..739c0965e9 100644 --- a/src/main/drivers/compass/compass_ist8308.c +++ b/src/main/drivers/compass/compass_ist8308.c @@ -32,7 +32,6 @@ #include "drivers/time.h" #include "drivers/nvic.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/light_led.h" diff --git a/src/main/drivers/compass/compass_ist8310.c b/src/main/drivers/compass/compass_ist8310.c index f196a4d055..bbd4687ead 100644 --- a/src/main/drivers/compass/compass_ist8310.c +++ b/src/main/drivers/compass/compass_ist8310.c @@ -32,7 +32,6 @@ #include "drivers/time.h" #include "drivers/nvic.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/bus.h" #include "drivers/light_led.h" diff --git a/src/main/drivers/compass/compass_mlx90393.c b/src/main/drivers/compass/compass_mlx90393.c index c2b5e40114..c931876143 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 iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. 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 5d73607294..06c54aa779 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 iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #pragma once diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index a022e12576..bc7b3400f6 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -4,8 +4,6 @@ #include "platform.h" -#ifdef USE_EXTI - #include "build/assert.h" #include "drivers/exti.h" @@ -199,6 +197,4 @@ _EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); _EXTI_IRQ_HANDLER(EXTI3_IRQHandler); _EXTI_IRQ_HANDLER(EXTI4_IRQHandler); _EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); -_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); - -#endif // USE_EXTI +_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); \ No newline at end of file diff --git a/src/main/drivers/flash.c b/src/main/drivers/flash.c index 5046bef8fa..18c26f6df7 100644 --- a/src/main/drivers/flash.c +++ b/src/main/drivers/flash.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute + * INAV is free software. You can redistribute * this software and/or modify this software 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 + * 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. diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h index ea3452bae8..4dfa8cb195 100644 --- a/src/main/drivers/flash.h +++ b/src/main/drivers/flash.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute + * INAV is free software. You can redistribute * this software and/or modify this software 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 + * 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. diff --git a/src/main/drivers/flash_w25n01g.c b/src/main/drivers/flash_w25n01g.c index 2f563cb04b..fc28772461 100644 --- a/src/main/drivers/flash_w25n01g.c +++ b/src/main/drivers/flash_w25n01g.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav are free software. You can redistribute + * INAV are free software. You can redistribute * this software and/or modify this software 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 are distributed in the hope that they + * INAV are distributed in the hope that they * 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. diff --git a/src/main/drivers/flash_w25n01g.h b/src/main/drivers/flash_w25n01g.h index ea6737eebb..032234005b 100644 --- a/src/main/drivers/flash_w25n01g.h +++ b/src/main/drivers/flash_w25n01g.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav are free software. You can redistribute + * INAV are free software. You can redistribute * this software and/or modify this software 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 are distributed in the hope that they + * INAV are distributed in the hope that they * 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. diff --git a/src/main/drivers/irlock.c b/src/main/drivers/irlock.c index 9088da1285..2ce13213cb 100644 --- a/src/main/drivers/irlock.c +++ b/src/main/drivers/irlock.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/drivers/irlock.h b/src/main/drivers/irlock.h index 04c6efcb1d..55e01475c9 100644 --- a/src/main/drivers/irlock.h +++ b/src/main/drivers/irlock.h @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #pragma once diff --git a/src/main/drivers/nvic.h b/src/main/drivers/nvic.h index 68586b7c08..42dfaa8d38 100644 --- a/src/main/drivers/nvic.h +++ b/src/main/drivers/nvic.h @@ -12,11 +12,8 @@ #define NVIC_PRIO_TIMER 3 #define NVIC_PRIO_TIMER_DMA 3 #define NVIC_PRIO_SDIO 3 -#define NVIC_PRIO_GYRO_INT_EXTI 4 #define NVIC_PRIO_USB 5 #define NVIC_PRIO_SERIALUART 5 -#define NVIC_PRIO_SONAR_EXTI 7 - // Use all available bits for priority and zero bits to sub-priority #ifdef USE_HAL_DRIVER diff --git a/src/main/drivers/osd.h b/src/main/drivers/osd.h index 62f0c05dc5..629228aa2c 100644 --- a/src/main/drivers/osd.h +++ b/src/main/drivers/osd.h @@ -45,7 +45,9 @@ typedef struct displayCanvas_s displayCanvas_t; typedef enum { VIDEO_SYSTEM_AUTO = 0, VIDEO_SYSTEM_PAL, - VIDEO_SYSTEM_NTSC + VIDEO_SYSTEM_NTSC, + VIDEO_SYSTEM_HDZERO, + VIDEO_SYSTEM_DJIWTF } videoSystem_e; typedef enum { diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index b9881cf3cc..adcb595ce2 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -171,9 +171,13 @@ #define SYM_AH_V_FT_1 0xD7 // 215 mAh/v-ft right #define SYM_AH_V_M_0 0xD8 // 216 mAh/v-m left #define SYM_AH_V_M_1 0xD9 // 217 mAh/v-m right +#define SYM_FLIGHT_MINS_REMAINING 0xDA // 218 Flight time (mins) remaining +#define SYM_FLIGHT_HOURS_REMAINING 0xDB // 219 Flight time (hours) remaining +#define SYM_GROUND_COURSE 0xDC // 220 Ground course +#define SYM_CROSS_TRACK_ERROR 0xFC // 252 Cross track error -#define SYM_LOGO_START 0x101 // 257 to 280, INAV logo -#define SYM_LOGO_WIDTH 6 +#define SYM_LOGO_START 0x101 // 257 to 297, INAV logo +#define SYM_LOGO_WIDTH 10 #define SYM_LOGO_HEIGHT 4 #define SYM_AH_LEFT 0x12C // 300 Arrow left @@ -220,6 +224,7 @@ #define SYM_HOME_DIST 0x165 // 357 DIST #define SYM_AH_CH_CENTER 0x166 // 358 Crossair center +#define SYM_FLIGHT_DIST_REMAINING 0x167 // 359 Flight distance reminaing #define SYM_AH_CH_TYPE3 0x190 // 400 to 402, crosshair 3 #define SYM_AH_CH_TYPE4 0x193 // 403 to 405, crosshair 4 diff --git a/src/main/drivers/persistent.c b/src/main/drivers/persistent.c index b4ed38903a..43a1b1d0a5 100644 --- a/src/main/drivers/persistent.c +++ b/src/main/drivers/persistent.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav free software. You can redistribute + * INAV free software. You can redistribute * this software and/or modify this software 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 distributed in the hope that it + * INAV 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. diff --git a/src/main/drivers/pitotmeter/pitotmeter_virtual.c b/src/main/drivers/pitotmeter/pitotmeter_virtual.c index b8af2df33a..ef3eb8d034 100644 --- a/src/main/drivers/pitotmeter/pitotmeter_virtual.c +++ b/src/main/drivers/pitotmeter/pitotmeter_virtual.c @@ -64,12 +64,18 @@ static void virtualPitotCalculate(pitotDev_t *pitot, float *pressure, float *tem UNUSED(pitot); float airSpeed = 0.0f; if (pitotIsCalibrationComplete()) { - if (isEstimatedWindSpeedValid()) { + if (isEstimatedWindSpeedValid() && STATE(GPS_FIX)) { uint16_t windHeading; //centidegrees float windSpeed = getEstimatedHorizontalWindSpeed(&windHeading); //cm/s float horizontalWindSpeed = windSpeed * cos_approx(CENTIDEGREES_TO_RADIANS(windHeading - posControl.actualState.yaw)); //yaw int32_t centidegrees airSpeed = posControl.actualState.velXY - horizontalWindSpeed; //float cm/s or gpsSol.groundSpeed int16_t cm/s - } else { + airSpeed = calc_length_pythagorean_2D(airSpeed,getEstimatedActualVelocity(Z)+getEstimatedWindSpeed(Z)); + } + else if (STATE(GPS_FIX)) + { + airSpeed = calc_length_pythagorean_3D(gpsSol.velNED[X],gpsSol.velNED[Y],gpsSol.velNED[Z]); + } + else { airSpeed = pidProfile()->fixedWingReferenceAirspeed; //float cm/s } } diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index a0d05bf853..1d3ab1b584 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -230,6 +230,9 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU timOutputs->maxTimMotorCount = 0; timOutputs->maxTimServoCount = 0; + uint8_t motorCount = getMotorCount(); + uint8_t motorIdx = 0; + for (int idx = 0; idx < timerHardwareCount; idx++) { timerHardware_t *timHw = &timerHardware[idx]; @@ -240,13 +243,20 @@ void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerU // Check for known conflicts (i.e. UART, LEDSTRIP, Rangefinder and ADC) if (checkPwmTimerConflicts(timHw)) { - LOG_W(PWM, "Timer output %d skipped", idx); + LOG_WARNING(PWM, "Timer output %d skipped", idx); continue; } // Determine if timer belongs to motor/servo if (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER) { // Multicopter + + // Make sure first motorCount outputs get assigned to motor + if ((timHw->usageFlags & TIM_USE_MC_MOTOR) && (motorIdx < motorCount)) { + timHw->usageFlags = timHw->usageFlags & ~TIM_USE_MC_SERVO; + motorIdx += 1; + } + // We enable mapping to servos if mixer is actually using them if (isMixerUsingServos && timHw->usageFlags & TIM_USE_MC_SERVO) { type = MAP_TO_SERVO_OUTPUT; @@ -295,7 +305,7 @@ static void pwmInitMotors(timMotorServoHardware_t * timOutputs) // Check if too many motors if (motorCount > MAX_MOTORS) { pwmInitError = PWM_INIT_ERROR_TOO_MANY_MOTORS; - LOG_E(PWM, "Too many motors. Mixer requested %d, max %d", motorCount, MAX_MOTORS); + LOG_ERROR(PWM, "Too many motors. Mixer requested %d, max %d", motorCount, MAX_MOTORS); return; } @@ -304,14 +314,14 @@ static void pwmInitMotors(timMotorServoHardware_t * timOutputs) // Now if we need to configure individual motor outputs - do that if (!motorsUseHardwareTimers()) { - LOG_I(PWM, "Skipped timer init for motors"); + LOG_INFO(PWM, "Skipped timer init for motors"); return; } // If mixer requests more motors than we have timer outputs - throw an error if (motorCount > timOutputs->maxTimMotorCount) { pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS; - LOG_E(PWM, "Not enough motor outputs. Mixer requested %d, outputs %d", motorCount, timOutputs->maxTimMotorCount); + LOG_ERROR(PWM, "Not enough motor outputs. Mixer requested %d, outputs %d", motorCount, timOutputs->maxTimMotorCount); return; } @@ -320,7 +330,7 @@ static void pwmInitMotors(timMotorServoHardware_t * timOutputs) const timerHardware_t *timHw = timOutputs->timMotors[idx]; if (!pwmMotorConfig(timHw, idx, feature(FEATURE_PWM_OUTPUT_ENABLE))) { pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED; - LOG_E(PWM, "Timer allocation failed for motor %d", idx); + LOG_ERROR(PWM, "Timer allocation failed for motor %d", idx); return; } } @@ -331,14 +341,14 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs) const int servoCount = getServoCount(); if (!isMixerUsingServos()) { - LOG_I(PWM, "Mixer does not use servos"); + LOG_INFO(PWM, "Mixer does not use servos"); return; } // Check if too many servos if (servoCount > MAX_SERVOS) { pwmInitError = PWM_INIT_ERROR_TOO_MANY_SERVOS; - LOG_E(PWM, "Too many servos. Mixer requested %d, max %d", servoCount, MAX_SERVOS); + LOG_ERROR(PWM, "Too many servos. Mixer requested %d, max %d", servoCount, MAX_SERVOS); return; } @@ -348,14 +358,14 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs) // Check if we need to init timer output for servos if (!servosUseHardwareTimers()) { // External PWM servo driver - LOG_I(PWM, "Skipped timer init for servos - using external servo driver"); + LOG_INFO(PWM, "Skipped timer init for servos - using external servo driver"); return; } // If mixer requests more servos than we have timer outputs - throw an error if (servoCount > timOutputs->maxTimServoCount) { pwmInitError = PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS; - LOG_E(PWM, "Too many servos. Mixer requested %d, timer outputs %d", servoCount, timOutputs->maxTimServoCount); + LOG_ERROR(PWM, "Too many servos. Mixer requested %d, timer outputs %d", servoCount, timOutputs->maxTimServoCount); return; } @@ -365,7 +375,7 @@ static void pwmInitServos(timMotorServoHardware_t * timOutputs) if (!pwmServoConfig(timHw, idx, servoConfig()->servoPwmRate, servoConfig()->servoCenterPulse, feature(FEATURE_PWM_OUTPUT_ENABLE))) { pwmInitError = PWM_INIT_ERROR_TIMER_INIT_FAILED; - LOG_E(PWM, "Timer allocation failed for servo %d", idx); + LOG_ERROR(PWM, "Timer allocation failed for servo %d", idx); return; } } diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index db9e1e3296..658c3f5cb5 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -130,7 +130,7 @@ static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uin static pwmOutputPort_t *pwmOutAllocatePort(void) { if (allocatedOutputPortCount >= MAX_PWM_OUTPUT_PORTS) { - LOG_E(PWM, "Attempt to allocate PWM output beyond MAX_PWM_OUTPUT_PORTS"); + LOG_ERROR(PWM, "Attempt to allocate PWM output beyond MAX_PWM_OUTPUT_PORTS"); return NULL; } @@ -261,7 +261,7 @@ static pwmOutputPort_t * motorConfigDshot(const timerHardware_t * timerHardware, // Configure timer DMA if (timerPWMConfigChannelDMA(port->tch, port->dmaBuffer, sizeof(port->dmaBuffer[0]), DSHOT_DMA_BUFFER_SIZE)) { // Only mark as DSHOT channel if DMA was set successfully - memset(port->dmaBuffer, 0, sizeof(port->dmaBuffer)); + ZERO_FARRAY(port->dmaBuffer); port->configured = true; } diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 92d89c4c12..7ce128516f 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -18,7 +18,7 @@ /* * Cleanflight (or Baseflight): original * jflyper: Mono-timer and single-wire half-duplex - * jflyper: Ported to iNav + * jflyper: Ported to INAV */ #include diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index 9b2c12d466..bb089b4cb9 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -48,7 +48,7 @@ void systemBeep(bool onoff) #ifdef USE_SIMULATOR if (ARMING_FLAG(SIMULATOR_MODE)) { - if (simulatorData.flags & SIMU_MUTE_BEEPER) { + if (SIMULATOR_HAS_OPTION(HITL_MUTE_BEEPER)) { onoff = false; } } diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index f2178475b4..5cb9ccfd20 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -26,8 +26,6 @@ #include "drivers/nvic.h" #include "drivers/system.h" -#include "drivers/exti.h" - #include "target/system.h" diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index 4418e9ad2c..094b54f714 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -80,7 +80,7 @@ TCH_t * timerGetTCH(const timerHardware_t * timHw) const int timerIndex = lookupTimerIndex(timHw->tim); if (timerIndex >= HARDWARE_TIMER_DEFINITION_COUNT) { - LOG_E(TIMER, "Can't find hardware timer definition"); + LOG_ERROR(TIMER, "Can't find hardware timer definition"); return NULL; } @@ -90,7 +90,7 @@ TCH_t * timerGetTCH(const timerHardware_t * timHw) // Check for OOM if (timerCtx[timerIndex] == NULL) { - LOG_E(TIMER, "Can't allocate TCH object"); + LOG_ERROR(TIMER, "Can't allocate TCH object"); return NULL; } diff --git a/src/main/drivers/usb_msc.c b/src/main/drivers/usb_msc.c index 937a88fb17..3b3904dd91 100644 --- a/src/main/drivers/usb_msc.c +++ b/src/main/drivers/usb_msc.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav + * This file is part of INAV * - * iNav is free software. You can redistribute + * INAV is free software. You can redistribute * this software and/or modify this software 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 + * 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. diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index bea83a1711..6dd129b5c3 100644 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -84,7 +84,6 @@ bool cliMode = false; #include "flight/mixer.h" #include "flight/pid.h" #include "flight/servos.h" -#include "flight/secondary_imu.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/beeper.h" @@ -1903,26 +1902,39 @@ static void cliServoMix(char *cmdline) #ifdef USE_PROGRAMMING_FRAMEWORK -static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions, const logicCondition_t *defaultLogicConditions) +static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions, const logicCondition_t *defaultLogicConditions, int16_t showLC) { const char *format = "logic %d %d %d %d %d %d %d %d %d"; - for (uint32_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) { - const logicCondition_t logic = logicConditions[i]; + for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) { + if (showLC == -1 || showLC == i) { + const logicCondition_t logic = logicConditions[i]; - bool equalsDefault = false; - if (defaultLogicConditions) { - logicCondition_t defaultValue = defaultLogicConditions[i]; - equalsDefault = - logic.enabled == defaultValue.enabled && - logic.activatorId == defaultValue.activatorId && - logic.operation == defaultValue.operation && - logic.operandA.type == defaultValue.operandA.type && - logic.operandA.value == defaultValue.operandA.value && - logic.operandB.type == defaultValue.operandB.type && - logic.operandB.value == defaultValue.operandB.value && - logic.flags == defaultValue.flags; + bool equalsDefault = false; + if (defaultLogicConditions) { + logicCondition_t defaultValue = defaultLogicConditions[i]; + equalsDefault = + logic.enabled == defaultValue.enabled && + logic.activatorId == defaultValue.activatorId && + logic.operation == defaultValue.operation && + logic.operandA.type == defaultValue.operandA.type && + logic.operandA.value == defaultValue.operandA.value && + logic.operandB.type == defaultValue.operandB.type && + logic.operandB.value == defaultValue.operandB.value && + logic.flags == defaultValue.flags; - cliDefaultPrintLinef(dumpMask, equalsDefault, format, + cliDefaultPrintLinef(dumpMask, equalsDefault, format, + i, + logic.enabled, + logic.activatorId, + logic.operation, + logic.operandA.type, + logic.operandA.value, + logic.operandB.type, + logic.operandB.value, + logic.flags + ); + } + cliDumpPrintLinef(dumpMask, equalsDefault, format, i, logic.enabled, logic.activatorId, @@ -1934,27 +1946,20 @@ static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions logic.flags ); } - cliDumpPrintLinef(dumpMask, equalsDefault, format, - i, - logic.enabled, - logic.activatorId, - logic.operation, - logic.operandA.type, - logic.operandA.value, - logic.operandB.type, - logic.operandB.value, - logic.flags - ); } } -static void cliLogic(char *cmdline) { +static void processCliLogic(char *cmdline, int16_t lcIndex) { char * saveptr; int args[9], check = 0; uint8_t len = strlen(cmdline); if (len == 0) { - printLogic(DUMP_MASTER, logicConditions(0), NULL); + if (!commandBatchActive) { + printLogic(DUMP_MASTER, logicConditions(0), NULL, -1); + } else if (lcIndex >= 0) { + printLogic(DUMP_MASTER, logicConditions(0), NULL, lcIndex); + } } else if (sl_strncasecmp(cmdline, "reset", 5) == 0) { pgResetCopy(logicConditionsMutable(0), PG_LOGIC_CONDITIONS); } else { @@ -2003,13 +2008,17 @@ static void cliLogic(char *cmdline) { logicConditionsMutable(i)->operandB.value = args[OPERAND_B_VALUE]; logicConditionsMutable(i)->flags = args[FLAGS]; - cliLogic(""); + processCliLogic("", i); } else { cliShowParseError(); } } } +static void cliLogic(char *cmdline) { + processCliLogic(cmdline, -1); +} + static void printGvar(uint8_t dumpMask, const globalVariableConfig_t *gvars, const globalVariableConfig_t *defaultGvars) { const char *format = "gvar %d %d %d %d"; @@ -3076,55 +3085,6 @@ static void cliBatch(char *cmdline) } #endif -#ifdef USE_SECONDARY_IMU - -static void printImu2Status(void) -{ - cliPrintLinef("Secondary IMU active: %d", secondaryImuState.active); - cliPrintLine("Calibration status:"); - cliPrintLinef("Sys: %d", secondaryImuState.calibrationStatus.sys); - cliPrintLinef("Gyro: %d", secondaryImuState.calibrationStatus.gyr); - cliPrintLinef("Acc: %d", secondaryImuState.calibrationStatus.acc); - cliPrintLinef("Mag: %d", secondaryImuState.calibrationStatus.mag); - cliPrintLine("Calibration gains:"); - - cliPrintLinef( - "Gyro: %d %d %d", - secondaryImuConfig()->calibrationOffsetGyro[X], - secondaryImuConfig()->calibrationOffsetGyro[Y], - secondaryImuConfig()->calibrationOffsetGyro[Z] - ); - cliPrintLinef( - "Acc: %d %d %d", - secondaryImuConfig()->calibrationOffsetAcc[X], - secondaryImuConfig()->calibrationOffsetAcc[Y], - secondaryImuConfig()->calibrationOffsetAcc[Z] - ); - cliPrintLinef( - "Mag: %d %d %d", - secondaryImuConfig()->calibrationOffsetMag[X], - secondaryImuConfig()->calibrationOffsetMag[Y], - secondaryImuConfig()->calibrationOffsetMag[Z] - ); - cliPrintLinef( - "Radius: %d %d", - secondaryImuConfig()->calibrationRadiusAcc, - secondaryImuConfig()->calibrationRadiusMag - ); -} - -static void cliImu2(char *cmdline) -{ - if (sl_strcasecmp(cmdline, "fetch") == 0) { - secondaryImuFetchCalibration(); - printImu2Status(); - } else { - printImu2Status(); - } -} - -#endif - static void cliSave(char *cmdline) { UNUSED(cmdline); @@ -3351,19 +3311,14 @@ static void cliStatus(char *cmdline) cliPrintLinef(" PCLK2 = %d MHz", clocks.PCLK2_Frequency / 1000000); #endif - cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s, IMU2=%s", + cliPrintLinef("Sensor status: GYRO=%s, ACC=%s, MAG=%s, BARO=%s, RANGEFINDER=%s, OPFLOW=%s, GPS=%s", hardwareSensorStatusNames[getHwGyroStatus()], hardwareSensorStatusNames[getHwAccelerometerStatus()], hardwareSensorStatusNames[getHwCompassStatus()], hardwareSensorStatusNames[getHwBarometerStatus()], hardwareSensorStatusNames[getHwRangefinderStatus()], hardwareSensorStatusNames[getHwOpticalFlowStatus()], - hardwareSensorStatusNames[getHwGPSStatus()], -#ifdef USE_SECONDARY_IMU - hardwareSensorStatusNames[getHwSecondaryImuStatus()] -#else - hardwareSensorStatusNames[0] -#endif + hardwareSensorStatusNames[getHwGPSStatus()] ); #ifdef USE_ESC_SENSOR @@ -3639,7 +3594,7 @@ static void printConfig(const char *cmdline, bool doDiff) printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0)); // print custom servo mixer if exists - cliPrintHashLine("servo mix"); + cliPrintHashLine("servo mixer"); cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n"); printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0)); @@ -3651,16 +3606,6 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("safehome"); printSafeHomes(dumpMask, safeHomeConfig_CopyArray, safeHomeConfig(0)); #endif -#ifdef USE_PROGRAMMING_FRAMEWORK - cliPrintHashLine("logic"); - printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0)); - - cliPrintHashLine("gvar"); - printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0)); - - cliPrintHashLine("pid"); - printPid(dumpMask, programmingPids_CopyArray, programmingPids(0)); -#endif cliPrintHashLine("feature"); printFeature(dumpMask, &featureConfig_Copy, featureConfig()); @@ -3716,6 +3661,17 @@ static void printConfig(const char *cmdline, bool doDiff) printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1); #endif +#ifdef USE_PROGRAMMING_FRAMEWORK + cliPrintHashLine("logic"); + printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0), -1); + + cliPrintHashLine("global vars"); + printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0)); + + cliPrintHashLine("programmable pid controllers"); + printPid(dumpMask, programmingPids_CopyArray, programmingPids(0)); +#endif + cliPrintHashLine("master"); dumpAllValues(MASTER_VALUE, dumpMask); @@ -3736,7 +3692,6 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintLinef("profile %d", currentProfileIndexSave + 1); cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1); - cliPrintHashLine("save configuration\r\nsave"); #ifdef USE_CLI_BATCH batchModeEnabled = false; #endif @@ -3755,6 +3710,10 @@ static void printConfig(const char *cmdline, bool doDiff) cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask); } + if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) { + cliPrintHashLine("save configuration\r\nsave"); + } + #ifdef USE_CLI_BATCH if (batchModeEnabled) { cliPrintHashLine("end the command batch"); @@ -3904,9 +3863,6 @@ const clicmd_t cmdTable[] = { "[]", cliBatteryProfile), CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource), CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange), -#ifdef USE_SECONDARY_IMU - CLI_COMMAND_DEF("imu2", "Secondary IMU", NULL, cliImu2), -#endif #if defined(USE_SAFE_HOME) CLI_COMMAND_DEF("safehome", "safe home list", NULL, cliSafeHomes), #endif @@ -4055,7 +4011,7 @@ void cliProcess(void) bufferIndex = 0; } - memset(cliBuffer, 0, sizeof(cliBuffer)); + ZERO_FARRAY(cliBuffer); // 'exit' will reset this flag, so we don't need to print prompt again if (!cliMode) diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h index 308b87d314..e07c328560 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav + * This file is part of INAV * - * iNav free software. You can redistribute + * INAV free software. You can redistribute * this software and/or modify this software 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 distributed in the hope that it + * INAV 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. diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index fa18a97d93..8e0b5341b1 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -86,7 +86,6 @@ FILE_COMPILE_FOR_SPEED #include "flight/servos.h" #include "flight/pid.h" #include "flight/imu.h" -#include "flight/secondary_imu.h" #include "flight/rate_dynamics.h" #include "flight/failsafe.h" @@ -213,10 +212,10 @@ static void updateArmingStatus(void) /* CHECK: Throttle */ if (!armingConfig()->fixed_wing_auto_arm) { // Don't want this check if fixed_wing_auto_arm is in use - machine arms on throttle > LOW - if (calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) != THROTTLE_LOW) { - ENABLE_ARMING_FLAG(ARMING_DISABLED_THROTTLE); - } else { + if (throttleStickIsLow()) { DISABLE_ARMING_FLAG(ARMING_DISABLED_THROTTLE); + } else { + ENABLE_ARMING_FLAG(ARMING_DISABLED_THROTTLE); } } @@ -265,7 +264,7 @@ static void updateArmingStatus(void) /* CHECK: */ if ( - sensors(SENSOR_ACC) && + sensors(SENSOR_ACC) && !STATE(ACCELEROMETER_CALIBRATED) && // Require ACC calibration only if any of the setting might require it ( @@ -389,7 +388,7 @@ static bool emergencyArmingIsEnabled(void) return emergencyArmingIsTriggered() && emergencyArmingCanOverrideArmingDisabled(); } -void annexCode(float dT) +static void processPilotAndFailSafeActions(float dT) { if (failsafeShouldApplyControlInput()) { // Failsafe will apply rcCommand for us @@ -436,8 +435,6 @@ void annexCode(float dT) rcCommand[PITCH] = rcCommand_PITCH; } } - - updateArmingStatus(); } void disarm(disarmReason_t disarmReason) @@ -525,9 +522,6 @@ void releaseSharedTelemetryPorts(void) { void tryArm(void) { -#ifdef USE_MULTI_MISSION - setMultiMissionOnArm(); -#endif updateArmingStatus(); #ifdef USE_DSHOT @@ -636,13 +630,13 @@ void processRx(timeUs_t currentTimeUs) failsafeUpdateState(); - const throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); + const bool throttleIsLow = throttleStickIsLow(); // When armed and motors aren't spinning, do beeps periodically if (ARMING_FLAG(ARMED) && feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY)) { static bool armedBeeperOn = false; - if (throttleStatus == THROTTLE_LOW) { + if (throttleIsLow) { beeper(BEEPER_ARMED); armedBeeperOn = true; } else if (armedBeeperOn) { @@ -651,7 +645,7 @@ void processRx(timeUs_t currentTimeUs) } } - processRcStickPositions(throttleStatus); + processRcStickPositions(throttleIsLow); processAirmode(); updateActivatedModes(); @@ -765,7 +759,7 @@ void processRx(timeUs_t currentTimeUs) pidResetErrorAccumulators(); } else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { - if (throttleStatus == THROTTLE_LOW) { + if (throttleIsLow) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) { ENABLE_STATE(ANTI_WINDUP); @@ -784,7 +778,7 @@ void processRx(timeUs_t currentTimeUs) } } else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) { - if (throttleStatus == THROTTLE_LOW) { + if (throttleIsLow) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) { ENABLE_STATE(ANTI_WINDUP); @@ -808,7 +802,7 @@ void processRx(timeUs_t currentTimeUs) else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { DISABLE_STATE(ANTI_WINDUP); //This case applies only to MR when Airmode management is throttle threshold activated - if (throttleStatus == THROTTLE_LOW && !STATE(AIRMODE_ACTIVE)) { + if (throttleIsLow && !STATE(AIRMODE_ACTIVE)) { pidResetErrorAccumulators(); } } @@ -883,7 +877,9 @@ void taskMainPidLoop(timeUs_t currentTimeUs) imuUpdateAccelerometer(); imuUpdateAttitude(currentTimeUs); - annexCode(dT); + processPilotAndFailSafeActions(dT); + + updateArmingStatus(); if (rxConfig()->rcFilterFrequency) { rcInterpolationApply(isRXDataNew, currentTimeUs); @@ -927,13 +923,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs) // Calculate stabilisation pidController(dT); -#ifdef HIL - if (hilActive) { - hilUpdateControlState(); - motorControlEnable = false; - } -#endif - mixTable(); if (isMixerUsingServos()) { diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 6b462b12f8..a8ab8146d2 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -72,7 +72,6 @@ #include "drivers/timer.h" #include "drivers/uart_inverter.h" #include "drivers/io.h" -#include "drivers/exti.h" #include "drivers/vtx_common.h" #ifdef USE_USB_MSC #include "drivers/usb_msc.h" @@ -97,7 +96,6 @@ #include "flight/power_limits.h" #include "flight/rpm_filter.h" #include "flight/servos.h" -#include "flight/secondary_imu.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/beeper.h" @@ -106,7 +104,7 @@ #include "io/displayport_frsky_osd.h" #include "io/displayport_msp.h" #include "io/displayport_max7456.h" -#include "io/displayport_hdzero_osd.h" +#include "io/displayport_msp_osd.h" #include "io/displayport_srxl.h" #include "io/flashfs.h" #include "io/gps.h" @@ -249,9 +247,7 @@ void init(void) ledInit(false); -#ifdef USE_EXTI EXTIInit(); -#endif #ifdef USE_SPEKTRUM_BIND if (rxConfig()->receiverType == RX_TYPE_SERIAL) { @@ -547,9 +543,9 @@ void init(void) osdDisplayPort = frskyOSDDisplayPortInit(osdConfig()->video_system); } #endif -#ifdef USE_HDZERO_OSD +#ifdef USE_MSP_OSD if (!osdDisplayPort) { - osdDisplayPort = hdzeroOsdDisplayPortInit(); + osdDisplayPort = mspOsdDisplayPortInit(osdConfig()->video_system); } #endif #if defined(USE_MAX7456) @@ -680,9 +676,6 @@ void init(void) latchActiveFeatures(); motorControlEnable = true; -#ifdef USE_SECONDARY_IMU - secondaryImuInit(); -#endif fcTasksInit(); #ifdef USE_OSD diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ac28c1ca13..524fc6319b 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -73,11 +73,9 @@ #include "flight/failsafe.h" #include "flight/imu.h" -#include "flight/hil.h" #include "flight/mixer.h" #include "flight/pid.h" #include "flight/servos.h" -#include "flight/secondary_imu.h" #include "config/config_eeprom.h" #include "config/feature.h" @@ -402,15 +400,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteData(dst, shortGitRevision, GIT_SHORT_REVISION_LENGTH); break; -#ifdef HIL - case MSP_HIL_STATE: - sbufWriteU16(dst, hilToSIM.pidCommand[ROLL]); - sbufWriteU16(dst, hilToSIM.pidCommand[PITCH]); - sbufWriteU16(dst, hilToSIM.pidCommand[YAW]); - sbufWriteU16(dst, hilToSIM.pidCommand[THROTTLE]); - break; -#endif - case MSP_SENSOR_STATUS: sbufWriteU8(dst, isHardwareHealthy() ? 1 : 0); sbufWriteU8(dst, getHwGyroStatus()); @@ -421,11 +410,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, getHwRangefinderStatus()); sbufWriteU8(dst, getHwPitotmeterStatus()); sbufWriteU8(dst, getHwOpticalFlowStatus()); -#ifdef USE_SECONDARY_IMU - sbufWriteU8(dst, getHwSecondaryImuStatus()); -#else - sbufWriteU8(dst, 0); -#endif break; case MSP_ACTIVEBOXES: @@ -1581,7 +1565,7 @@ static void mspFcWaypointOutCommand(sbuf_t *dst, sbuf_t *src) const uint8_t msp_wp_no = sbufReadU8(src); // get the wp number navWaypoint_t msp_wp; getWaypoint(msp_wp_no, &msp_wp); - sbufWriteU8(dst, msp_wp_no); // wp_no + sbufWriteU8(dst, msp_wp_no); // wp_no sbufWriteU8(dst, msp_wp.action); // action (WAYPOINT) sbufWriteU32(dst, msp_wp.lat); // lat sbufWriteU32(dst, msp_wp.lon); // lon @@ -2484,9 +2468,9 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else { DISABLE_STATE(GPS_FIX); } - gpsSol.flags.validVelNE = 0; - gpsSol.flags.validVelD = 0; - gpsSol.flags.validEPE = 0; + gpsSol.flags.validVelNE = false; + gpsSol.flags.validVelD = false; + gpsSol.flags.validEPE = false; gpsSol.numSat = sbufReadU8(src); gpsSol.llh.lat = sbufReadU32(src); gpsSol.llh.lon = sbufReadU32(src); @@ -3223,7 +3207,7 @@ void mspWriteSimulatorOSD(sbuf_t *dst) int processedRows = 16; - while (bytesCount < 80) //whole response should be less 155 bytes at worst. + while (bytesCount < 80) //whole response should be less 155 bytes at worst. { bool blink1; uint16_t lastChar; @@ -3290,14 +3274,14 @@ void mspWriteSimulatorOSD(sbuf_t *dst) else if (count > 2 || cmd !=0 ) { cmd |= count; //long command for blink/bank switch and symbol repeat - sbufWriteU8(dst, 0); + sbufWriteU8(dst, 0); sbufWriteU8(dst, cmd); sbufWriteU8(dst, lastChar & 0xff); bytesCount += 3; } else if (count == 2) //cmd == 0 here { - sbufWriteU8(dst, lastChar & 0xff); + sbufWriteU8(dst, lastChar & 0xff); sbufWriteU8(dst, lastChar & 0xff); bytesCount+=2; } @@ -3394,19 +3378,23 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu break; #endif case MSP2_INAV_SAFEHOME: - *ret = mspFcSafeHomeOutCommand(dst, src); - break; + *ret = mspFcSafeHomeOutCommand(dst, src); + break; #ifdef USE_SIMULATOR case MSP_SIMULATOR: - tmp_u8 = sbufReadU8(src); //MSP_SIMULATOR version - if (tmp_u8 != 2) break; + tmp_u8 = sbufReadU8(src); // Get the Simulator MSP version + + // Check the MSP version of simulator + if (tmp_u8 != SIMULATOR_MSP_VERSION) { + break; + } simulatorData.flags = sbufReadU8(src); - if ((simulatorData.flags & SIMU_ENABLE) == 0) { + if (!SIMULATOR_HAS_OPTION(HITL_ENABLE)) { - if (ARMING_FLAG(SIMULATOR_MODE)) { // just once + if (ARMING_FLAG(SIMULATOR_MODE)) { // Just once DISABLE_ARMING_FLAG(SIMULATOR_MODE); #ifdef USE_BARO @@ -3416,19 +3404,19 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu DISABLE_STATE(COMPASS_CALIBRATED); compassInit(); #endif - simulatorData.flags = 0; - //review: many states were affected. reboot? + simulatorData.flags = HITL_RESET_FLAGS; + // Review: Many states were affected. Reboot? - disarm(DISARM_SWITCH); //disarm to prevent motor output!!! + disarm(DISARM_SWITCH); // Disarm to prevent motor output!!! } - } - else if (!areSensorsCalibrating()) { - if (!ARMING_FLAG(SIMULATOR_MODE)) { // just once + } else if (!areSensorsCalibrating()) { + if (!ARMING_FLAG(SIMULATOR_MODE)) { // Just once #ifdef USE_BARO - baroStartCalibration(); + baroStartCalibration(); #endif + #ifdef USE_MAG - if (compassConfig()->mag_hardware != MAG_NONE){ + if (compassConfig()->mag_hardware != MAG_NONE) { sensorsSet(SENSOR_MAG); ENABLE_STATE(COMPASS_CALIBRATED); DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE); @@ -3438,21 +3426,21 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu } #endif ENABLE_ARMING_FLAG(SIMULATOR_MODE); - LOG_D(SYSTEM, "Simulator enabled"); + LOG_DEBUG(SYSTEM, "Simulator enabled"); } if (dataSize >= 14) { - if (feature(FEATURE_GPS) && ((simulatorData.flags & SIMU_HAS_NEW_GPS_DATA)!=0) ) { + if (feature(FEATURE_GPS) && SIMULATOR_HAS_OPTION(HITL_HAS_NEW_GPS_DATA)) { gpsSol.fixType = sbufReadU8(src); gpsSol.hdop = gpsSol.fixType == GPS_NO_FIX ? 9999 : 100; gpsSol.flags.hasNewData = true; gpsSol.numSat = sbufReadU8(src); if (gpsSol.fixType != GPS_NO_FIX) { - gpsSol.flags.validVelNE = 1; - gpsSol.flags.validVelD = 1; - gpsSol.flags.validEPE = 1; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; + gpsSol.flags.validEPE = true; gpsSol.llh.lat = sbufReadU32(src); gpsSol.llh.lon = sbufReadU32(src); @@ -3468,92 +3456,82 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu gpsSol.epv = 100; ENABLE_STATE(GPS_FIX); - - // Feed data to navigation - gpsProcessNewSolutionData(); + } else { + sbufAdvance(src, sizeof(uint32_t) + sizeof(uint32_t) + sizeof(uint32_t) + sizeof(uint16_t) + sizeof(uint16_t) + sizeof(uint16_t) * 3); } - else { - sbufAdvance(src, 4 + 4 + 4 + 2 + 2 + 2 * 3); - // Feed data to navigation - gpsProcessNewSolutionData(); - } - } - else { - sbufAdvance(src, 1 + 1 + 4 + 4 + 4 + 2 + 2 + 2 * 3); + // Feed data to navigation + gpsProcessNewSolutionData(); + } else { + sbufAdvance(src, sizeof(uint8_t) + sizeof(uint8_t) + sizeof(uint32_t) + sizeof(uint32_t) + sizeof(uint32_t) + sizeof(uint16_t) + sizeof(uint16_t) + sizeof(uint16_t) * 3); } - if ((simulatorData.flags & SIMU_USE_SENSORS) == 0) { + if (!SIMULATOR_HAS_OPTION(HITL_USE_IMU)) { attitude.values.roll = (int16_t)sbufReadU16(src); attitude.values.pitch = (int16_t)sbufReadU16(src); attitude.values.yaw = (int16_t)sbufReadU16(src); + } else { + sbufAdvance(src, sizeof(uint16_t) * XYZ_AXIS_COUNT); } - else - { - sbufAdvance(src, 2*3); - } - - acc.accADCf[X] = ((int16_t)sbufReadU16(src)) / 1000.0f;// acceleration in 1G units + + // Get the acceleration in 1G units + acc.accADCf[X] = ((int16_t)sbufReadU16(src)) / 1000.0f; acc.accADCf[Y] = ((int16_t)sbufReadU16(src)) / 1000.0f; acc.accADCf[Z] = ((int16_t)sbufReadU16(src)) / 1000.0f; - acc.accVibeSq[X] = 0; - acc.accVibeSq[Y] = 0; - acc.accVibeSq[Z] = 0; - + acc.accVibeSq[X] = 0.0f; + acc.accVibeSq[Y] = 0.0f; + acc.accVibeSq[Z] = 0.0f; + + // Get the angular velocity in DPS gyro.gyroADCf[X] = ((int16_t)sbufReadU16(src)) / 16.0f; gyro.gyroADCf[Y] = ((int16_t)sbufReadU16(src)) / 16.0f; gyro.gyroADCf[Z] = ((int16_t)sbufReadU16(src)) / 16.0f; - if (sensors(SENSOR_BARO)) - { + if (sensors(SENSOR_BARO)) { baro.baroPressure = (int32_t)sbufReadU32(src); - baro.baroTemperature = 2500; - } - else { - sbufAdvance(src,4); + baro.baroTemperature = DEGREES_TO_CENTIDEGREES(SIMULATOR_BARO_TEMP); + } else { + sbufAdvance(src, sizeof(uint32_t)); } - if (sensors(SENSOR_MAG)) - { - mag.magADC[X] = ((int16_t)sbufReadU16(src)) / 20; //16000/20 = 800uT + if (sensors(SENSOR_MAG)) { + mag.magADC[X] = ((int16_t)sbufReadU16(src)) / 20; // 16000 / 20 = 800uT mag.magADC[Y] = ((int16_t)sbufReadU16(src)) / 20; mag.magADC[Z] = ((int16_t)sbufReadU16(src)) / 20; - } - else { - sbufAdvance(src, 2*3); + } else { + sbufAdvance(src, sizeof(uint16_t) * XYZ_AXIS_COUNT); } - if (simulatorData.flags & SIMU_EXT_BATTERY_VOLTAGE) { - simulatorData.vbat = sbufReadU8(src); - } - else { - simulatorData.vbat = 126; + if (SIMULATOR_HAS_OPTION(HITL_EXT_BATTERY_VOLTAGE)) { + simulatorData.vbat = sbufReadU8(src); + } else { + simulatorData.vbat = (uint8_t)(SIMULATOR_FULL_BATTERY * 10.0f); } - if (simulatorData.flags & SIMU_AIRSPEED) { - simulatorData.airSpeed = sbufReadU16(src); + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { + simulatorData.airSpeed = sbufReadU16(src); } - } - else { + } else { DISABLE_STATE(GPS_FIX); } } - sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_ROLL); - sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_PITCH); - sbufWriteU16(dst, (uint16_t)simulatorData.INPUT_STABILIZED_YAW); - sbufWriteU16(dst, (uint16_t)(ARMING_FLAG(ARMED) ? simulatorData.INPUT_STABILIZED_THROTTLE : -500)); + sbufWriteU16(dst, (uint16_t)simulatorData.input[INPUT_STABILIZED_ROLL]); + sbufWriteU16(dst, (uint16_t)simulatorData.input[INPUT_STABILIZED_PITCH]); + sbufWriteU16(dst, (uint16_t)simulatorData.input[INPUT_STABILIZED_YAW]); + sbufWriteU16(dst, (uint16_t)(ARMING_FLAG(ARMED) ? simulatorData.input[INPUT_STABILIZED_THROTTLE] : -500)); simulatorData.debugIndex++; if (simulatorData.debugIndex == 8) { simulatorData.debugIndex = 0; } - tmp_u8 = simulatorData.debugIndex | - ((mixerConfig()->platformType == PLATFORM_AIRPLANE) ? 128 : 0) | + tmp_u8 = simulatorData.debugIndex | + ((mixerConfig()->platformType == PLATFORM_AIRPLANE) ? 128 : 0) | (ARMING_FLAG(ARMED) ? 64 : 0) | (!feature(FEATURE_OSD) ? 32: 0) | - (!isOSDTypeSupportedBySimulator() ? 16: 0); - sbufWriteU8(dst, tmp_u8 ); + (!isOSDTypeSupportedBySimulator() ? 16 : 0); + + sbufWriteU8(dst, tmp_u8); sbufWriteU32(dst, debug[simulatorData.debugIndex]); sbufWriteU16(dst, attitude.values.roll); diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 7fb1cd9be0..80458c3ac3 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -84,18 +84,19 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { .boxId = BOXOSDALT3, .boxName = "OSD ALT 3", .permanentId = 44 }, { .boxId = BOXNAVCOURSEHOLD, .boxName = "NAV COURSE HOLD", .permanentId = 45 }, { .boxId = BOXBRAKING, .boxName = "MC BRAKING", .permanentId = 46 }, - { .boxId = BOXUSER1, .boxName = "USER1", .permanentId = BOX_PERMANENT_ID_USER1 }, - { .boxId = BOXUSER2, .boxName = "USER2", .permanentId = BOX_PERMANENT_ID_USER2 }, - { .boxId = BOXUSER3, .boxName = "USER3", .permanentId = BOX_PERMANENT_ID_USER3 }, - { .boxId = BOXLOITERDIRCHN, .boxName = "LOITER CHANGE", .permanentId = 50 }, - { .boxId = BOXMSPRCOVERRIDE, .boxName = "MSP RC OVERRIDE", .permanentId = 51 }, - { .boxId = BOXPREARM, .boxName = "PREARM", .permanentId = 52 }, - { .boxId = BOXTURTLE, .boxName = "TURTLE", .permanentId = 53 }, - { .boxId = BOXNAVCRUISE, .boxName = "NAV CRUISE", .permanentId = 54 }, - { .boxId = BOXAUTOLEVEL, .boxName = "AUTO LEVEL", .permanentId = 55 }, - { .boxId = BOXPLANWPMISSION, .boxName = "WP PLANNER", .permanentId = 56 }, - { .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 57 }, - { .boxId = BOXGPSOFF, .boxName = "GPS OFF", .permanentId = 58 }, + { .boxId = BOXUSER1, .boxName = "USER1", .permanentId = BOX_PERMANENT_ID_USER1 }, // 47 + { .boxId = BOXUSER2, .boxName = "USER2", .permanentId = BOX_PERMANENT_ID_USER2 }, // 48 + { .boxId = BOXUSER3, .boxName = "USER3", .permanentId = BOX_PERMANENT_ID_USER3 }, // 57 + { .boxId = BOXUSER4, .boxName = "USER4", .permanentId = BOX_PERMANENT_ID_USER4 }, // 58 + { .boxId = BOXLOITERDIRCHN, .boxName = "LOITER CHANGE", .permanentId = 49 }, + { .boxId = BOXMSPRCOVERRIDE, .boxName = "MSP RC OVERRIDE", .permanentId = 50 }, + { .boxId = BOXPREARM, .boxName = "PREARM", .permanentId = 51 }, + { .boxId = BOXTURTLE, .boxName = "TURTLE", .permanentId = 52 }, + { .boxId = BOXNAVCRUISE, .boxName = "NAV CRUISE", .permanentId = 53 }, + { .boxId = BOXAUTOLEVEL, .boxName = "AUTO LEVEL", .permanentId = 54 }, + { .boxId = BOXPLANWPMISSION, .boxName = "WP PLANNER", .permanentId = 55 }, + { .boxId = BOXSOARING, .boxName = "SOARING", .permanentId = 56 }, + { .boxId = BOXCHANGEMISSION, .boxName = "MISSION CHANGE", .permanentId = 59 }, { .boxId = CHECKBOX_ITEM_COUNT, .boxName = NULL, .permanentId = 0xFF } }; @@ -228,6 +229,9 @@ void initActiveBoxIds(void) ADD_ACTIVE_BOX(BOXHOMERESET); ADD_ACTIVE_BOX(BOXGCSNAV); ADD_ACTIVE_BOX(BOXPLANWPMISSION); +#ifdef USE_MULTI_MISSION + ADD_ACTIVE_BOX(BOXCHANGEMISSION); +#endif } if (STATE(AIRPLANE)) { @@ -316,10 +320,9 @@ void initActiveBoxIds(void) ADD_ACTIVE_BOX(BOXUSER1); ADD_ACTIVE_BOX(BOXUSER2); ADD_ACTIVE_BOX(BOXUSER3); + ADD_ACTIVE_BOX(BOXUSER4); #endif - ADD_ACTIVE_BOX(BOXGPSOFF); - #if defined(USE_OSD) && defined(OSD_LAYOUT_COUNT) #if OSD_LAYOUT_COUNT > 0 ADD_ACTIVE_BOX(BOXOSDALT1); @@ -349,7 +352,7 @@ void initActiveBoxIds(void) void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) { uint8_t activeBoxes[CHECKBOX_ITEM_COUNT]; - memset(activeBoxes, 0, sizeof(activeBoxes)); + ZERO_FARRAY(activeBoxes); // Serialize the flags in the order we delivered them, ignoring BOXNAMES and BOXINDEXES // Requires new Multiwii protocol version to fix @@ -396,6 +399,7 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXUSER1)), BOXUSER1); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXUSER2)), BOXUSER2); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXUSER3)), BOXUSER3); + CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXUSER4)), BOXUSER4); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXLOITERDIRCHN)), BOXLOITERDIRCHN); #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXMSPRCOVERRIDE)), BOXMSPRCOVERRIDE); @@ -403,7 +407,9 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAUTOLEVEL)), BOXAUTOLEVEL); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)), BOXPLANWPMISSION); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXSOARING)), BOXSOARING); - CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXGPSOFF)), BOXGPSOFF); +#ifdef USE_MULTI_MISSION + CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION)), BOXCHANGEMISSION); +#endif memset(mspBoxModeFlags, 0, sizeof(boxBitmask_t)); for (uint32_t i = 0; i < activeBoxIdCount; i++) { diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 011f98e397..0e0b8c5432 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -49,7 +49,6 @@ #include "flight/pid.h" #include "flight/power_limits.h" #include "flight/rpm_filter.h" -#include "flight/secondary_imu.h" #include "flight/servos.h" #include "flight/wind_estimator.h" @@ -66,7 +65,7 @@ #include "io/smartport_master.h" #include "io/vtx.h" #include "io/osd_dji_hd.h" -#include "io/displayport_hdzero_osd.h" +#include "io/displayport_msp_osd.h" #include "io/servo_sbus.h" #include "msp/msp_serial.h" @@ -107,12 +106,12 @@ void taskHandleSerial(timeUs_t currentTimeUs) djiOsdSerialProcess(); #endif -#ifdef USE_HDZERO_OSD - // Capture HDZero messages to determine if VTX is connected - hdzeroOsdSerialProcess(mspFcProcessCommand); +#ifdef USE_MSP_OSD + // Capture MSP Displayport messages to determine if VTX is connected + mspOsdSerialProcess(mspFcProcessCommand); #endif -} +} void taskUpdateBattery(timeUs_t currentTimeUs) { static timeUs_t batMonitoringLastServiced = 0; @@ -398,9 +397,6 @@ void fcTasksInit(void) #if defined(USE_SMARTPORT_MASTER) setTaskEnabled(TASK_SMARTPORT_MASTER, true); #endif -#ifdef USE_SECONDARY_IMU - setTaskEnabled(TASK_SECONDARY_IMU, secondaryImuConfig()->hardwareType != SECONDARY_IMU_NONE && secondaryImuState.active); -#endif } cfTask_t cfTasks[TASK_COUNT] = { @@ -629,14 +625,6 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_IDLE, }, #endif -#ifdef USE_SECONDARY_IMU - [TASK_SECONDARY_IMU] = { - .taskName = "IMU2", - .taskFunc = taskSecondaryImu, - .desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec - .staticPriority = TASK_PRIORITY_IDLE, - }, -#endif #ifdef USE_RPM_FILTER [TASK_RPM_FILTER] = { .taskName = "RPM", diff --git a/src/main/fc/firmware_update.c b/src/main/fc/firmware_update.c index be8a22171b..d6f3f65f62 100644 --- a/src/main/fc/firmware_update.c +++ b/src/main/fc/firmware_update.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute this software + * INAV is free software. You can redistribute this software * and/or modify this software 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 they will be + * INAV is distributed in the hope that they 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. diff --git a/src/main/fc/firmware_update.h b/src/main/fc/firmware_update.h index 4bbb11693e..7951d88838 100644 --- a/src/main/fc/firmware_update.h +++ b/src/main/fc/firmware_update.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute this software + * INAV is free software. You can redistribute this software * and/or modify this software 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 they will be + * INAV is distributed in the hope that they 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. diff --git a/src/main/fc/firmware_update_common.h b/src/main/fc/firmware_update_common.h index ce396875ad..4ae3445099 100644 --- a/src/main/fc/firmware_update_common.h +++ b/src/main/fc/firmware_update_common.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute this software + * INAV is free software. You can redistribute this software * and/or modify this software 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 they will be + * INAV is distributed in the hope that they 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. diff --git a/src/main/fc/rc_adjustments.c b/src/main/fc/rc_adjustments.c index d1edcd20b5..37c338fedd 100644 --- a/src/main/fc/rc_adjustments.c +++ b/src/main/fc/rc_adjustments.c @@ -42,6 +42,7 @@ #include "fc/settings.h" #include "navigation/navigation.h" +#include "navigation/navigation_private.h" #include "flight/mixer.h" #include "flight/pid.h" @@ -297,6 +298,10 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU .adjustmentFunction = ADJUSTMENT_FW_LEVEL_TRIM, .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} + }, { + .adjustmentFunction = ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX, + .mode = ADJUSTMENT_MODE_STEP, + .data = { .stepConfig = { .step = 1 }} } }; @@ -569,7 +574,7 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t navigationUsePIDs(); break; case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - applyAdjustmentU16(ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, ¤tBatteryProfileMutable->fwMinThrottleDownPitchAngle, delta, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX); + applyAdjustmentU16(ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE, &navConfigMutable()->fw.minThrottleDownPitchAngle, delta, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MIN, SETTING_FW_MIN_THROTTLE_DOWN_PITCH_MAX); break; #if defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP) case ADJUSTMENT_VTX_POWER_LEVEL: @@ -587,7 +592,7 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t case ADJUSTMENT_TPA_BREAKPOINT: applyAdjustmentU16(ADJUSTMENT_TPA_BREAKPOINT, &controlRateConfig->throttle.pa_breakpoint, delta, PWM_RANGE_MIN, PWM_RANGE_MAX); break; - case ADJUSTMENT_FW_TPA_TIME_CONSTANT: + case ADJUSTMENT_FW_TPA_TIME_CONSTANT: applyAdjustmentU16(ADJUSTMENT_FW_TPA_TIME_CONSTANT, &controlRateConfig->throttle.fixedWingTauMs, delta, SETTING_FW_TPA_TIME_CONSTANT_MIN, SETTING_FW_TPA_TIME_CONSTANT_MAX); break; case ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS: @@ -602,6 +607,13 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t blackboxLogInflightAdjustmentEvent(ADJUSTMENT_FW_LEVEL_TRIM, (int)(newValue * 10.0f)); break; } +#ifdef USE_MULTI_MISSION + case ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX: + if (posControl.multiMissionCount && !FLIGHT_MODE(NAV_WP_MODE)) { + applyAdjustmentU8(ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX, &navConfigMutable()->general.waypoint_multi_mission_index, delta, SETTING_NAV_WP_MULTI_MISSION_INDEX_MIN, posControl.multiMissionCount); + } + break; +#endif default: break; }; diff --git a/src/main/fc/rc_adjustments.h b/src/main/fc/rc_adjustments.h index 30f25340bd..d5119ae927 100644 --- a/src/main/fc/rc_adjustments.h +++ b/src/main/fc/rc_adjustments.h @@ -84,6 +84,7 @@ typedef enum { ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS = 56, ADJUSTMENT_FW_TPA_TIME_CONSTANT = 57, ADJUSTMENT_FW_LEVEL_TRIM = 58, + ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX = 59, ADJUSTMENT_FUNCTION_COUNT // must be last } adjustmentFunction_e; diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 8b238c628d..0e122cd93d 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -37,6 +37,7 @@ #include "drivers/time.h" +#include "fc/cli.h" #include "fc/config.h" #include "fc/controlrate_profile.h" #include "fc/fc_core.h" @@ -110,22 +111,25 @@ bool isRollPitchStickDeflected(uint8_t deadband) throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e type) { - int value; - if (type == THROTTLE_STATUS_TYPE_RC) { - value = rxGetChannelValue(THROTTLE); - } else { + int value = rxGetChannelValue(THROTTLE); // THROTTLE_STATUS_TYPE_RC + if (type == THROTTLE_STATUS_TYPE_COMMAND) { value = rcCommand[THROTTLE]; } const uint16_t mid_throttle_deadband = rcControlsConfig()->mid_throttle_deadband; - if (feature(FEATURE_REVERSIBLE_MOTORS) && (value > (PWM_RANGE_MIDDLE - mid_throttle_deadband) && value < (PWM_RANGE_MIDDLE + mid_throttle_deadband))) - return THROTTLE_LOW; - else if (!feature(FEATURE_REVERSIBLE_MOTORS) && (value < rxConfig()->mincheck)) + bool midThrottle = value > (PWM_RANGE_MIDDLE - mid_throttle_deadband) && value < (PWM_RANGE_MIDDLE + mid_throttle_deadband); + if ((feature(FEATURE_REVERSIBLE_MOTORS) && midThrottle) || (!feature(FEATURE_REVERSIBLE_MOTORS) && (value < rxConfig()->mincheck))) { return THROTTLE_LOW; + } return THROTTLE_HIGH; } +bool throttleStickIsLow(void) +{ + return calculateThrottleStatus(feature(FEATURE_REVERSIBLE_MOTORS) ? THROTTLE_STATUS_TYPE_COMMAND : THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW; +} + int16_t throttleStickMixedValue(void) { int16_t throttleValue; @@ -180,7 +184,7 @@ static void updateRcStickPositions(void) rcStickPositions = tmp; } -void processRcStickPositions(throttleStatus_e throttleStatus) +void processRcStickPositions(bool isThrottleLow) { static timeMs_t lastTickTimeMs = 0; static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors @@ -210,7 +214,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus) if (STATE(AIRPLANE) && feature(FEATURE_MOTOR_STOP) && armingConfig()->fixed_wing_auto_arm) { // Auto arm on throttle when using fixedwing and motorstop - if (throttleStatus != THROTTLE_LOW) { + if (!isThrottleLow) { tryArm(); return; } @@ -226,7 +230,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus) if (ARMING_FLAG(ARMED) && !IS_RC_MODE_ACTIVE(BOXFAILSAFE) && rxIsReceivingSignal() && !failsafeIsActive()) { const timeMs_t disarmDelay = currentTimeMs - rcDisarmTimeMs; if (disarmDelay > armingConfig()->switchDisarmDelayMs) { - if (armingConfig()->disarm_kill_switch || (throttleStatus == THROTTLE_LOW)) { + if (armingConfig()->disarm_kill_switch || isThrottleLow) { disarm(DISARM_SWITCH); } } @@ -251,7 +255,12 @@ void processRcStickPositions(throttleStatus_e throttleStatus) return; } - // actions during not armed + // Disable stick commands when in CLI mode. Ideally, they should also be disabled when configurator is connected + if (cliMode) { + return; + } + + // actions during not armed and not in CLI // GYRO calibration if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) { diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 2637283e3d..ea23eae907 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -87,7 +87,7 @@ typedef struct rcControlsConfig_s { uint8_t pos_hold_deadband; // Deadband for position hold uint8_t control_deadband; // General deadband to check if sticks are deflected, us PWM. uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold - uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC + uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC uint8_t airmodeHandlingType; // Defaults to ANTI_WINDUP triggered at sticks centered uint16_t airmodeThrottleThreshold; // Throttle threshold for airmode initial activation } rcControlsConfig_t; @@ -95,8 +95,8 @@ typedef struct rcControlsConfig_s { PG_DECLARE(rcControlsConfig_t, rcControlsConfig); typedef struct armingConfig_s { - bool fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm - bool disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value + bool fixed_wing_auto_arm; // Auto-arm fixed wing aircraft on throttle up and never disarm + bool disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value uint16_t switchDisarmDelayMs; // additional delay between ARM box going off and actual disarm uint16_t prearmTimeoutMs; // duration for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout. } armingConfig_t; @@ -112,6 +112,7 @@ bool isRollPitchStickDeflected(uint8_t deadband); throttleStatus_e calculateThrottleStatus(throttleStatusType_e type); int16_t throttleStickMixedValue(void); rollPitchStatus_e calculateRollPitchCenterStatus(void); -void processRcStickPositions(throttleStatus_e throttleStatus); +void processRcStickPositions(bool isThrottleLow); +bool throttleStickIsLow(void); int32_t getRcStickDeflection(int32_t axis); diff --git a/src/main/fc/rc_modes.h b/src/main/fc/rc_modes.h index d8819ad75c..a72be3ddb8 100644 --- a/src/main/fc/rc_modes.h +++ b/src/main/fc/rc_modes.h @@ -75,7 +75,8 @@ typedef enum { BOXPLANWPMISSION = 46, BOXSOARING = 47, BOXUSER3 = 48, - BOXGPSOFF = 49, + BOXUSER4 = 49, + BOXCHANGEMISSION = 50, CHECKBOX_ITEM_COUNT } boxId_e; diff --git a/src/main/fc/rc_smoothing.c b/src/main/fc/rc_smoothing.c index c47cbc8e7c..91e5a0792b 100644 --- a/src/main/fc/rc_smoothing.c +++ b/src/main/fc/rc_smoothing.c @@ -82,7 +82,7 @@ void rcInterpolationApply(bool isRXDataNew, timeUs_t currentTimeUs) static int filterFrequency; static bool initDone = false; - const float dT = getLooptime() * 1e-6f; + const float dT = US2S(getLooptime()); if (isRXDataNew) { if (!initDone) { diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index 01fc555c42..779935b127 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -167,29 +167,33 @@ typedef enum { flightModeForTelemetry_e getFlightModeForTelemetry(void); #ifdef USE_SIMULATOR + +#define SIMULATOR_MSP_VERSION 2 // Simulator MSP version +#define SIMULATOR_BARO_TEMP 25 // °C +#define SIMULATOR_FULL_BATTERY 12.6f // Volts +#define SIMULATOR_HAS_OPTION(flag) ((simulatorData.flags & flag) != 0) + typedef enum { - SIMU_ENABLE = (1 << 0), - SIMU_SIMULATE_BATTERY = (1 << 1), - SIMU_MUTE_BEEPER = (1 << 2), - SIMU_USE_SENSORS = (1 << 3), - SIMU_HAS_NEW_GPS_DATA = (1 << 4), - SIMU_EXT_BATTERY_VOLTAGE = (1 << 5),//extend MSP_SIMULATOR format 2 - SIMU_AIRSPEED = (1 << 6) + HITL_RESET_FLAGS = (0 << 0), + HITL_ENABLE = (1 << 0), + HITL_SIMULATE_BATTERY = (1 << 1), + HITL_MUTE_BEEPER = (1 << 2), + HITL_USE_IMU = (1 << 3), // Use the Acc and Gyro data provided by XPlane to calculate Attitude (i.e. 100% of the calculations made by AHRS from INAV) + HITL_HAS_NEW_GPS_DATA = (1 << 4), + HITL_EXT_BATTERY_VOLTAGE = (1 << 5), // Extend MSP_SIMULATOR format 2 + HITL_AIRSPEED = (1 << 6) } simulatorFlags_t; typedef struct { simulatorFlags_t flags; uint8_t debugIndex; - uint8_t vbat; //126 ->12.6V - uint16_t airSpeed; //cm/s - - int16_t INPUT_STABILIZED_ROLL; - int16_t INPUT_STABILIZED_PITCH; - int16_t INPUT_STABILIZED_YAW; - int16_t INPUT_STABILIZED_THROTTLE; + uint8_t vbat; // 126 -> 12.6V + uint16_t airSpeed; // cm/s + int16_t input[4]; } simulatorData_t; extern simulatorData_t simulatorData; + #endif uint32_t enableFlightMode(flightModeFlags_e mask); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index be17f96325..15b05bf3c6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -9,9 +9,6 @@ tables: - name: rangefinder_hardware values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"] enum: rangefinderType_e - - name: secondary_imu_hardware - values: ["NONE", "BNO055_SERIAL"] - enum: secondaryImuType_e - name: mag_hardware values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"] enum: magSensor_e @@ -43,6 +40,9 @@ tables: - name: voltage_sensor values: ["NONE", "ADC", "ESC"] enum: voltageSensor_e + - name: imu_inertia_comp_method + values: ["VELNED", "TURNRATE","ADAPTIVE"] + enum: imu_inertia_comp_method_e - name: gps_provider values: ["NMEA", "UBLOX", "UBLOX7", "MSP"] enum: gpsProvider_e @@ -72,7 +72,7 @@ tables: values: ["BATTERY", "CELL"] enum: osd_stats_min_voltage_unit_e - name: osd_video_system - values: ["AUTO", "PAL", "NTSC", "HD"] + values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF"] enum: videoSystem_e - name: osd_telemetry values: ["OFF", "ON","TEST"] @@ -90,8 +90,8 @@ tables: - name: debug_modes values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", - "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "IMU2", "ALTITUDE", - "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING"] + "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE", + "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST"] - name: aux_operator values: ["OR", "AND"] enum: modeActivationOperator_e @@ -480,98 +480,6 @@ groups: type: uint8_t table: alignment - - name: PG_SECONDARY_IMU - type: secondaryImuConfig_t - headers: ["flight/secondary_imu.h"] - condition: USE_SECONDARY_IMU - members: - - name: imu2_hardware - description: "Selection of a Secondary IMU hardware type. NONE disables this functionality" - default_value: "NONE" - field: hardwareType - table: secondary_imu_hardware - - name: imu2_use_for_osd_heading - description: "If set to ON, Secondary IMU data will be used for Analog OSD heading" - default_value: OFF - field: useForOsdHeading - type: bool - - name: imu2_use_for_osd_ahi - description: "If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon" - field: useForOsdAHI - default_value: OFF - type: bool - - name: imu2_use_for_stabilized - description: "If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH)" - field: useForStabilized - default_value: OFF - type: bool - - name: imu2_align_roll - description: "Roll alignment for Secondary IMU. 1/10 of a degree" - field: rollDeciDegrees - default_value: 0 - min: -1800 - max: 3600 - - name: imu2_align_pitch - description: "Pitch alignment for Secondary IMU. 1/10 of a degree" - field: pitchDeciDegrees - default_value: 0 - min: -1800 - max: 3600 - - name: imu2_align_yaw - description: "Yaw alignment for Secondary IMU. 1/10 of a degree" - field: yawDeciDegrees - default_value: 0 - min: -1800 - max: 3600 - - name: imu2_gain_acc_x - description: "Secondary IMU ACC calibration data" - field: calibrationOffsetAcc[X] - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_gain_acc_y - field: calibrationOffsetAcc[Y] - description: "Secondary IMU ACC calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_gain_acc_z - field: calibrationOffsetAcc[Z] - description: "Secondary IMU ACC calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_gain_mag_x - field: calibrationOffsetMag[X] - description: "Secondary IMU MAG calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_gain_mag_y - field: calibrationOffsetMag[Y] - description: "Secondary IMU MAG calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_gain_mag_z - field: calibrationOffsetMag[Z] - description: "Secondary IMU MAG calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_radius_acc - field: calibrationRadiusAcc - description: "Secondary IMU MAG calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: imu2_radius_mag - field: calibrationRadiusMag - description: "Secondary IMU MAG calibration data" - default_value: 0 - min: INT16_MIN - max: INT16_MAX - - name: PG_COMPASS_CONFIG type: compassConfig_t headers: ["sensors/compass.h"] @@ -927,10 +835,11 @@ groups: description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." default_value: "DROP" table: failsafe_procedure - - name: failsafe_mission - description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode" - default_value: ON - type: bool + - name: failsafe_mission_delay + description: "Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end." + default_value: 0 + min: -1 + max: 600 - name: PG_LIGHTS_CONFIG type: lightsConfig_t @@ -1139,12 +1048,6 @@ groups: default_value: 1000 min: PWM_RANGE_MIN max: PWM_RANGE_MAX - - name: fw_min_throttle_down_pitch - description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" - default_value: 0 - field: fwMinThrottleDownPitchAngle - min: 0 - max: 450 - name: nav_mc_hover_thr description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." default_value: 1500 @@ -1492,7 +1395,7 @@ groups: members: - name: imu_dcm_kp description: "Inertial Measurement Unit KP Gain for accelerometer measurements" - default_value: 1000 + default_value: 2000 field: dcm_kp_acc max: UINT16_MAX - name: imu_dcm_ki @@ -1502,12 +1405,12 @@ groups: max: UINT16_MAX - name: imu_dcm_kp_mag description: "Inertial Measurement Unit KP Gain for compass measurements" - default_value: 5000 + default_value: 2000 field: dcm_kp_mag max: UINT16_MAX - name: imu_dcm_ki_mag description: "Inertial Measurement Unit KI Gain for compass measurements" - default_value: 0 + default_value: 50 field: dcm_ki_mag max: UINT16_MAX - name: small_angle @@ -1516,17 +1419,27 @@ groups: min: 0 max: 180 - name: imu_acc_ignore_rate - description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" - default_value: 0 + description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy" + default_value: 15 field: acc_ignore_rate min: 0 - max: 20 + max: 30 - name: imu_acc_ignore_slope description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" - default_value: 0 + default_value: 5 field: acc_ignore_slope min: 0 - max: 5 + max: 10 + - name: imu_gps_yaw_windcomp + description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)" + default_value: ON + field: gps_yaw_windcomp + type: bool + - name: imu_inertia_comp_method + description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop" + default_value: VELNED + field: inertia_comp_method + table: imu_inertia_comp_method - name: PG_ARMING_CONFIG type: armingConfig_t @@ -1562,7 +1475,7 @@ groups: field: appliedDefaults type: uint8_t min: 0 - max: 4 + max: 99 - name: PG_RPM_FILTER_CONFIG headers: ["flight/rpm_filter.h"] @@ -1914,11 +1827,6 @@ groups: field: fixedWingItermThrowLimit min: FW_ITERM_THROW_LIMIT_MIN max: FW_ITERM_THROW_LIMIT_MAX - - name: fw_loiter_direction - description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick." - default_value: "RIGHT" - field: loiter_direction - table: direction - name: fw_reference_airspeed description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present." default_value: 1500 @@ -2267,7 +2175,7 @@ groups: min: 0 max: 255 - name: inav_use_gps_velned - description: "Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance." + description: "Defined if INAV should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF INAV will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance." default_value: ON field: use_gps_velned type: bool @@ -2276,7 +2184,7 @@ groups: type: bool default_value: OFF - name: inav_allow_dead_reckoning - description: "Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation" + description: "Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation" default_value: OFF field: allow_dead_reckoning type: bool @@ -2392,10 +2300,16 @@ groups: headers: ["navigation/navigation.h"] members: - name: nav_disarm_on_landing - description: "If set to ON, iNav disarms the FC after landing" + description: "If set to ON, INAV disarms the FC after landing" default_value: OFF field: general.flags.disarm_on_landing type: bool + - name: nav_land_detect_sensitivity + description: "Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases." + default_value: 5 + field: general.land_detect_sensitivity + min: 1 + max: 15 - name: nav_use_midthr_for_althold description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" default_value: OFF @@ -2434,22 +2348,23 @@ groups: field: general.waypoint_enforce_altitude min: 0 max: 2000 - - name: nav_wp_safe_distance - description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." - default_value: 10000 + - name: nav_wp_max_safe_distance + description: "First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check." + default_value: 100 field: general.waypoint_safe_distance - max: 65000 + min: 0 + max: 1500 - name: nav_wp_mission_restart description: "Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint." default_value: "RESUME" field: general.flags.waypoint_mission_restart table: nav_wp_mission_restart - name: nav_wp_multi_mission_index - description: "Index of mission selected from multi mission WP entry loaded in flight controller. 1 is the first useable WP mission in the entry. Limited to a maximum of 9 missions. Set index to 0 to display current active WP count in OSD Mission field." + description: "Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions." default_value: 1 field: general.waypoint_multi_mission_index condition: USE_MULTI_MISSION - min: 0 + min: 1 max: 9 - name: nav_fw_wp_tracking_accuracy description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable." @@ -2651,10 +2566,10 @@ groups: field: mc.max_bank_angle min: 15 max: 45 - - name: nav_mc_auto_disarm_delay - description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (ms)" + - name: nav_auto_disarm_delay + description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)" default_value: 2000 - field: mc.auto_disarm_delay + field: general.auto_disarm_delay min: 100 max: 10000 - name: nav_mc_braking_speed_threshold @@ -2730,12 +2645,6 @@ groups: default_value: ON field: mc.slowDownForTurning type: bool - - name: nav_fw_auto_disarm_delay - description: "Delay before plane disarms when `nav_disarm_on_landing` is set (ms)" - default_value: 2000 - field: fw.auto_disarm_delay - min: 100 - max: 10000 - name: nav_fw_bank_angle description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" default_value: 35 @@ -2760,6 +2669,12 @@ groups: field: fw.pitch_to_throttle_smooth min: 0 max: 9 + - name: fw_min_throttle_down_pitch + description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" + default_value: 0 + field: fw.minThrottleDownPitchAngle + min: 0 + max: 450 - name: nav_fw_pitch2thr_threshold description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]" default_value: 50 @@ -2772,6 +2687,11 @@ groups: field: fw.loiter_radius min: 0 max: 30000 + - name: fw_loiter_direction + description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick." + default_value: "RIGHT" + field: fw.loiter_direction + table: direction - name: nav_fw_cruise_speed description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" default_value: 0 @@ -3100,7 +3020,7 @@ groups: type: uint8_t default_value: "OFF" - name: osd_video_system - description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, and `HD`" + description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO` and 'DJIWTF'" default_value: "AUTO" table: osd_video_system field: video_system @@ -3508,6 +3428,13 @@ groups: default_value: 3 description: Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) + - name: osd_ahi_pitch_interval + field: ahi_pitch_interval + min: 0 + max: 30 + default_value: 0 + description: Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD) + - name: osd_home_position_arm_screen type: bool default_value: ON @@ -3725,7 +3652,7 @@ groups: field: smartAudioEarlyAkkWorkaroundEnable type: bool - name: vtx_smartaudio_alternate_softserial_method - description: "Enable the alternate softserial method. This is the method used in iNav 3.0 and ealier." + description: "Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier." default_value: ON field: smartAudioAltSoftSerialMethod type: bool diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 9a1cf2e194..79ea091af3 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -67,13 +67,13 @@ static failsafeState_t failsafeState; -PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 3); PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, .failsafe_delay = SETTING_FAILSAFE_DELAY_DEFAULT, // 0.5 sec .failsafe_recovery_delay = SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT, // 0.5 seconds (plus 200ms explicit delay) .failsafe_off_delay = SETTING_FAILSAFE_OFF_DELAY_DEFAULT, // 20sec - .failsafe_throttle_low_delay = SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT, // default throttle low delay for "just disarm" on failsafe condition + .failsafe_throttle_low_delay = SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT, // default throttle low delay for "just disarm" on failsafe condition .failsafe_procedure = SETTING_FAILSAFE_PROCEDURE_DEFAULT, // default full failsafe procedure .failsafe_fw_roll_angle = SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT, // 20 deg left .failsafe_fw_pitch_angle = SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT, // 10 deg dive (yes, positive means dive) @@ -81,7 +81,7 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, .failsafe_stick_motion_threshold = SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT, .failsafe_min_distance = SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT, // No minimum distance for failsafe by default .failsafe_min_distance_procedure = SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT, // default minimum distance failsafe procedure - .failsafe_mission = SETTING_FAILSAFE_MISSION_DEFAULT, // Enable failsafe in WP mode or not + .failsafe_mission_delay = SETTING_FAILSAFE_MISSION_DELAY_DEFAULT, // Time delay before Failsafe activated during WP mission (s) ); typedef enum { @@ -336,8 +336,14 @@ static bool failsafeCheckStickMotion(void) static failsafeProcedure_e failsafeChooseFailsafeProcedure(void) { - if ((FLIGHT_MODE(NAV_WP_MODE) || isWaypointMissionRTHActive()) && !failsafeConfig()->failsafe_mission) { - return FAILSAFE_PROCEDURE_NONE; + if ((FLIGHT_MODE(NAV_WP_MODE) || isWaypointMissionRTHActive()) && failsafeConfig()->failsafe_mission_delay) { + if (!failsafeState.wpModeDelayedFailsafeStart) { + failsafeState.wpModeDelayedFailsafeStart = millis(); + return FAILSAFE_PROCEDURE_NONE; + } else if ((millis() - failsafeState.wpModeDelayedFailsafeStart < (MILLIS_PER_SECOND * (uint16_t)failsafeConfig()->failsafe_mission_delay)) || + failsafeConfig()->failsafe_mission_delay == -1) { + return FAILSAFE_PROCEDURE_NONE; + } } // Craft is closer than minimum failsafe procedure distance (if set to non-zero) @@ -381,7 +387,7 @@ void failsafeUpdateState(void) case FAILSAFE_IDLE: if (armed) { // Track throttle command below minimum time - if (THROTTLE_HIGH == calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC)) { + if (!throttleStickIsLow()) { failsafeState.throttleLowPeriod = millis() + failsafeConfig()->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND; } if (!receivingRxDataAndNotFailsafeMode) { @@ -393,6 +399,7 @@ void failsafeUpdateState(void) failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_3_SECONDS; // require 3 seconds of valid rxData } else { failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED; + failsafeState.wpModeDelayedFailsafeStart = 0; } reprocessState = true; } @@ -448,6 +455,9 @@ void failsafeUpdateState(void) if (receivingRxDataAndNotFailsafeMode && sticksAreMoving) { failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED; reprocessState = true; + } else if (failsafeChooseFailsafeProcedure() != FAILSAFE_PROCEDURE_NONE) { // trigger new failsafe procedure if changed + failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED; + reprocessState = true; } break; diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 0a118d733d..7cd88acd59 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -42,7 +42,7 @@ typedef struct failsafeConfig_s { uint16_t failsafe_stick_motion_threshold; uint16_t failsafe_min_distance; // Minimum distance required for failsafe procedure to be taken. 1 step = 1 centimeter. 0 = Regular failsafe_procedure always active (default) uint8_t failsafe_min_distance_procedure; // selected minimum distance failsafe procedure is 0: auto-landing, 1: Drop it, 2: Return To Home (RTH) - bool failsafe_mission; // Enable failsafe in WP mode or not + int16_t failsafe_mission_delay; // Time delay before Failsafe triggered when WP mission in progress (s) } failsafeConfig_t; PG_DECLARE(failsafeConfig_t, failsafeConfig); @@ -148,6 +148,7 @@ typedef struct failsafeState_s { timeMs_t landingShouldBeFinishedAt; timeMs_t receivingRxDataPeriod; // period for the required period of valid rxData timeMs_t receivingRxDataPeriodPreset; // preset for the required period of valid rxData + timeMs_t wpModeDelayedFailsafeStart; // waypoint mission delayed failsafe timer start time failsafeProcedure_e activeProcedure; failsafePhase_e phase; failsafeRxLinkState_e rxLinkState; diff --git a/src/main/flight/gyroanalyse.c b/src/main/flight/gyroanalyse.c index 94fa23b844..16626f1dbe 100644 --- a/src/main/flight/gyroanalyse.c +++ b/src/main/flight/gyroanalyse.c @@ -96,7 +96,7 @@ void gyroDataAnalyseStateInit( for (int i = 0; i < DYN_NOTCH_PEAK_COUNT; i++) { state->centerFrequency[axis][i] = state->maxFrequency; - pt1FilterInit(&state->detectedFrequencyFilter[axis][i], DYN_NOTCH_SMOOTH_FREQ_HZ, filterUpdateUs * 1e-6f); + pt1FilterInit(&state->detectedFrequencyFilter[axis][i], DYN_NOTCH_SMOOTH_FREQ_HZ, US2S(filterUpdateUs)); } } diff --git a/src/main/flight/hil.c b/src/main/flight/hil.c deleted file mode 100644 index bb3b4a2d5d..0000000000 --- a/src/main/flight/hil.c +++ /dev/null @@ -1,73 +0,0 @@ -/* - * 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 . - */ - -// Inertial Measurement Unit (IMU) - -#include -#include -#include - -#include "platform.h" - -#ifdef HIL - -#include "build/build_config.h" -#include "build/debug.h" - -#include "common/axis.h" -#include "common/maths.h" -#include "common/filter.h" - -#include "drivers/time.h" - -#include "sensors/sensors.h" -#include "sensors/acceleration.h" -#include "sensors/boardalignment.h" - -#include "flight/pid.h" -#include "flight/imu.h" -#include "flight/hil.h" - -#include "fc/config.h" -#include "fc/runtime_config.h" - -#include "navigation/navigation.h" -#include "navigation/navigation_private.h" - - -bool hilActive = false; -hilIncomingStateData_t hilToFC; -hilOutgoingStateData_t hilToSIM; - -void hilUpdateControlState(void) -{ - // FIXME: There must be a cleaner way to to this - // If HIL active, store PID outout into hilState and disable motor control - if (FLIGHT_MODE(MANUAL_MODE) || !STATE(AIRPLANE)) { - hilToSIM.pidCommand[ROLL] = rcCommand[ROLL]; - hilToSIM.pidCommand[PITCH] = rcCommand[PITCH]; - hilToSIM.pidCommand[YAW] = rcCommand[YAW]; - } else { - hilToSIM.pidCommand[ROLL] = axisPID[ROLL]; - hilToSIM.pidCommand[PITCH] = axisPID[PITCH]; - hilToSIM.pidCommand[YAW] = axisPID[YAW]; - } - - hilToSIM.pidCommand[THROTTLE] = rcCommand[THROTTLE]; -} - -#endif diff --git a/src/main/flight/hil.h b/src/main/flight/hil.h deleted file mode 100644 index df51c1441d..0000000000 --- a/src/main/flight/hil.h +++ /dev/null @@ -1,42 +0,0 @@ -/* - * 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 - -#ifdef HIL - -typedef struct { - int16_t rollAngle; // deg * 10 - int16_t pitchAngle; // deg * 10 - int16_t yawAngle; // deg * 10 - - int32_t baroAlt; // cm above launch - - int16_t bodyAccel[3]; // cm/s/s // forward, right, up -} hilIncomingStateData_t; - -typedef struct { - int16_t pidCommand[4]; -} hilOutgoingStateData_t; - -extern bool hilActive; -extern hilIncomingStateData_t hilToFC; -extern hilOutgoingStateData_t hilToSIM; - -void hilUpdateControlState(void); - -#endif diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 3cc883f024..bdd69ba6d2 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -36,6 +36,8 @@ FILE_COMPILE_FOR_SPEED #include "common/maths.h" #include "common/vector.h" #include "common/quaternion.h" +#include "common/time.h" + #include "config/feature.h" #include "config/parameter_group.h" @@ -47,15 +49,18 @@ FILE_COMPILE_FOR_SPEED #include "fc/runtime_config.h" #include "fc/settings.h" -#include "flight/hil.h" #include "flight/imu.h" #include "flight/mixer.h" #include "flight/pid.h" +#if defined(USE_WIND_ESTIMATOR) +#include "flight/wind_estimator.h" +#endif #include "io/gps.h" #include "sensors/acceleration.h" #include "sensors/barometer.h" +#include "sensors/pitotmeter.h" #include "sensors/compass.h" #include "sensors/gyro.h" #include "sensors/sensors.h" @@ -73,11 +78,13 @@ FILE_COMPILE_FOR_SPEED // http://gentlenav.googlecode.com/files/fastRotations.pdf #define SPIN_RATE_LIMIT 20 -#define MAX_ACC_NEARNESS 0.33 // 33% or G error soft-accepted (0.67-1.33G) -#define IMU_CENTRIFUGAL_LPF 1 // Hz - +#define MAX_ACC_NEARNESS 0.2 // 20% or G error soft-accepted (0.8-1.2G) +#define IMU_ROTATION_LPF 3 // Hz FASTRAM fpVector3_t imuMeasuredAccelBF; FASTRAM fpVector3_t imuMeasuredRotationBF; +//centrifugal force compensated using gps +FASTRAM fpVector3_t compansatedGravityBF;// cm/s/s + STATIC_FASTRAM float smallAngleCosZ; STATIC_FASTRAM bool isAccelUpdatedAtLeastOnce; @@ -88,20 +95,34 @@ FASTRAM attitudeEulerAngles_t attitude; // absolute angle inclinatio FASTRAM float rMat[3][3]; STATIC_FASTRAM imuRuntimeConfig_t imuRuntimeConfig; -STATIC_FASTRAM pt1Filter_t rotRateFilter; -STATIC_FASTRAM bool gpsHeadingInitialized; +STATIC_FASTRAM pt1Filter_t rotRateFilterX; +STATIC_FASTRAM pt1Filter_t rotRateFilterY; +STATIC_FASTRAM pt1Filter_t rotRateFilterZ; +FASTRAM fpVector3_t imuMeasuredRotationBFFiltered = {.v = {0.0f, 0.0f, 0.0f}}; + +STATIC_FASTRAM pt1Filter_t HeadVecEFFilterX; +STATIC_FASTRAM pt1Filter_t HeadVecEFFilterY; +STATIC_FASTRAM pt1Filter_t HeadVecEFFilterZ; +FASTRAM fpVector3_t HeadVecEFFiltered = {.v = {0.0f, 0.0f, 0.0f}}; + +STATIC_FASTRAM float GPS3DspeedFiltered=0.0f; +STATIC_FASTRAM pt1Filter_t GPS3DspeedFilter; + +FASTRAM bool gpsHeadingInitialized; PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 2); PG_RESET_TEMPLATE(imuConfig_t, imuConfig, - .dcm_kp_acc = SETTING_IMU_DCM_KP_DEFAULT, // 0.25 * 10000 + .dcm_kp_acc = SETTING_IMU_DCM_KP_DEFAULT, // 0.20 * 10000 .dcm_ki_acc = SETTING_IMU_DCM_KI_DEFAULT, // 0.005 * 10000 - .dcm_kp_mag = SETTING_IMU_DCM_KP_MAG_DEFAULT, // 1.00 * 10000 - .dcm_ki_mag = SETTING_IMU_DCM_KI_MAG_DEFAULT, // 0.00 * 10000 + .dcm_kp_mag = SETTING_IMU_DCM_KP_MAG_DEFAULT, // 0.20 * 10000 + .dcm_ki_mag = SETTING_IMU_DCM_KI_MAG_DEFAULT, // 0.005 * 10000 .small_angle = SETTING_SMALL_ANGLE_DEFAULT, .acc_ignore_rate = SETTING_IMU_ACC_IGNORE_RATE_DEFAULT, - .acc_ignore_slope = SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT + .acc_ignore_slope = SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT, + .gps_yaw_windcomp = 1, + .inertia_comp_method = COMPMETHOD_VELNED ); STATIC_UNIT_TESTED void imuComputeRotationMatrix(void) @@ -165,7 +186,15 @@ void imuInit(void) imuComputeRotationMatrix(); // Initialize rotation rate filter - pt1FilterReset(&rotRateFilter, 0); + pt1FilterReset(&rotRateFilterX, 0); + pt1FilterReset(&rotRateFilterY, 0); + pt1FilterReset(&rotRateFilterZ, 0); + // Initialize Heading vector filter + pt1FilterReset(&HeadVecEFFilterX, 0); + pt1FilterReset(&HeadVecEFFilterY, 0); + pt1FilterReset(&HeadVecEFFilterZ, 0); + // Initialize 3d speed filter + pt1FilterReset(&GPS3DspeedFilter, 0); } void imuSetMagneticDeclination(float declinationDeg) @@ -194,7 +223,7 @@ void imuTransformVectorEarthToBody(fpVector3_t * v) quaternionRotateVector(v, v, &orientation); } -#if defined(USE_GPS) || defined(HIL) +#if defined(USE_GPS) STATIC_UNIT_TESTED void imuComputeQuaternionFromRPY(int16_t initialRoll, int16_t initialPitch, int16_t initialYaw) { if (initialRoll > 1800) initialRoll -= 3600; @@ -276,13 +305,13 @@ static void imuCheckAndResetOrientationQuaternion(const fpQuaternion_t * quat, c // Previous quaternion valid. Reset to it orientation = *quat; imuErrorEvent.errorCode = 1; - LOG_E(IMU, "AHRS orientation quaternion error. Reset to last known good value"); + LOG_ERROR(IMU, "AHRS orientation quaternion error. Reset to last known good value"); } else { // No valid reference. Best guess from accelerometer imuResetOrientationQuaternion(accBF); imuErrorEvent.errorCode = 2; - LOG_E(IMU, "AHRS orientation quaternion error. Best guess from ACC"); + LOG_ERROR(IMU, "AHRS orientation quaternion error. Best guess from ACC"); } #ifdef USE_BLACKBOX @@ -292,6 +321,11 @@ static void imuCheckAndResetOrientationQuaternion(const fpQuaternion_t * quat, c #endif } +bool isGPSTrustworthy(void) +{ + return sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 6; +} + static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVector3_t * accBF, const fpVector3_t * magBF, bool useCOG, float courseOverGround, float accWScaler, float magWScaler) { STATIC_FASTRAM fpVector3_t vGyroDriftEstimate = { 0 }; @@ -329,8 +363,8 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe #ifdef USE_SIMULATOR if (ARMING_FLAG(SIMULATOR_MODE)) { - imuSetMagneticDeclination(0); - } + imuSetMagneticDeclination(0); + } #endif // Reference mag field vector heading is Magnetic North in EF. We compute that by rotating True North vector by declination and assuming Z-component is zero @@ -352,8 +386,18 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe // (Rxx; Ryx) - measured (estimated) heading vector (EF) // (-cos(COG), sin(COG)) - reference heading vector (EF) - // Compute heading vector in EF from scalar CoG + // Compute heading vector in EF from scalar CoG,x axis of accelerometer is pointing backwards. fpVector3_t vCoG = { .v = { -cos_approx(courseOverGround), sin_approx(courseOverGround), 0.0f } }; +#if defined(USE_WIND_ESTIMATOR) + // remove wind elements in vCoG for better heading estimation + if (isEstimatedWindSpeedValid() && imuConfig()->gps_yaw_windcomp) + { + vectorScale(&vCoG, &vCoG, gpsSol.groundSpeed); + vCoG.x += getEstimatedWindSpeed(X); + vCoG.y -= getEstimatedWindSpeed(Y); + vectorNormalize(&vCoG, &vCoG); + } +#endif // Rotate Forward vector from BF to EF - will yield Heading vector in Earth frame quaternionRotateVectorInv(&vHeadingEF, &vForward, &orientation); @@ -379,7 +423,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe fpVector3_t vTmp; // integral error scaled by Ki - vectorScale(&vTmp, &vErr, imuRuntimeConfig.dcm_ki_mag * dt); + vectorScale(&vTmp, &vErr, imuRuntimeConfig.dcm_ki_mag * magWScaler * dt); vectorAdd(&vGyroDriftEstimate, &vGyroDriftEstimate, &vTmp); } } @@ -409,7 +453,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe fpVector3_t vTmp; // integral error scaled by Ki - vectorScale(&vTmp, &vErr, imuRuntimeConfig.dcm_ki_acc * dt); + vectorScale(&vTmp, &vErr, imuRuntimeConfig.dcm_ki_acc * accWScaler * dt); vectorAdd(&vGyroDriftEstimate, &vGyroDriftEstimate, &vTmp); } } @@ -418,6 +462,11 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe vectorScale(&vErr, &vErr, imuRuntimeConfig.dcm_kp_acc * accWScaler); vectorAdd(&vRotation, &vRotation, &vErr); } + // Anti wind-up + float i_limit = DEGREES_TO_RADIANS(2.0f) * (imuRuntimeConfig.dcm_kp_acc + imuRuntimeConfig.dcm_kp_mag) / 2.0f; + vGyroDriftEstimate.x = constrainf(vGyroDriftEstimate.x, -i_limit, i_limit); + vGyroDriftEstimate.y = constrainf(vGyroDriftEstimate.y, -i_limit, i_limit); + vGyroDriftEstimate.z = constrainf(vGyroDriftEstimate.z, -i_limit, i_limit); // Apply gyro drift correction vectorAdd(&vRotation, &vRotation, &vGyroDriftEstimate); @@ -462,7 +511,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) { #ifdef USE_SIMULATOR - if (ARMING_FLAG(SIMULATOR_MODE) && ((simulatorData.flags & SIMU_USE_SENSORS) == 0)) { + if (ARMING_FLAG(SIMULATOR_MODE) && !SIMULATOR_HAS_OPTION(HITL_USE_IMU)) { imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw); imuComputeRotationMatrix(); } @@ -486,15 +535,17 @@ STATIC_UNIT_TESTED void imuUpdateEulerAngles(void) } } -static float imuCalculateAccelerometerWeight(const float dT) +static float imuCalculateAccelerometerWeightNearness(void) { - float accMagnitudeSq = 0; - for (int axis = 0; axis < 3; axis++) { - accMagnitudeSq += acc.accADCf[axis] * acc.accADCf[axis]; - } - + fpVector3_t accBFNorm; + vectorScale(&accBFNorm, &compansatedGravityBF, 1.0f / GRAVITY_CMSS); + const float accMagnitudeSq = vectorNormSquared(&accBFNorm); const float accWeight_Nearness = bellCurve(fast_fsqrtf(accMagnitudeSq) - 1.0f, MAX_ACC_NEARNESS); + return accWeight_Nearness; +} +static float imuCalculateAccelerometerWeightRateIgnore(const float acc_ignore_slope_multipiler) +{ // Experiment: if rotation rate on a FIXED_WING_LEGACY is higher than a threshold - centrifugal force messes up too much and we // should not use measured accel for AHRS comp // Centrifugal acceleration AccelC = Omega^2 * R = Speed^2 / R @@ -513,24 +564,100 @@ static float imuCalculateAccelerometerWeight(const float dT) // Default - don't apply rate/ignore scaling float accWeight_RateIgnore = 1.0f; - if (ARMING_FLAG(ARMED) && STATE(FIXED_WING_LEGACY) && imuConfig()->acc_ignore_rate) { - const float rotRateMagnitude = calc_length_pythagorean_2D(imuMeasuredRotationBF.y, imuMeasuredRotationBF.z); - const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, IMU_CENTRIFUGAL_LPF, dT); - - if (imuConfig()->acc_ignore_slope) { + if (ARMING_FLAG(ARMED) && imuConfig()->acc_ignore_rate) + { + float rotRateMagnitude = fast_fsqrtf(vectorNormSquared(&imuMeasuredRotationBFFiltered)); + rotRateMagnitude = rotRateMagnitude / (acc_ignore_slope_multipiler + 0.001f); + if (imuConfig()->acc_ignore_slope) + { const float rateSlopeMin = DEGREES_TO_RADIANS((imuConfig()->acc_ignore_rate - imuConfig()->acc_ignore_slope)); const float rateSlopeMax = DEGREES_TO_RADIANS((imuConfig()->acc_ignore_rate + imuConfig()->acc_ignore_slope)); - accWeight_RateIgnore = scaleRangef(constrainf(rotRateMagnitudeFiltered, rateSlopeMin, rateSlopeMax), rateSlopeMin, rateSlopeMax, 1.0f, 0.0f); + accWeight_RateIgnore = scaleRangef(constrainf(rotRateMagnitude, rateSlopeMin, rateSlopeMax), rateSlopeMin, rateSlopeMax, 1.0f, 0.0f); } - else { - if (rotRateMagnitudeFiltered > DEGREES_TO_RADIANS(imuConfig()->acc_ignore_rate)) { + else + { + if (rotRateMagnitude > DEGREES_TO_RADIANS(imuConfig()->acc_ignore_rate)) + { accWeight_RateIgnore = 0.0f; } } } - return accWeight_Nearness * accWeight_RateIgnore; + return accWeight_RateIgnore; +} + +static void imuCalculateFilters(float dT) +{ + //flitering + imuMeasuredRotationBFFiltered.x = pt1FilterApply4(&rotRateFilterX, imuMeasuredRotationBF.x, IMU_ROTATION_LPF, dT); + imuMeasuredRotationBFFiltered.y = pt1FilterApply4(&rotRateFilterY, imuMeasuredRotationBF.y, IMU_ROTATION_LPF, dT); + imuMeasuredRotationBFFiltered.z = pt1FilterApply4(&rotRateFilterZ, imuMeasuredRotationBF.z, IMU_ROTATION_LPF, dT); + HeadVecEFFiltered.x = pt1FilterApply4(&HeadVecEFFilterX, rMat[0][0], IMU_ROTATION_LPF, dT); + HeadVecEFFiltered.y = pt1FilterApply4(&HeadVecEFFilterY, rMat[1][0], IMU_ROTATION_LPF, dT); + HeadVecEFFiltered.z = pt1FilterApply4(&HeadVecEFFilterZ, rMat[2][0], IMU_ROTATION_LPF, dT); + + //anti aliasing + float GPS3Dspeed = calc_length_pythagorean_3D(gpsSol.velNED[X],gpsSol.velNED[Y],gpsSol.velNED[Z]); + GPS3DspeedFiltered = pt1FilterApply4(&GPS3DspeedFilter, GPS3Dspeed, IMU_ROTATION_LPF, dT); +} + +static void imuCalculateGPSacceleration(fpVector3_t *vEstcentrifugalAccelBF, float *acc_ignore_slope_multipiler) +{ + static rtcTime_t lastGPSNewDataTime = 0; + static bool lastGPSHeartbeat; + static fpVector3_t lastGPSvel; + + const fpVector3_t currentGPSvel = {.v = {gpsSol.velNED[X], gpsSol.velNED[Y], gpsSol.velNED[Z]}}; // cm/s gps speed + const rtcTime_t currenttime = millis(); + + // on first gps data acquired, time_delta_ms will be large, vEstcentrifugalAccelBF will be minimal to disable the compensation + rtcTime_t time_delta_ms = currenttime - lastGPSNewDataTime; + if (lastGPSHeartbeat != gpsSol.flags.gpsHeartbeat && time_delta_ms > 0) + { + // on new gps frame, update accEF and estimate centrifugal accleration + fpVector3_t vGPSacc = {.v = {0.0f, 0.0f, 0.0f}}; + vGPSacc.x = -(currentGPSvel.x - lastGPSvel.x) / (MS2S(time_delta_ms)); // the x axis of accerometer is pointing backward + vGPSacc.y = (currentGPSvel.y - lastGPSvel.y) / (MS2S(time_delta_ms)); + vGPSacc.z = (currentGPSvel.z - lastGPSvel.z) / (MS2S(time_delta_ms)); + // Calculate estimated centrifugal accleration vector in body frame + quaternionRotateVector(vEstcentrifugalAccelBF, &vGPSacc, &orientation); // EF -> BF + lastGPSNewDataTime = currenttime; + lastGPSvel = currentGPSvel; + } + lastGPSHeartbeat = gpsSol.flags.gpsHeartbeat; + *acc_ignore_slope_multipiler = 4; +} + +static void imuCalculateTurnRateacceleration(fpVector3_t *vEstcentrifugalAccelBF, float dT, float *acc_ignore_slope_multipiler) +{ + //fixed wing only + static float lastspeed = -1.0f; + float currentspeed; + if (isGPSTrustworthy()){ + //first speed choice is gps + currentspeed = GPS3DspeedFiltered; + *acc_ignore_slope_multipiler = 4.0f; + } +#ifdef USE_PITOT + if (sensors(SENSOR_PITOT) && pitotIsHealthy() && currentspeed < 0) + { + // second choice is pitot + currentspeed = getAirspeedEstimate(); + *acc_ignore_slope_multipiler = 2.0f; + } +#endif + if (currentspeed < 0) + { + //third choice is fixedWingReferenceAirspeed + currentspeed = pidProfile()->fixedWingReferenceAirspeed; + *acc_ignore_slope_multipiler = 1.0f; + } + float speed_change = lastspeed > 0 ? currentspeed - lastspeed : 0; + vEstcentrifugalAccelBF->x = -speed_change/dT; + vEstcentrifugalAccelBF->y = -currentspeed*imuMeasuredRotationBFFiltered.z; + vEstcentrifugalAccelBF->z = currentspeed*imuMeasuredRotationBFFiltered.y; + lastspeed = currentspeed; } static void imuCalculateEstimatedAttitude(float dT) @@ -544,7 +671,6 @@ static void imuCalculateEstimatedAttitude(float dT) float courseOverGround = 0; bool useMag = false; bool useCOG = false; - #if defined(USE_GPS) if (STATE(FIXED_WING_LEGACY)) { bool canUseCOG = isGPSHeadingValid(); @@ -577,60 +703,78 @@ static void imuCalculateEstimatedAttitude(float dT) useMag = true; } } + + imuCalculateFilters(dT); + // centrifugal force compensation + static fpVector3_t vEstcentrifugalAccelBF_velned; + static fpVector3_t vEstcentrifugalAccelBF_turnrate; + float acc_ignore_slope_multipiler = 1.0f; // when using gps centrifugal_force_compensation, AccelerometerWeightRateIgnore slope will be multiplied by this value + if (isGPSTrustworthy()) + { + imuCalculateGPSacceleration(&vEstcentrifugalAccelBF_velned, &acc_ignore_slope_multipiler); + } + if (STATE(AIRPLANE)) + { + imuCalculateTurnRateacceleration(&vEstcentrifugalAccelBF_turnrate, dT, &acc_ignore_slope_multipiler); + } + if (imuConfig()->inertia_comp_method == COMPMETHOD_ADAPTIVE && isGPSTrustworthy() && STATE(AIRPLANE)) + { + fpVector3_t compansatedGravityBF_velned; + vectorAdd(&compansatedGravityBF_velned, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned); + float velned_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_velned)) - GRAVITY_CMSS); + + fpVector3_t compansatedGravityBF_turnrate; + vectorAdd(&compansatedGravityBF_turnrate, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate); + float turnrate_magnitude = fabsf(fast_fsqrtf(vectorNormSquared(&compansatedGravityBF_turnrate)) - GRAVITY_CMSS); + if (velned_magnitude > turnrate_magnitude) + { + compansatedGravityBF = compansatedGravityBF_turnrate; + } + else + { + compansatedGravityBF = compansatedGravityBF_velned; + } + } + else if (imuConfig()->inertia_comp_method == COMPMETHOD_VELNED && isGPSTrustworthy()) + { + vectorAdd(&compansatedGravityBF, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_velned); + } + else if (STATE(AIRPLANE)) + { + vectorAdd(&compansatedGravityBF, &imuMeasuredAccelBF, &vEstcentrifugalAccelBF_turnrate); + } + else + { + compansatedGravityBF = imuMeasuredAccelBF; + } #else // In absence of GPS MAG is the only option if (canUseMAG) { useMag = true; } + compansatedGravityBF = imuMeasuredAccelBF #endif - - fpVector3_t measuredMagBF = { .v = { mag.magADC[X], mag.magADC[Y], mag.magADC[Z] } }; - - const float magWeight = imuGetPGainScaleFactor() * 1.0f; - const float accWeight = imuGetPGainScaleFactor() * imuCalculateAccelerometerWeight(dT); + float accWeight = imuGetPGainScaleFactor() * imuCalculateAccelerometerWeightNearness(); + accWeight = accWeight * imuCalculateAccelerometerWeightRateIgnore(acc_ignore_slope_multipiler); const bool useAcc = (accWeight > 0.001f); + const float magWeight = imuGetPGainScaleFactor() * 1.0f; + fpVector3_t measuredMagBF = {.v = {mag.magADC[X], mag.magADC[Y], mag.magADC[Z]}}; imuMahonyAHRSupdate(dT, &imuMeasuredRotationBF, - useAcc ? &imuMeasuredAccelBF : NULL, + useAcc ? &compansatedGravityBF : NULL, useMag ? &measuredMagBF : NULL, useCOG, courseOverGround, accWeight, magWeight); - imuUpdateEulerAngles(); } -#ifdef HIL -void imuHILUpdate(void) -{ - /* Set attitude */ - attitude.values.roll = hilToFC.rollAngle; - attitude.values.pitch = hilToFC.pitchAngle; - attitude.values.yaw = hilToFC.yawAngle; - - /* Compute rotation quaternion for future use */ - imuComputeQuaternionFromRPY(attitude.values.roll, attitude.values.pitch, attitude.values.yaw); - - /* Fake accADC readings */ - accADCf[X] = hilToFC.bodyAccel[X] / GRAVITY_CMSS; - accADCf[Y] = hilToFC.bodyAccel[Y] / GRAVITY_CMSS; - accADCf[Z] = hilToFC.bodyAccel[Z] / GRAVITY_CMSS; -} -#endif - void imuUpdateAccelerometer(void) { -#ifdef HIL - if (sensors(SENSOR_ACC) && !hilActive) { - accUpdate(); - isAccelUpdatedAtLeastOnce = true; - } -#else if (sensors(SENSOR_ACC)) { accUpdate(); isAccelUpdatedAtLeastOnce = true; } -#endif } void imuCheckVibrationLevels(void) @@ -655,23 +799,10 @@ void imuUpdateAttitude(timeUs_t currentTimeUs) previousIMUUpdateTimeUs = currentTimeUs; if (sensors(SENSOR_ACC) && isAccelUpdatedAtLeastOnce) { -#ifdef HIL - if (!hilActive) { - gyroGetMeasuredRotationRate(&imuMeasuredRotationBF); // Calculate gyro rate in body frame in rad/s - accGetMeasuredAcceleration(&imuMeasuredAccelBF); // Calculate accel in body frame in cm/s/s - imuCheckVibrationLevels(); - imuCalculateEstimatedAttitude(dT); // Update attitude estimate - } - else { - imuHILUpdate(); - imuUpdateMeasuredAcceleration(); - } -#else gyroGetMeasuredRotationRate(&imuMeasuredRotationBF); // Calculate gyro rate in body frame in rad/s accGetMeasuredAcceleration(&imuMeasuredAccelBF); // Calculate accel in body frame in cm/s/s imuCheckVibrationLevels(); imuCalculateEstimatedAttitude(dT); // Update attitude estimate -#endif } else { acc.accADCf[X] = 0.0f; acc.accADCf[Y] = 0.0f; @@ -681,7 +812,7 @@ void imuUpdateAttitude(timeUs_t currentTimeUs) bool isImuReady(void) { - return sensors(SENSOR_ACC) && gyroIsCalibrationComplete(); + return sensors(SENSOR_ACC) && STATE(ACCELEROMETER_CALIBRATED) && gyroIsCalibrationComplete(); } bool isImuHeadingValid(void) diff --git a/src/main/flight/imu.h b/src/main/flight/imu.h index 2d9c6ec763..f438cc079f 100644 --- a/src/main/flight/imu.h +++ b/src/main/flight/imu.h @@ -26,6 +26,9 @@ extern fpVector3_t imuMeasuredAccelBF; // cm/s/s extern fpVector3_t imuMeasuredRotationBF; // rad/s +extern fpVector3_t imuMeasuredRotationBFFiltered; // rad/s +extern fpVector3_t compansatedGravityBF; // cm/s/s +extern fpVector3_t HeadVecEFFiltered; typedef union { int16_t raw[XYZ_AXIS_COUNT]; @@ -49,6 +52,8 @@ typedef struct imuConfig_s { uint8_t small_angle; uint8_t acc_ignore_rate; uint8_t acc_ignore_slope; + uint8_t gps_yaw_windcomp; + uint8_t inertia_comp_method; } imuConfig_t; PG_DECLARE(imuConfig_t, imuConfig); @@ -61,6 +66,13 @@ typedef struct imuRuntimeConfig_s { uint8_t small_angle; } imuRuntimeConfig_t; +typedef enum +{ + COMPMETHOD_VELNED = 0, + COMPMETHOD_TURNRATE, + COMPMETHOD_ADAPTIVE +} imu_inertia_comp_method_e; + void imuConfigure(void); void imuSetMagneticDeclination(float declinationDeg); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index ee4cf4ef54..c06fc5bb46 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -626,11 +626,8 @@ motorStatus_e getMotorStatus(void) } const bool fixedWingOrAirmodeNotActive = STATE(FIXED_WING_LEGACY) || !STATE(AIRMODE_ACTIVE); - const bool throttleStickLow = - (calculateThrottleStatus(feature(FEATURE_REVERSIBLE_MOTORS) ? THROTTLE_STATUS_TYPE_COMMAND : THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW); - - if (throttleStickLow && fixedWingOrAirmodeNotActive) { + if (throttleStickIsLow() && fixedWingOrAirmodeNotActive) { if ((navConfig()->general.flags.nav_overrides_motor_stop == NOMS_OFF_ALWAYS) && failsafeIsActive()) { // If we are in failsafe and user was holding stick low before it was triggered and nav_overrides_motor_stop is set to OFF_ALWAYS // and either on a plane or on a quad with inactive airmode - stop motor @@ -652,7 +649,6 @@ motorStatus_e getMotorStatus(void) return MOTOR_STOPPED_USER; } } - } return MOTOR_RUNNING; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index f497ad424f..dd2a480412 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -46,7 +46,6 @@ FILE_COMPILE_FOR_SPEED #include "flight/imu.h" #include "flight/mixer.h" #include "flight/rpm_filter.h" -#include "flight/secondary_imu.h" #include "flight/kalman.h" #include "flight/smith_predictor.h" @@ -172,7 +171,7 @@ static EXTENDED_FASTRAM bool levelingEnabled = false; static EXTENDED_FASTRAM float fixedWingLevelTrim; static EXTENDED_FASTRAM pidController_t fixedWingLevelTrimController; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 4); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 5); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -278,7 +277,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .fixedWingItermLimitOnStickPosition = SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT, .fixedWingYawItermBankFreeze = SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT, - .loiter_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT, .navVelXyDTermLpfHz = SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT, .navVelXyDtermAttenuation = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT, .navVelXyDtermAttenuationStart = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT, @@ -328,11 +326,11 @@ bool pidInitFilters(void) } for (int i = 0; i < XYZ_AXIS_COUNT; i++) { - pt1FilterInit(&windupLpf[i], pidProfile()->iterm_relax_cutoff, refreshRate * 1e-6f); + pt1FilterInit(&windupLpf[i], pidProfile()->iterm_relax_cutoff, US2S(refreshRate)); } #ifdef USE_ANTIGRAVITY - pt1FilterInit(&antigravityThrottleLpf, pidProfile()->antigravityCutoff, TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f); + pt1FilterInit(&antigravityThrottleLpf, pidProfile()->antigravityCutoff, US2S(TASK_PERIOD_HZ(TASK_AUX_RATE_HZ))); #endif #ifdef USE_D_BOOST @@ -343,7 +341,7 @@ bool pidInitFilters(void) if (pidProfile()->controlDerivativeLpfHz) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - pt3FilterInit(&pidState[axis].rateTargetFilter, pt3FilterGain(pidProfile()->controlDerivativeLpfHz, refreshRate * 1e-6f)); + pt3FilterInit(&pidState[axis].rateTargetFilter, pt3FilterGain(pidProfile()->controlDerivativeLpfHz, US2S(refreshRate))); } } @@ -379,7 +377,7 @@ bool pidInitFilters(void) void pidResetTPAFilter(void) { if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) { - pt1FilterInitRC(&fixedWingTpaFilter, MS2S(currentControlRateProfile->throttle.fixedWingTauMs), TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f); + pt1FilterInitRC(&fixedWingTpaFilter, MS2S(currentControlRateProfile->throttle.fixedWingTauMs), US2S(TASK_PERIOD_HZ(TASK_AUX_RATE_HZ))); pt1FilterReset(&fixedWingTpaFilter, getThrottleIdleValue()); } } @@ -597,7 +595,7 @@ static float computePidLevelTarget(flight_dynamics_index_t axis) { // Automatically pitch down if the throttle is manually controlled and reduced bellow cruise throttle if ((axis == FD_PITCH) && STATE(AIRPLANE) && FLIGHT_MODE(ANGLE_MODE) && !navigationIsControllingThrottle()) { - angleTarget += scaleRange(MAX(0, currentBatteryProfile->nav.fw.cruise_throttle - rcCommand[THROTTLE]), 0, currentBatteryProfile->nav.fw.cruise_throttle - PWM_RANGE_MIN, 0, currentBatteryProfile->fwMinThrottleDownPitchAngle); + angleTarget += scaleRange(MAX(0, currentBatteryProfile->nav.fw.cruise_throttle - rcCommand[THROTTLE]), 0, currentBatteryProfile->nav.fw.cruise_throttle - PWM_RANGE_MIN, 0, navConfig()->fw.minThrottleDownPitchAngle); } //PITCH trim applied by a AutoLevel flight mode and manual pitch trimming @@ -624,23 +622,7 @@ static float computePidLevelTarget(flight_dynamics_index_t axis) { static void pidLevel(const float angleTarget, pidState_t *pidState, flight_dynamics_index_t axis, float horizonRateMagnitude, float dT) { - -#ifdef USE_SECONDARY_IMU - float actual; - if (secondaryImuState.active && secondaryImuConfig()->useForStabilized) { - if (axis == FD_ROLL) { - actual = secondaryImuState.eulerAngles.values.roll; - } else { - actual = secondaryImuState.eulerAngles.values.pitch; - } - } else { - actual = attitude.raw[axis]; - } - - float angleErrorDeg = DECIDEGREES_TO_DEGREES(angleTarget - actual); -#else float angleErrorDeg = DECIDEGREES_TO_DEGREES(angleTarget - attitude.raw[axis]); -#endif // Soaring mode deadband inactive if pitch/roll stick not centered to allow RC stick adjustment if (FLIGHT_MODE(SOARING_MODE) && axis == FD_PITCH && calculateRollPitchCenterStatus() == CENTERED) { @@ -948,7 +930,7 @@ float pidHeadingHold(float dT) - output - that gives about 2 seconds to correct any error, no matter how big. Of course, usually more because of inertia. That was making him quite "soft" for small changes and rapid for big ones that started to appear - when iNav introduced real RTH and WAYPOINT that might require rapid heading changes. + when INAV introduced real RTH and WAYPOINT that might require rapid heading changes. New approach uses modified principle: - manual yaw rate is not used. MAG_HOLD is decoupled from manual input settings diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8520ff5d0d..8a95dc5b32 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -132,8 +132,7 @@ typedef struct pidProfile_s { float fixedWingCoordinatedPitchGain; // This is the gain of the pitch rate to keep the pitch angle constant during coordinated turns. float fixedWingItermLimitOnStickPosition; //Do not allow Iterm to grow when stick position is above this point uint16_t fixedWingYawItermBankFreeze; // Freeze yaw Iterm when bank angle is more than this many degrees - - uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise) + float navVelXyDTermLpfHz; uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity diff --git a/src/main/flight/power_limits.c b/src/main/flight/power_limits.c index 549ead0019..9865f0b485 100644 --- a/src/main/flight/power_limits.c +++ b/src/main/flight/power_limits.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/flight/power_limits.h b/src/main/flight/power_limits.h index 2f4385252c..d5b877273b 100644 --- a/src/main/flight/power_limits.h +++ b/src/main/flight/power_limits.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav + * This file is part of INAV * - * iNav free software. You can redistribute + * INAV free software. You can redistribute * this software and/or modify this software 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 distributed in the hope that it + * INAV 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. diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c index f1f0819a21..ffca6c8ea6 100644 --- a/src/main/flight/rpm_filter.c +++ b/src/main/flight/rpm_filter.c @@ -161,7 +161,7 @@ void rpmFiltersInit(void) { for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { - pt1FilterInit(&motorFrequencyFilter[i], RPM_FILTER_RPM_LPF_HZ, RPM_FILTER_UPDATE_RATE_US * 1e-6f); + pt1FilterInit(&motorFrequencyFilter[i], RPM_FILTER_RPM_LPF_HZ, US2S(RPM_FILTER_UPDATE_RATE_US)); } rpmGyroUpdateFn = (rpmFilterUpdateFnPtr)nullRpmFilterUpdate; diff --git a/src/main/flight/secondary_imu.c b/src/main/flight/secondary_imu.c deleted file mode 100644 index 44eda2d7d2..0000000000 --- a/src/main/flight/secondary_imu.c +++ /dev/null @@ -1,241 +0,0 @@ -/* - * This file is part of INAV. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute 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. - * - * This file 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 this program. If not, see http://www.gnu.org/licenses/. - */ - -#include "platform.h" -#ifdef USE_SECONDARY_IMU - -#include "stdint.h" - -#include "build/debug.h" - -#include "common/utils.h" -#include "common/axis.h" - -#include "build/debug.h" -#include "scheduler/scheduler.h" -#include "config/parameter_group_ids.h" - -#include "drivers/sensor.h" -#include "drivers/accgyro/accgyro_bno055_serial.h" - -#include "fc/settings.h" - -#include "flight/secondary_imu.h" - -#include "sensors/boardalignment.h" -#include "sensors/compass.h" - -PG_REGISTER_WITH_RESET_FN(secondaryImuConfig_t, secondaryImuConfig, PG_SECONDARY_IMU, 2); - -EXTENDED_FASTRAM secondaryImuState_t secondaryImuState; - -void pgResetFn_secondaryImuConfig(secondaryImuConfig_t *instance) -{ - instance->hardwareType = SECONDARY_IMU_NONE, - instance->rollDeciDegrees = 0; - instance->pitchDeciDegrees = 0; - instance->yawDeciDegrees = 0; - instance->useForOsdHeading = 0; - instance->useForOsdAHI = 0; - instance->useForStabilized = 0; - - for (uint8_t i = 0; i < 3; i++) - { - instance->calibrationOffsetGyro[i] = 0; - instance->calibrationOffsetMag[i] = 0; - instance->calibrationOffsetAcc[i] = 0; - } - instance->calibrationRadiusAcc = 0; - instance->calibrationRadiusMag = 0; -} - -void secondaryImuInit(void) -{ - secondaryImuState.active = false; - // Create magnetic declination matrix -#ifdef USE_MAG - const int deg = compassConfig()->mag_declination / 100; - const int min = compassConfig()->mag_declination % 100; -#else - const int deg = 0; - const int min = 0; -#endif - - secondaryImuSetMagneticDeclination(deg + min / 60.0f); - - bno055CalibrationData_t calibrationData; - calibrationData.offset[ACC][X] = secondaryImuConfig()->calibrationOffsetAcc[X]; - calibrationData.offset[ACC][Y] = secondaryImuConfig()->calibrationOffsetAcc[Y]; - calibrationData.offset[ACC][Z] = secondaryImuConfig()->calibrationOffsetAcc[Z]; - calibrationData.offset[MAG][X] = secondaryImuConfig()->calibrationOffsetMag[X]; - calibrationData.offset[MAG][Y] = secondaryImuConfig()->calibrationOffsetMag[Y]; - calibrationData.offset[MAG][Z] = secondaryImuConfig()->calibrationOffsetMag[Z]; - calibrationData.offset[GYRO][X] = secondaryImuConfig()->calibrationOffsetGyro[X]; - calibrationData.offset[GYRO][Y] = secondaryImuConfig()->calibrationOffsetGyro[Y]; - calibrationData.offset[GYRO][Z] = secondaryImuConfig()->calibrationOffsetGyro[Z]; - calibrationData.radius[ACC] = secondaryImuConfig()->calibrationRadiusAcc; - calibrationData.radius[MAG] = secondaryImuConfig()->calibrationRadiusMag; - - requestedSensors[SENSOR_INDEX_IMU2] = secondaryImuConfig()->hardwareType; - - if (secondaryImuConfig()->hardwareType == SECONDARY_IMU_BNO055_SERIAL) { - secondaryImuState.active = bno055SerialInit(calibrationData, (secondaryImuConfig()->calibrationRadiusAcc && secondaryImuConfig()->calibrationRadiusMag)); - - if (secondaryImuState.active) { - detectedSensors[SENSOR_INDEX_IMU2] = SECONDARY_IMU_BNO055_SERIAL; - rescheduleTask(TASK_SECONDARY_IMU, TASK_PERIOD_HZ(50)); - } - } - - if (!secondaryImuState.active) { - detectedSensors[SENSOR_INDEX_IMU2] = SECONDARY_IMU_NONE; - } - -} - -void secondaryImuProcess(void) { - //Apply mag declination - secondaryImuState.eulerAngles.raw[2] += secondaryImuState.magDeclination; - - //TODO this way of rotating a vector makes no sense, something simpler have to be developed - const fpVector3_t v = { - .x = secondaryImuState.eulerAngles.raw[0], - .y = secondaryImuState.eulerAngles.raw[1], - .z = secondaryImuState.eulerAngles.raw[2], - }; - - fpVector3_t rotated; - - fp_angles_t imuAngles = { - .angles.roll = DECIDEGREES_TO_RADIANS(secondaryImuConfig()->rollDeciDegrees), - .angles.pitch = DECIDEGREES_TO_RADIANS(secondaryImuConfig()->pitchDeciDegrees), - .angles.yaw = DECIDEGREES_TO_RADIANS(secondaryImuConfig()->yawDeciDegrees), - }; - fpMat3_t rotationMatrix; - rotationMatrixFromAngles(&rotationMatrix, &imuAngles); - rotationMatrixRotateVector(&rotated, &v, &rotationMatrix); - rotated.z = ((int32_t)(rotated.z + secondaryImuConfig()->yawDeciDegrees)) % 3600; - - secondaryImuState.eulerAngles.values.roll = rotated.x; - secondaryImuState.eulerAngles.values.pitch = rotated.y; - secondaryImuState.eulerAngles.values.yaw = rotated.z; - - DEBUG_SET(DEBUG_IMU2, 0, secondaryImuState.eulerAngles.values.roll); - DEBUG_SET(DEBUG_IMU2, 1, secondaryImuState.eulerAngles.values.pitch); - DEBUG_SET(DEBUG_IMU2, 2, secondaryImuState.eulerAngles.values.yaw); - - DEBUG_SET(DEBUG_IMU2, 3, secondaryImuState.calibrationStatus.mag); - DEBUG_SET(DEBUG_IMU2, 4, secondaryImuState.calibrationStatus.gyr); - DEBUG_SET(DEBUG_IMU2, 5, secondaryImuState.calibrationStatus.acc); - DEBUG_SET(DEBUG_IMU2, 6, secondaryImuState.magDeclination); -} - -void taskSecondaryImu(timeUs_t currentTimeUs) -{ - static uint8_t tick = 0; - tick++; - - if (!secondaryImuState.active) - { - return; - } - /* - * Secondary IMU works in decidegrees - */ - UNUSED(currentTimeUs); - - if (secondaryImuConfig()->hardwareType == SECONDARY_IMU_BNO055_SERIAL) { - /* - * Every 2 seconds fetch current calibration state - */ - if (tick == 100) - { - bno055SerialGetCalibStat(); - tick = 0; - } else { - bno055SerialFetchEulerAngles(); - } - } -} - -void secondaryImuFetchCalibration(void) { - bno055CalibrationData_t calibrationData; - - if (secondaryImuConfig()->hardwareType == SECONDARY_IMU_BNO055_SERIAL) { - calibrationData = bno055SerialGetCalibrationData(); - } else { - return; - } - - secondaryImuConfigMutable()->calibrationOffsetAcc[X] = calibrationData.offset[ACC][X]; - secondaryImuConfigMutable()->calibrationOffsetAcc[Y] = calibrationData.offset[ACC][Y]; - secondaryImuConfigMutable()->calibrationOffsetAcc[Z] = calibrationData.offset[ACC][Z]; - - secondaryImuConfigMutable()->calibrationOffsetMag[X] = calibrationData.offset[MAG][X]; - secondaryImuConfigMutable()->calibrationOffsetMag[Y] = calibrationData.offset[MAG][Y]; - secondaryImuConfigMutable()->calibrationOffsetMag[Z] = calibrationData.offset[MAG][Z]; - - secondaryImuConfigMutable()->calibrationOffsetGyro[X] = calibrationData.offset[GYRO][X]; - secondaryImuConfigMutable()->calibrationOffsetGyro[Y] = calibrationData.offset[GYRO][Y]; - secondaryImuConfigMutable()->calibrationOffsetGyro[Z] = calibrationData.offset[GYRO][Z]; - - secondaryImuConfigMutable()->calibrationRadiusAcc = calibrationData.radius[ACC]; - secondaryImuConfigMutable()->calibrationRadiusMag = calibrationData.radius[MAG]; -} - -void secondaryImuSetMagneticDeclination(float declination) { //Incoming units are degrees - secondaryImuState.magDeclination = declination * 10.0f; //Internally declination is stored in decidegrees -} - -bool isSecondaryImuHealthy(void) { - return secondaryImuState.active; -} - -hardwareSensorStatus_e getHwSecondaryImuStatus(void) -{ -#ifdef USE_SECONDARY_IMU - if (detectedSensors[SENSOR_INDEX_IMU2] != SECONDARY_IMU_NONE) { - if (isSecondaryImuHealthy()) { - return HW_SENSOR_OK; - } - else { - return HW_SENSOR_UNHEALTHY; - } - } - else { - if (requestedSensors[SENSOR_INDEX_IMU2] != SECONDARY_IMU_NONE) { - // Selected but not detected - return HW_SENSOR_UNAVAILABLE; - } - else { - // Not selected and not detected - return HW_SENSOR_NONE; - } - } -#else - return HW_SENSOR_NONE; -#endif -} - -#endif diff --git a/src/main/flight/secondary_imu.h b/src/main/flight/secondary_imu.h deleted file mode 100644 index 64fb3c7656..0000000000 --- a/src/main/flight/secondary_imu.h +++ /dev/null @@ -1,70 +0,0 @@ -/* - * This file is part of INAV. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute 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. - * - * This file 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 this program. If not, see http://www.gnu.org/licenses/. - */ - -#pragma once - -#include "config/parameter_group.h" -#include "common/time.h" -#include "sensors/sensors.h" -#include "drivers/accgyro/accgyro_bno055_serial.h" -#include "sensors/diagnostics.h" - -typedef enum { - SECONDARY_IMU_NONE = 0, - SECONDARY_IMU_BNO055_SERIAL = 1, -} secondaryImuType_e; - -typedef struct secondaryImuConfig_s { - uint8_t hardwareType; - int16_t rollDeciDegrees; - int16_t pitchDeciDegrees; - int16_t yawDeciDegrees; - uint8_t useForOsdHeading; - uint8_t useForOsdAHI; - uint8_t useForStabilized; - int16_t calibrationOffsetGyro[3]; - int16_t calibrationOffsetMag[3]; - int16_t calibrationOffsetAcc[3]; - int16_t calibrationRadiusAcc; - int16_t calibrationRadiusMag; -} secondaryImuConfig_t; - -typedef struct secondaryImuState_s { - flightDynamicsTrims_t eulerAngles; - bno055CalibStat_t calibrationStatus; - uint8_t active; - float magDeclination; -} secondaryImuState_t; - -extern secondaryImuState_t secondaryImuState; - -PG_DECLARE(secondaryImuConfig_t, secondaryImuConfig); - -void secondaryImuProcess(void); -void secondaryImuInit(void); -void taskSecondaryImu(timeUs_t currentTimeUs); -void secondaryImuFetchCalibration(void); -void secondaryImuSetMagneticDeclination(float declination); -bool isSecondaryImuHealthy(void); -hardwareSensorStatus_e getHwSecondaryImuStatus(void); \ No newline at end of file diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 6295b04d3e..f3a1b5c6d9 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -321,10 +321,10 @@ void servoMixer(float dT) #undef GET_RX_CHANNEL_INPUT #ifdef USE_SIMULATOR - simulatorData.INPUT_STABILIZED_ROLL = input[INPUT_STABILIZED_ROLL]; - simulatorData.INPUT_STABILIZED_PITCH = input[INPUT_STABILIZED_PITCH]; - simulatorData.INPUT_STABILIZED_YAW = input[INPUT_STABILIZED_YAW]; - simulatorData.INPUT_STABILIZED_THROTTLE = input[INPUT_STABILIZED_THROTTLE]; + simulatorData.input[INPUT_STABILIZED_ROLL] = input[INPUT_STABILIZED_ROLL]; + simulatorData.input[INPUT_STABILIZED_PITCH] = input[INPUT_STABILIZED_PITCH]; + simulatorData.input[INPUT_STABILIZED_YAW] = input[INPUT_STABILIZED_YAW]; + simulatorData.input[INPUT_STABILIZED_THROTTLE] = input[INPUT_STABILIZED_THROTTLE]; #endif for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { diff --git a/src/main/flight/smith_predictor.c b/src/main/flight/smith_predictor.c index 271c088add..c3fc55f077 100644 --- a/src/main/flight/smith_predictor.c +++ b/src/main/flight/smith_predictor.c @@ -61,7 +61,7 @@ void smithPredictorInit(smithPredictor_t *predictor, float delay, float strength predictor->samples = (delay * 1000) / looptime; predictor->idx = 0; predictor->smithPredictorStrength = strength; - pt1FilterInit(&predictor->smithPredictorFilter, filterLpfHz, looptime * 1e-6f); + pt1FilterInit(&predictor->smithPredictorFilter, filterLpfHz, US2S(looptime)); } else { predictor->enabled = false; } diff --git a/src/main/flight/wind_estimator.c b/src/main/flight/wind_estimator.c index c58aeb99a9..cbe014a531 100644 --- a/src/main/flight/wind_estimator.c +++ b/src/main/flight/wind_estimator.c @@ -40,6 +40,8 @@ #include "io/gps.h" + +#define WINDESTIMATOR_TIMEOUT 60 //60s // Based on WindEstimation.pdf paper static bool hasValidWindEstimate = false; @@ -49,8 +51,6 @@ static float lastFuselageDirection[XYZ_AXIS_COUNT]; bool isEstimatedWindSpeedValid(void) { - // TODO: Add a timeout. Estimated wind should expire if - // if we can't update it for an extended time. return hasValidWindEstimate; } @@ -78,6 +78,12 @@ float getEstimatedHorizontalWindSpeed(uint16_t *angle) void updateWindEstimator(timeUs_t currentTimeUs) { static timeUs_t lastUpdateUs = 0; + static timeUs_t lastValidWindEstimate = 0; + + if (US2S(currentTimeUs - lastValidWindEstimate) > WINDESTIMATOR_TIMEOUT) + { + hasValidWindEstimate = false; + } if (!STATE(FIXED_WING_LEGACY) || !isGPSHeadingValid() || @@ -102,9 +108,9 @@ void updateWindEstimator(timeUs_t currentTimeUs) groundVelocity[Z] = gpsSol.velNED[Z]; // Fuselage direction in earth frame - fuselageDirection[X] = rMat[0][0]; - fuselageDirection[Y] = -rMat[1][0]; - fuselageDirection[Z] = -rMat[2][0]; + fuselageDirection[X] = HeadVecEFFiltered.x; + fuselageDirection[Y] = -HeadVecEFFiltered.y; + fuselageDirection[Z] = -HeadVecEFFiltered.z; timeDelta_t timeDelta = cmpTimeUs(currentTimeUs, lastUpdateUs); // scrap our data and start over if we're taking too long to get a direction change @@ -160,14 +166,15 @@ void updateWindEstimator(timeUs_t currentTimeUs) float prevWindLength = calc_length_pythagorean_3D(estimatedWind[X], estimatedWind[Y], estimatedWind[Z]); float windLength = calc_length_pythagorean_3D(wind[X], wind[Y], wind[Z]); - if (windLength < prevWindLength + 2000) { + if (windLength < prevWindLength + 4000) { // TODO: Better filtering - estimatedWind[X] = estimatedWind[X] * 0.95f + wind[X] * 0.05f; - estimatedWind[Y] = estimatedWind[Y] * 0.95f + wind[Y] * 0.05f; - estimatedWind[Z] = estimatedWind[Z] * 0.95f + wind[Z] * 0.05f; + estimatedWind[X] = estimatedWind[X] * 0.98f + wind[X] * 0.02f; + estimatedWind[Y] = estimatedWind[Y] * 0.98f + wind[Y] * 0.02f; + estimatedWind[Z] = estimatedWind[Z] * 0.98f + wind[Z] * 0.02f; } lastUpdateUs = currentTimeUs; + lastValidWindEstimate = currentTimeUs; hasValidWindEstimate = true; } } diff --git a/src/main/io/asyncfatfs/asyncfatfs.c b/src/main/io/asyncfatfs/asyncfatfs.c index 98b8fdd1b9..82ed7d6583 100644 --- a/src/main/io/asyncfatfs/asyncfatfs.c +++ b/src/main/io/asyncfatfs/asyncfatfs.c @@ -3167,7 +3167,7 @@ uint32_t afatfs_fwriteSync(afatfsFilePtr_t file, uint8_t *data, uint32_t length) while (true) { uint32_t leftToWrite = length - written; uint32_t justWritten = afatfs_fwrite(file, data + written, leftToWrite); - /*if (justWritten != leftToWrite) LOG_E(SYSTEM, "%ld -> %ld", length, written);*/ + /*if (justWritten != leftToWrite) LOG_ERROR(SYSTEM, "%ld -> %ld", length, written);*/ written += justWritten; if (written < length) { diff --git a/src/main/io/displayport_msp.c b/src/main/io/displayport_msp.c index 27fc439e0a..989588c3d9 100644 --- a/src/main/io/displayport_msp.c +++ b/src/main/io/displayport_msp.c @@ -38,6 +38,8 @@ #include "msp/msp_protocol.h" #include "msp/msp_serial.h" +#define MSP_OSD_MAX_STRING_LENGTH 30 + static displayPort_t mspDisplayPort; extern uint8_t cliMode; @@ -70,21 +72,21 @@ static int grab(displayPort_t *displayPort) static int release(displayPort_t *displayPort) { - uint8_t subcmd[] = { 1 }; + uint8_t subcmd[] = { MSP_DP_RELEASE }; return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); } static int clearScreen(displayPort_t *displayPort) { - uint8_t subcmd[] = { 2 }; + uint8_t subcmd[] = { MSP_DP_CLEAR_SCREEN }; return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); } static int drawScreen(displayPort_t *displayPort) { - uint8_t subcmd[] = { 4 }; + uint8_t subcmd[] = { MSP_DP_DRAW_SCREEN }; return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); } @@ -96,7 +98,7 @@ static int screenSize(const displayPort_t *displayPort) static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *string, textAttributes_t attr) { UNUSED(attr); -#define MSP_OSD_MAX_STRING_LENGTH 30 // FIXME move this + uint8_t buf[MSP_OSD_MAX_STRING_LENGTH + 4]; int len = strlen(string); @@ -104,7 +106,7 @@ static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, con len = MSP_OSD_MAX_STRING_LENGTH; } - buf[0] = 3; + buf[0] = MSP_DP_WRITE_STRING; buf[1] = row; buf[2] = col; buf[3] = 0; diff --git a/src/main/io/displayport_msp.h b/src/main/io/displayport_msp.h index 57ff6ae09f..683860fa3a 100644 --- a/src/main/io/displayport_msp.h +++ b/src/main/io/displayport_msp.h @@ -20,5 +20,11 @@ #include "config/parameter_group.h" #include "drivers/display.h" +// MSP Display Port commands +#define MSP_DP_RELEASE 1 +#define MSP_DP_CLEAR_SCREEN 2 +#define MSP_DP_WRITE_STRING 3 +#define MSP_DP_DRAW_SCREEN 4 + struct displayPort_s; struct displayPort_s *displayPortMspInit(void); diff --git a/src/main/io/displayport_hdzero_osd.c b/src/main/io/displayport_msp_osd.c similarity index 55% rename from src/main/io/displayport_hdzero_osd.c rename to src/main/io/displayport_msp_osd.c index ee2462e5fc..6267d230ff 100644 --- a/src/main/io/displayport_hdzero_osd.c +++ b/src/main/io/displayport_msp_osd.c @@ -30,23 +30,27 @@ FILE_COMPILE_FOR_SPEED -//#define HDZERO_STATS - -#if defined(USE_OSD) && defined(USE_HDZERO_OSD) +#if defined(USE_OSD) && defined(USE_MSP_OSD) #include "common/utils.h" #include "common/printf.h" #include "common/time.h" #include "common/bitarray.h" +#include "cms/cms.h" + #include "drivers/display.h" #include "drivers/display_font_metadata.h" #include "drivers/osd_symbols.h" +#include "fc/rc_modes.h" + +#include "io/osd.h" + #include "msp/msp_protocol.h" #include "msp/msp_serial.h" -#include "displayport_hdzero_osd.h" +#include "displayport_msp_osd.h" #define FONT_VERSION 3 @@ -54,49 +58,58 @@ FILE_COMPILE_FOR_SPEED #define MSP_WRITE_STRING 3 #define MSP_DRAW_SCREEN 4 #define MSP_SET_OPTIONS 5 + +typedef enum { // defines are from hdzero code + SD_3016, + HD_5018, + HD_3016, // Special HDZERO mode that just sends the centre 30x16 of the 50x18 canvas to the VRX + HD_6022 // added to support DJI wtfos 60x22 grid +} resolutionType_e; + #define DRAW_FREQ_DENOM 4 // 60Hz #define TX_BUFFER_SIZE 1024 #define VTX_TIMEOUT 1000 // 1 second timer static mspProcessCommandFnPtr mspProcessCommand; -static mspPort_t hdZeroMspPort; -static displayPort_t hdZeroOsdDisplayPort; +static mspPort_t mspPort; +static displayPort_t mspOsdDisplayPort; static bool vtxSeen, vtxActive, vtxReset; static timeMs_t vtxHeartbeat; -// HD screen size -#define ROWS 18 -#define COLS 50 +// PAL screen size +#define PAL_COLS 30 +#define PAL_ROWS 16 +// NTSC screen size +#define NTSC_COLS 30 +#define NTSC_ROWS 13 +// HDZERO screen size +#define HDZERO_COLS 50 +#define HDZERO_ROWS 18 +// Avatar screen size +#define AVATAR_COLS 54 +#define AVATAR_ROWS 20 +// DJIWTF screen size +#define DJI_COLS 60 +#define DJI_ROWS 22 + +// set COLS and ROWS to largest size available +#define COLS DJI_COLS +#define ROWS DJI_ROWS + +// set screen size #define SCREENSIZE (ROWS*COLS) + +static uint8_t currentOsdMode; // HDZero screen mode can change across layouts + static uint8_t screen[SCREENSIZE]; static BITARRAY_DECLARE(fontPage, SCREENSIZE); // font page for each character on the screen static BITARRAY_DECLARE(dirty, SCREENSIZE); // change status for each character on the screen static bool screenCleared; +static uint8_t screenRows, screenCols; +static videoSystem_e osdVideoSystem; extern uint8_t cliMode; -#ifdef HDZERO_STATS -static uint32_t dataSent; -static uint8_t resetCount; -#endif - -static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int len) -{ - UNUSED(displayPort); - - int sent = 0; - - if (!cliMode && vtxActive) { - sent = mspSerialPushPort(cmd, subcmd, len, &hdZeroMspPort, MSP_V1); - } - -#ifdef HDZERO_STATS - dataSent += sent; -#endif - - return sent; -} - static void checkVtxPresent(void) { if (vtxActive && (millis()-vtxHeartbeat) > VTX_TIMEOUT) { @@ -104,14 +117,55 @@ static void checkVtxPresent(void) } } -static int setHdMode(displayPort_t *displayPort) +static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int len) { + UNUSED(displayPort); + checkVtxPresent(); - uint8_t subcmd[] = { MSP_SET_OPTIONS, 0, 1 }; // font selection, mode (SD/HD) + + int sent = 0; + if (!cliMode && vtxActive) { + sent = mspSerialPushPort(cmd, subcmd, len, &mspPort, MSP_V1); + } + + return sent; +} + +static uint8_t determineHDZeroOsdMode(void) +{ + if (cmsInMenu) { + return HD_5018; + } + + // Check if all visible widgets are in the center 30x16 chars of the canvas. + int activeLayout = osdGetActiveLayout(NULL); + osd_items_e index = 0; + do { + index = osdIncElementIndex(index); + uint16_t pos = osdLayoutsConfig()->item_pos[activeLayout][index]; + if (OSD_VISIBLE(pos)) { + uint8_t elemPosX = OSD_X(pos); + uint8_t elemPosY = OSD_Y(pos); + if (!osdItemIsFixed(index) && (elemPosX < 10 || elemPosX > 39 || elemPosY == 0 || elemPosY == 17)) { + return HD_5018; + } + } + } while (index > 0); + + return HD_3016; +} + +static int setDisplayMode(displayPort_t *displayPort) +{ + if (osdVideoSystem == VIDEO_SYSTEM_HDZERO) { + currentOsdMode = determineHDZeroOsdMode(); // Can change between layouts + } + + uint8_t subcmd[] = { MSP_SET_OPTIONS, 0, currentOsdMode }; // Font selection, mode (SD/HD) return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); } -static void hdZeroInit(void) +static void init(void) { memset(screen, SYM_BLANK, sizeof(screen)); BITARRAY_CLR_ALL(fontPage); @@ -122,9 +176,17 @@ static int clearScreen(displayPort_t *displayPort) { uint8_t subcmd[] = { MSP_CLEAR_SCREEN }; - hdZeroInit(); - setHdMode(displayPort); - screenCleared = true; + if (!cmsInMenu && IS_RC_MODE_ACTIVE(BOXOSD)) { // OSD is off + output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); + subcmd[0] = MSP_DRAW_SCREEN; + vtxReset = true; + } + else { + init(); + setDisplayMode(displayPort); + screenCleared = true; + } + return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd)); } @@ -183,40 +245,6 @@ static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, con return 0; } -#ifdef HDZERO_STATS -static void printStats(displayPort_t *displayPort, uint32_t updates) -{ - static timeMs_t lastTime; - static uint32_t maxDataSent, maxBufferUsed, maxUpdates; - timeMs_t currentTime = millis(); - char lineBuffer[100]; - - if (updates > maxUpdates) { - maxUpdates = updates; // updates sent per displayWrite - } - - uint32_t bufferUsed = TX_BUFFER_SIZE - serialTxBytesFree(hdZeroMspPort.port); - if (bufferUsed > maxBufferUsed) { - maxBufferUsed = bufferUsed; // serial buffer used after displayWrite - } - - uint32_t diff = (currentTime - lastTime); - if (diff > 1000) { // Data sampled in 1 second - if (dataSent > maxDataSent) { - maxDataSent = dataSent; // bps (max 11520 allowed) - } - - dataSent = 0; - lastTime = currentTime; - } - - - tfp_sprintf(lineBuffer, "R:%2d %4ld %5ld(%5ld) U:%2ld(%2ld) B:%3ld(%4ld,%4ld)", resetCount, (millis()-vtxHeartbeat), - dataSent, maxDataSent, updates, maxUpdates, bufferUsed, maxBufferUsed, hdZeroMspPort.port->txBufferSize); - writeString(displayPort, 0, 17, lineBuffer, 0); -} -#endif - /** * Write only changed characters to the VTX */ @@ -224,74 +252,68 @@ static int drawScreen(displayPort_t *displayPort) // 250Hz { static uint8_t counter = 0; - if ((counter++ % DRAW_FREQ_DENOM) == 0) { - uint8_t subcmd[COLS + 4]; - uint8_t updateCount = 0; - subcmd[0] = MSP_WRITE_STRING; - - int next = BITARRAY_FIND_FIRST_SET(dirty, 0); - while (next >= 0) { - // Look for sequential dirty characters on the same line for the same font page - int pos = next; - uint8_t row = pos / COLS; - uint8_t col = pos % COLS; - int endOfLine = row * COLS + COLS; - bool page = bitArrayGet(fontPage, pos); - - uint8_t len = 4; - do { - bitArrayClr(dirty, pos); - subcmd[len++] = screen[pos++]; - - if (bitArrayGet(dirty, pos)) { - next = pos; - } - } while (next == pos && next < endOfLine && bitArrayGet(fontPage, next) == page); - - subcmd[1] = row; - subcmd[2] = col; - subcmd[3] = page; - output(displayPort, MSP_DISPLAYPORT, subcmd, len); - updateCount++; - next = BITARRAY_FIND_FIRST_SET(dirty, pos); - } - - if (updateCount > 0 || screenCleared) { - if (screenCleared) { - screenCleared = false; - } - subcmd[0] = MSP_DRAW_SCREEN; - output(displayPort, MSP_DISPLAYPORT, subcmd, 1); - } - -#ifdef HDZERO_STATS - printStats(displayPort, updateCount); -#endif - checkVtxPresent(); - - if (vtxReset) { -#ifdef HDZERO_STATS - resetCount++; -#endif - clearScreen(displayPort); - vtxReset = false; - } + if ((!cmsInMenu && IS_RC_MODE_ACTIVE(BOXOSD)) || (counter++ % DRAW_FREQ_DENOM)) { + return 0; } - return 0; + + uint8_t subcmd[COLS + 4]; + uint8_t updateCount = 0; + subcmd[0] = MSP_WRITE_STRING; + + int next = BITARRAY_FIND_FIRST_SET(dirty, 0); + while (next >= 0) { + // Look for sequential dirty characters on the same line for the same font page + int pos = next; + uint8_t row = pos / COLS; + uint8_t col = pos % COLS; + int endOfLine = row * COLS + screenCols; + bool page = bitArrayGet(fontPage, pos); + + uint8_t len = 4; + do { + bitArrayClr(dirty, pos); + subcmd[len++] = screen[pos++]; + + if (bitArrayGet(dirty, pos)) { + next = pos; + } + } while (next == pos && next < endOfLine && bitArrayGet(fontPage, next) == page); + + subcmd[1] = row; + subcmd[2] = col; + subcmd[3] = page; + output(displayPort, MSP_DISPLAYPORT, subcmd, len); + updateCount++; + next = BITARRAY_FIND_FIRST_SET(dirty, pos); + } + + if (updateCount > 0 || screenCleared) { + if (screenCleared) { + screenCleared = false; + } + + subcmd[0] = MSP_DRAW_SCREEN; + output(displayPort, MSP_DISPLAYPORT, subcmd, 1); + } + + if (vtxReset) { + clearScreen(displayPort); + vtxReset = false; + } + +return 0; } static void resync(displayPort_t *displayPort) { - displayPort->rows = ROWS; - displayPort->cols = COLS; - setHdMode(displayPort); + displayPort->rows = screenRows; + displayPort->cols = screenCols; } static int screenSize(const displayPort_t *displayPort) { - UNUSED(displayPort); - return SCREENSIZE; + return (displayPort->rows * displayPort->cols); } static uint32_t txBytesFree(const displayPort_t *displayPort) @@ -344,7 +366,7 @@ static int release(displayPort_t *displayPort) return 0; } -static const displayPortVTable_t hdzeroOsdVTable = { +static const displayPortVTable_t mspOsdVTable = { .grab = grab, .release = release, .clearScreen = clearScreen, @@ -362,14 +384,14 @@ static const displayPortVTable_t hdzeroOsdVTable = { .isReady = isReady, }; -bool hdzeroOsdSerialInit(void) +bool mspOsdSerialInit(void) { static volatile uint8_t txBuffer[TX_BUFFER_SIZE]; - memset(&hdZeroMspPort, 0, sizeof(mspPort_t)); + memset(&mspPort, 0, sizeof(mspPort_t)); - serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_HDZERO_OSD); + serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP_OSD); if (portConfig) { - serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_HDZERO_OSD, NULL, NULL, + serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_MSP_OSD, NULL, NULL, baudRates[portConfig->peripheral_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED); if (port) { @@ -379,7 +401,7 @@ bool hdzeroOsdSerialInit(void) port->txBufferTail = 0; port->txBufferHead = 0; - resetMspPort(&hdZeroMspPort, port); + resetMspPort(&mspPort, port); return true; } @@ -388,12 +410,40 @@ bool hdzeroOsdSerialInit(void) return false; } -displayPort_t* hdzeroOsdDisplayPortInit(void) +displayPort_t* mspOsdDisplayPortInit(const videoSystem_e videoSystem) { - if (hdzeroOsdSerialInit()) { - hdZeroInit(); - displayInit(&hdZeroOsdDisplayPort, &hdzeroOsdVTable); - return &hdZeroOsdDisplayPort; + if (mspOsdSerialInit()) { + switch(videoSystem) { + case VIDEO_SYSTEM_AUTO: + case VIDEO_SYSTEM_PAL: + currentOsdMode = SD_3016; + screenRows = PAL_ROWS; + screenCols = PAL_COLS; + break; + case VIDEO_SYSTEM_NTSC: + currentOsdMode = SD_3016; + screenRows = NTSC_ROWS; + screenCols = NTSC_COLS; + break; + case VIDEO_SYSTEM_HDZERO: + currentOsdMode = HD_5018; + screenRows = HDZERO_ROWS; + screenCols = HDZERO_COLS; + break; + case VIDEO_SYSTEM_DJIWTF: + currentOsdMode = HD_6022; + screenRows = DJI_ROWS; + screenCols = DJI_COLS; + break; + default: + break; + } + + osdVideoSystem = videoSystem; + init(); + displayInit(&mspOsdDisplayPort, &mspOsdVTable); + + return &mspOsdDisplayPort; } return NULL; } @@ -401,11 +451,11 @@ displayPort_t* hdzeroOsdDisplayPortInit(void) /* * Intercept MSP processor. * VTX sends an MSP command every 125ms or so. - * VTX will have be marked as not ready if no commands received within VTX_TIMEOUT. + * VTX will have be marked as not ready if no commands received within VTX_TIMEOUT ms. */ -static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) +static mspResult_e processMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) { - if (vtxSeen && !vtxActive) { + if ((vtxSeen && !vtxActive) || (cmd->cmd == MSP_EEPROM_WRITE)) { vtxReset = true; } @@ -416,12 +466,12 @@ static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, return mspProcessCommand(cmd, reply, mspPostProcessFn); } -void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn) +void mspOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn) { - if (hdZeroMspPort.port) { + if (mspPort.port) { mspProcessCommand = mspProcessCommandFn; - mspSerialProcessOnePort(&hdZeroMspPort, MSP_SKIP_NON_MSP_DATA, hdZeroProcessMspCommand); + mspSerialProcessOnePort(&mspPort, MSP_SKIP_NON_MSP_DATA, processMspCommand); } } -#endif // USE_HDZERO_OSD +#endif // USE_MSP_OSD diff --git a/src/main/io/displayport_hdzero_osd.h b/src/main/io/displayport_msp_osd.h similarity index 89% rename from src/main/io/displayport_hdzero_osd.h rename to src/main/io/displayport_msp_osd.h index 54d9f8480b..717c781a78 100644 --- a/src/main/io/displayport_hdzero_osd.h +++ b/src/main/io/displayport_msp_osd.h @@ -29,5 +29,5 @@ typedef struct displayPort_s displayPort_t; -displayPort_t *hdzeroOsdDisplayPortInit(void); -void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn); +displayPort_t *mspOsdDisplayPortInit(const videoSystem_e videoSystem); +void mspOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn); diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index a96453c01b..7ba9b75e36 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -44,8 +44,8 @@ #define FRSKY_OSD_INFO_READY_INTERVAL_MS 5000 #define FRSKY_OSD_TRACE(fmt, ...) -#define FRSKY_OSD_DEBUG(fmt, ...) LOG_D(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) -#define FRSKY_OSD_ERROR(fmt, ...) LOG_E(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) +#define FRSKY_OSD_DEBUG(fmt, ...) LOG_DEBUG(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) +#define FRSKY_OSD_ERROR(fmt, ...) LOG_ERROR(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) #define FRSKY_OSD_ASSERT(x) typedef enum diff --git a/src/main/io/gps.c b/src/main/io/gps.c index abc44c601f..4976b797be 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -70,6 +70,8 @@ #include "flight/pid.h" #include "flight/mixer.h" +#include "programming/logic_condition.h" + typedef struct { bool isDriverBased; portMode_t portMode; // Port mode RX/TX (only for serial based) @@ -168,7 +170,7 @@ void updateEstimatedGPSFix(void) { static int32_t last_lon = 0; static int32_t last_alt = 0; - if (IS_RC_MODE_ACTIVE(BOXGPSOFF)) + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX)) { gpsSol.fixType = GPS_NO_FIX; gpsSol.hdop = 9999; @@ -266,9 +268,9 @@ void gpsProcessNewSolutionData(void) } else { /* When no fix available - reset flags as well */ - gpsSol.flags.validVelNE = 0; - gpsSol.flags.validVelD = 0; - gpsSol.flags.validEPE = 0; + gpsSol.flags.validVelNE = false; + gpsSol.flags.validVelD = false; + gpsSol.flags.validEPE = false; DISABLE_STATE(GPS_FIX); } @@ -284,7 +286,7 @@ void gpsProcessNewSolutionData(void) gpsUpdateTime(); // Update timeout - gpsSetProtocolTimeout(GPS_TIMEOUT); + gpsSetProtocolTimeout(gpsState.baseTimeoutMs); // Update statistics gpsStats.lastMessageDt = gpsState.lastMessageMs - gpsState.lastLastMessageMs; @@ -303,17 +305,18 @@ static void gpsResetSolution(void) gpsSol.fixType = GPS_NO_FIX; - gpsSol.flags.validVelNE = 0; - gpsSol.flags.validVelD = 0; - gpsSol.flags.validMag = 0; - gpsSol.flags.validEPE = 0; - gpsSol.flags.validTime = 0; + gpsSol.flags.validVelNE = false; + gpsSol.flags.validVelD = false; + gpsSol.flags.validMag = false; + gpsSol.flags.validEPE = false; + gpsSol.flags.validTime = false; } void gpsPreInit(void) { // Make sure gpsProvider is known when gpsMagDetect is called gpsState.gpsConfig = gpsConfig(); + gpsState.baseTimeoutMs = (gpsState.gpsConfig->provider == GPS_NMEA) ? GPS_TIMEOUT*2 : GPS_TIMEOUT; } void gpsInit(void) @@ -326,7 +329,7 @@ void gpsInit(void) // Reset solution, timeout and prepare to start gpsResetSolution(); - gpsSetProtocolTimeout(GPS_TIMEOUT); + gpsSetProtocolTimeout(gpsState.baseTimeoutMs); gpsSetState(GPS_UNKNOWN); // If given GPS provider has protocol() function not defined - we can't use it @@ -394,6 +397,7 @@ static bool gpsFakeGPSUpdate(void) uint32_t delta = now - gpsState.lastMessageMs; if (delta > 100) { int32_t speed = ARMING_FLAG(ARMED) ? FAKE_GPS_GROUND_ARMED_SPEED : FAKE_GPS_GROUND_UNARMED_SPEED; + speed = speed * sin_approx((now % 1000) / 1000.f * M_PIf) * +speed; int32_t cmDelta = speed * (delta / 1000.0f); int32_t latCmDelta = cmDelta * cos_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); int32_t lonCmDelta = cmDelta * sin_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); @@ -414,10 +418,10 @@ static bool gpsFakeGPSUpdate(void) gpsSol.velNED[X] = speed * cos_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); gpsSol.velNED[Y] = speed * sin_approx(DECIDEGREES_TO_RADIANS(FAKE_GPS_GROUND_COURSE_DECIDEGREES)); gpsSol.velNED[Z] = 0; - gpsSol.flags.validVelNE = 1; - gpsSol.flags.validVelD = 1; - gpsSol.flags.validEPE = 1; - gpsSol.flags.validTime = 1; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; + gpsSol.flags.validEPE = true; + gpsSol.flags.validTime = true; gpsSol.eph = 100; gpsSol.epv = 100; gpsSol.time.year = 1983; @@ -432,9 +436,10 @@ static bool gpsFakeGPSUpdate(void) gpsUpdateTime(); onNewGPSData(); - gpsSetProtocolTimeout(GPS_TIMEOUT); + gpsSetProtocolTimeout(gpsState.baseTimeoutMs); gpsSetState(GPS_RUNNING); + gpsSol.flags.gpsHeartbeat = !gpsSol.flags.gpsHeartbeat; return true; } return false; @@ -498,7 +503,7 @@ bool gpsUpdate(void) gpsProviders[gpsState.gpsConfig->provider].restart(); // Switch to GPS_RUNNING state (mind the timeout) - gpsSetProtocolTimeout(GPS_TIMEOUT); + gpsSetProtocolTimeout(gpsState.baseTimeoutMs); gpsSetState(GPS_RUNNING); } break; @@ -508,7 +513,7 @@ bool gpsUpdate(void) gpsProviders[gpsState.gpsConfig->provider].protocol(); // Check for GPS timeout - if ((millis() - gpsState.lastMessageMs) > GPS_TIMEOUT) { + if ((millis() - gpsState.lastMessageMs) > gpsState.baseTimeoutMs) { sensorsClear(SENSOR_GPS); DISABLE_STATE(GPS_FIX); gpsSol.fixType = GPS_NO_FIX; diff --git a/src/main/io/gps_msp.c b/src/main/io/gps_msp.c index ce33828fb6..8eafb2dff1 100644 --- a/src/main/io/gps_msp.c +++ b/src/main/io/gps_msp.c @@ -94,9 +94,9 @@ void mspGPSReceiveNewData(const uint8_t * bufferPtr) gpsSol.eph = gpsConstrainEPE(pkt->horizontalPosAccuracy / 10); gpsSol.epv = gpsConstrainEPE(pkt->verticalPosAccuracy / 10); gpsSol.hdop = gpsConstrainHDOP(pkt->hdop); - gpsSol.flags.validVelNE = 1; - gpsSol.flags.validVelD = 1; - gpsSol.flags.validEPE = 1; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; + gpsSol.flags.validEPE = true; gpsSol.time.year = pkt->year; gpsSol.time.month = pkt->month; diff --git a/src/main/io/gps_nmea.c b/src/main/io/gps_nmea.c index 260378d78f..c5c3b420db 100755 --- a/src/main/io/gps_nmea.c +++ b/src/main/io/gps_nmea.c @@ -212,15 +212,15 @@ static bool gpsNewFrameNMEA(char c) gpsSol.hdop = gpsConstrainHDOP(gps_Msg.hdop); gpsSol.eph = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER); gpsSol.epv = gpsConstrainEPE(gps_Msg.hdop * GPS_HDOP_TO_EPH_MULTIPLIER); - gpsSol.flags.validEPE = 0; + gpsSol.flags.validEPE = false; } else { gpsSol.fixType = GPS_NO_FIX; } // NMEA does not report VELNED - gpsSol.flags.validVelNE = 0; - gpsSol.flags.validVelD = 0; + gpsSol.flags.validVelNE = false; + gpsSol.flags.validVelD = false; break; case FRAME_RMC: gpsSol.groundSpeed = gps_Msg.speed; @@ -235,10 +235,10 @@ static bool gpsNewFrameNMEA(char c) gpsSol.time.minutes = (gps_Msg.time / 10000) % 100; gpsSol.time.seconds = (gps_Msg.time / 100) % 100; gpsSol.time.millis = (gps_Msg.time & 100) * 10; - gpsSol.flags.validTime = 1; + gpsSol.flags.validTime = true; } else { - gpsSol.flags.validTime = 0; + gpsSol.flags.validTime = false; } break; @@ -276,8 +276,8 @@ STATIC_PROTOTHREAD(gpsProtocolReceiverThread) while (serialRxBytesWaiting(gpsState.gpsPort)) { uint8_t newChar = serialRead(gpsState.gpsPort); if (gpsNewFrameNMEA(newChar)) { - gpsSol.flags.validVelNE = 0; - gpsSol.flags.validVelD = 0; + gpsSol.flags.validVelNE = false; + gpsSol.flags.validVelD = false; ptSemaphoreSignal(semNewDataReady); break; } @@ -307,7 +307,7 @@ STATIC_PROTOTHREAD(gpsProtocolStateThreadNMEA) // No configuration is done for pure NMEA modules // GPS setup done, reset timeout - gpsSetProtocolTimeout(GPS_TIMEOUT); + gpsSetProtocolTimeout(gpsState.baseTimeoutMs); // GPS is ready - execute the gpsProcessNewSolutionData() based on gpsProtocolReceiverThread semaphore while (1) { diff --git a/src/main/io/gps_private.h b/src/main/io/gps_private.h index 539689c62f..fd35d8540f 100755 --- a/src/main/io/gps_private.h +++ b/src/main/io/gps_private.h @@ -23,7 +23,7 @@ #define GPS_HDOP_TO_EPH_MULTIPLIER 2 // empirical value -// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2000 ms) +// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 1000 ms) #define GPS_TIMEOUT (1000) #define GPS_SHORT_TIMEOUT (500) #define GPS_BAUD_CHANGE_DELAY (100) @@ -53,6 +53,7 @@ typedef struct { timeMs_t lastLastMessageMs; timeMs_t lastMessageMs; timeMs_t timeoutMs; + timeMs_t baseTimeoutMs; } gpsReceiverData_t; extern gpsReceiverData_t gpsState; diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c index 90715b3c81..330cb2b75f 100755 --- a/src/main/io/gps_ublox.c +++ b/src/main/io/gps_ublox.c @@ -609,7 +609,7 @@ static bool gpsParceFrameUBLOX(void) gpsSol.llh.alt = _buffer.posllh.altitude_msl / 10; //alt in cm gpsSol.eph = gpsConstrainEPE(_buffer.posllh.horizontal_accuracy / 10); gpsSol.epv = gpsConstrainEPE(_buffer.posllh.vertical_accuracy / 10); - gpsSol.flags.validEPE = 1; + gpsSol.flags.validEPE = true; if (next_fix_type != GPS_NO_FIX) gpsSol.fixType = next_fix_type; _new_position = true; @@ -632,8 +632,8 @@ static bool gpsParceFrameUBLOX(void) gpsSol.velNED[X] = _buffer.velned.ned_north; gpsSol.velNED[Y] = _buffer.velned.ned_east; gpsSol.velNED[Z] = _buffer.velned.ned_down; - gpsSol.flags.validVelNE = 1; - gpsSol.flags.validVelD = 1; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; _new_speed = true; break; case MSG_TIMEUTC: @@ -646,9 +646,9 @@ static bool gpsParceFrameUBLOX(void) gpsSol.time.seconds = _buffer.timeutc.sec; gpsSol.time.millis = _buffer.timeutc.nano / (1000*1000); - gpsSol.flags.validTime = 1; + gpsSol.flags.validTime = true; } else { - gpsSol.flags.validTime = 0; + gpsSol.flags.validTime = false; } break; case MSG_PVT: @@ -666,9 +666,9 @@ static bool gpsParceFrameUBLOX(void) gpsSol.eph = gpsConstrainEPE(_buffer.pvt.horizontal_accuracy / 10); gpsSol.epv = gpsConstrainEPE(_buffer.pvt.vertical_accuracy / 10); gpsSol.hdop = gpsConstrainHDOP(_buffer.pvt.position_DOP); - gpsSol.flags.validVelNE = 1; - gpsSol.flags.validVelD = 1; - gpsSol.flags.validEPE = 1; + gpsSol.flags.validVelNE = true; + gpsSol.flags.validVelD = true; + gpsSol.flags.validEPE = true; if (UBX_VALID_GPS_DATE_TIME(_buffer.pvt.valid)) { gpsSol.time.year = _buffer.pvt.year; @@ -679,9 +679,9 @@ static bool gpsParceFrameUBLOX(void) gpsSol.time.seconds = _buffer.pvt.sec; gpsSol.time.millis = _buffer.pvt.nano / (1000*1000); - gpsSol.flags.validTime = 1; + gpsSol.flags.validTime = true; } else { - gpsSol.flags.validTime = 0; + gpsSol.flags.validTime = false; } _new_position = true; @@ -1047,7 +1047,7 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread) } // GPS setup done, reset timeout - gpsSetProtocolTimeout(GPS_TIMEOUT); + gpsSetProtocolTimeout(gpsState.baseTimeoutMs); // GPS is ready - execute the gpsProcessNewSolutionData() based on gpsProtocolReceiverThread semaphore while (1) { diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d77913259d..284abe03e2 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -87,7 +87,6 @@ FILE_COMPILE_FOR_SPEED #include "flight/pid.h" #include "flight/power_limits.h" #include "flight/rth_estimator.h" -#include "flight/secondary_imu.h" #include "flight/servos.h" #include "flight/wind_estimator.h" @@ -115,7 +114,8 @@ FILE_COMPILE_FOR_SPEED #endif #define VIDEO_BUFFER_CHARS_PAL 480 -#define VIDEO_BUFFER_CHARS_HD 900 +#define VIDEO_BUFFER_CHARS_HDZERO 900 +#define VIDEO_BUFFER_CHARS_DJIWTF 1320 #define GFORCE_FILTER_TC 0.2 @@ -220,7 +220,11 @@ bool osdDisplayIsPAL(void) bool osdDisplayIsHD(void) { - return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_HD; + if (displayScreenSize(osdDisplayPort) >= VIDEO_BUFFER_CHARS_HDZERO) + { + return true; + } + return false; } /** @@ -1112,28 +1116,12 @@ uint16_t osdGetRemainingGlideTime(void) { static bool osdIsHeadingValid(void) { -#ifdef USE_SECONDARY_IMU - if (secondaryImuState.active && secondaryImuConfig()->useForOsdHeading) { - return true; - } else { - return isImuHeadingValid(); - } -#else return isImuHeadingValid(); -#endif } int16_t osdGetHeading(void) { -#ifdef USE_SECONDARY_IMU - if (secondaryImuState.active && secondaryImuConfig()->useForOsdHeading) { - return secondaryImuState.eulerAngles.values.yaw; - } else { - return attitude.values.yaw; - } -#else return attitude.values.yaw; -#endif } int16_t osdPanServoHomeDirectionOffset(void) @@ -1516,7 +1504,7 @@ int8_t getGeoWaypointNumber(int8_t waypointIndex) if (waypointIndex != lastWaypointIndex) { lastWaypointIndex = geoWaypointIndex = waypointIndex; - for (uint8_t i = 0; i <= waypointIndex; i++) { + for (uint8_t i = posControl.startWpIndex; i <= waypointIndex; i++) { if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { @@ -1525,7 +1513,7 @@ int8_t getGeoWaypointNumber(int8_t waypointIndex) } } - return geoWaypointIndex + 1; + return geoWaypointIndex - posControl.startWpIndex + 1; } void osdDisplaySwitchIndicator(const char *swName, int rcValue, char *buff) { @@ -1793,6 +1781,19 @@ static bool osdDrawSingleElement(uint8_t item) break; } + case OSD_GROUND_COURSE: + { + buff[0] = SYM_GROUND_COURSE; + if (osdIsHeadingValid()) { + tfp_sprintf(&buff[1], "%3d", (int16_t)CENTIDEGREES_TO_DEGREES(posControl.actualState.cog)); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = SYM_DEGREES; + buff[5] = '\0'; + break; + } + case OSD_COURSE_HOLD_ERROR: { if (ARMING_FLAG(ARMED) && !FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) { @@ -1839,6 +1840,18 @@ static bool osdDrawSingleElement(uint8_t item) break; } + case OSD_CROSS_TRACK_ERROR: + { + if (isWaypointNavTrackingActive()) { + buff[0] = SYM_CROSS_TRACK_ERROR; + osdFormatDistanceSymbol(buff + 1, navigationGetCrossTrackError(), 0); + } else { + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + return true; + } + break; + } + case OSD_GPS_HDOP: { buff[0] = SYM_HDP_L; @@ -1944,20 +1957,20 @@ static bool osdDrawSingleElement(uint8_t item) } #endif if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) { - buff[0] = SYM_FLY_M; + buff[0] = SYM_FLIGHT_MINS_REMAINING; strcpy(buff + 1, "--:--"); #if defined(USE_ADC) && defined(USE_GPS) updatedTimestamp = 0; #endif } else if (timeSeconds == -2) { // Wind is too strong to come back with cruise throttle - buff[0] = SYM_FLY_M; + buff[0] = SYM_FLIGHT_MINS_REMAINING; buff[1] = buff[2] = buff[4] = buff[5] = SYM_WIND_HORIZONTAL; buff[3] = ':'; buff[6] = '\0'; TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } else { - osdFormatTime(buff, timeSeconds, SYM_FLY_M, SYM_FLY_H); + osdFormatTime(buff, timeSeconds, SYM_FLIGHT_MINS_REMAINING, SYM_FLIGHT_HOURS_REMAINING); if (timeSeconds == 0) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } @@ -1978,7 +1991,8 @@ static bool osdDrawSingleElement(uint8_t item) updatedTimestamp = currentTimeUs; } #endif - buff[0] = SYM_TRIP_DIST; + //buff[0] = SYM_TRIP_DIST; + displayWriteChar(osdDisplayPort, elemPosX, elemPosY, SYM_FLIGHT_DIST_REMAINING); if ((!ARMING_FLAG(ARMED)) || (distanceMeters == -1)) { buff[4] = SYM_BLANK; buff[5] = '\0'; @@ -2222,7 +2236,7 @@ static bool osdDrawSingleElement(uint8_t item) for (int i = osdConfig()->hud_wp_disp - 1; i >= 0 ; i--) { // Display in reverse order so the next WP is always written on top j = posControl.activeWaypointIndex + i; - if (j > posControl.waypointCount - 1) { // limit to max WP index for mission + if (j > posControl.startWpIndex + posControl.waypointCount - 1) { // limit to max WP index for mission break; } if (posControl.waypointList[j].lat != 0 && posControl.waypointList[j].lon != 0) { @@ -2262,21 +2276,9 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_ARTIFICIAL_HORIZON: { - float rollAngle; - float pitchAngle; + float rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); + float pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); -#ifdef USE_SECONDARY_IMU - if (secondaryImuState.active && secondaryImuConfig()->useForOsdAHI) { - rollAngle = DECIDEGREES_TO_RADIANS(secondaryImuState.eulerAngles.values.roll); - pitchAngle = DECIDEGREES_TO_RADIANS(secondaryImuState.eulerAngles.values.pitch); - } else { - rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); - pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); - } -#else - rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); - pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); -#endif pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0; pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim()); if (osdConfig()->ahi_reverse_roll) { @@ -2566,7 +2568,7 @@ static bool osdDrawSingleElement(uint8_t item) return true; case OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)currentBatteryProfile->fwMinThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "0TP", 0, (float)navConfig()->fw.minThrottleDownPitchAngle / 10, 3, 1, ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE); return true; case OSD_FW_ALT_PID_OUTPUTS: @@ -3143,9 +3145,17 @@ static bool osdDrawSingleElement(uint8_t item) } case OSD_NAV_FW_CONTROL_SMOOTHNESS: - osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS); - return true; - + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "CTL S", 0, navConfig()->fw.control_smoothness, 1, 0, ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS); + return true; + } +#ifdef USE_MULTI_MISSION + case OSD_NAV_WP_MULTI_MISSION_INDEX: + { + osdDisplayAdjustableDecimalValue(elemPosX, elemPosY, "WP NO", 0, navConfig()->general.waypoint_multi_mission_index, 1, 0, ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX); + return true; + } +#endif case OSD_MISSION: { if (IS_RC_MODE_ACTIVE(BOXPLANWPMISSION)) { @@ -3169,22 +3179,20 @@ static bool osdDrawSingleElement(uint8_t item) } #ifdef USE_MULTI_MISSION else { - if (ARMING_FLAG(ARMED)){ + if (ARMING_FLAG(ARMED) && !(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION) && posControl.multiMissionCount > 1)){ // Limit field size when Armed, only show selected mission tfp_sprintf(buff, "M%u ", posControl.loadedMultiMissionIndex); - } else if (posControl.multiMissionCount && navConfig()->general.waypoint_multi_mission_index){ + } else if (posControl.multiMissionCount) { if (navConfig()->general.waypoint_multi_mission_index != posControl.loadedMultiMissionIndex) { tfp_sprintf(buff, "M%u/%u>LOAD", navConfig()->general.waypoint_multi_mission_index, posControl.multiMissionCount); } else { - // wpCount source for selected mission changes after Arming (until next mission load) - int8_t wpCount = posControl.loadedMultiMissionWPCount ? posControl.loadedMultiMissionWPCount : posControl.waypointCount; - if (posControl.waypointListValid && wpCount > 0) { - tfp_sprintf(buff, "M%u/%u>%2uWP", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, wpCount); + if (posControl.waypointListValid && posControl.waypointCount > 0) { + tfp_sprintf(buff, "M%u/%u>%2uWP", posControl.loadedMultiMissionIndex, posControl.multiMissionCount, posControl.waypointCount); } else { tfp_sprintf(buff, "M0/%u> 0WP", posControl.multiMissionCount); } } - } else { // multi_mission_index 0 - show active WP count + } else { // no multi mission loaded - show active WP count from other source tfp_sprintf(buff, "WP CNT>%2u", posControl.waypointCount); } } @@ -3237,7 +3245,7 @@ static bool osdDrawSingleElement(uint8_t item) return true; } -static uint8_t osdIncElementIndex(uint8_t elementIndex) +uint8_t osdIncElementIndex(uint8_t elementIndex) { ++elementIndex; @@ -3393,6 +3401,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .left_sidebar_scroll_step = SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT, .right_sidebar_scroll_step = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT, .sidebar_height = SETTING_OSD_SIDEBAR_HEIGHT_DEFAULT, + .ahi_pitch_interval = SETTING_OSD_AHI_PITCH_INTERVAL_DEFAULT, .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, @@ -3454,8 +3463,10 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2); osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_GROUND_COURSE] = OSD_POS(12, 3); osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ERROR] = OSD_POS(12, 2); osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ADJUSTMENT] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_CROSS_TRACK_ERROR] = OSD_POS(12, 3); osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; @@ -3630,7 +3641,7 @@ static void osdCompleteAsyncInitialization(void) uint8_t y = 1; displayFontMetadata_t metadata; bool fontHasMetadata = displayGetFontMetadata(&metadata, osdDisplayPort); - LOG_D(OSD, "Font metadata version %s: %u (%u chars)", + LOG_DEBUG(OSD, "Font metadata version %s: %u (%u chars)", fontHasMetadata ? "Y" : "N", metadata.version, metadata.charCount); if (fontHasMetadata && metadata.charCount > 256) { @@ -3657,7 +3668,7 @@ static void osdCompleteAsyncInitialization(void) char string_buffer[30]; tfp_sprintf(string_buffer, "INAV VERSION: %s", FC_VERSION_STRING); - uint8_t xPos = osdDisplayIsHD() ? 7 : 5; + uint8_t xPos = osdDisplayIsHD() ? 15 : 5; displayWrite(osdDisplayPort, xPos, y++, string_buffer); #ifdef USE_CMS displayWrite(osdDisplayPort, xPos+2, y++, CMS_STARTUP_HELP_TEXT1); @@ -3667,8 +3678,8 @@ static void osdCompleteAsyncInitialization(void) #ifdef USE_STATS - uint8_t statNameX = osdDisplayIsHD() ? 7 : 4; - uint8_t statValueX = osdDisplayIsHD() ? 27 : 24; + uint8_t statNameX = osdDisplayIsHD() ? 14 : 4; + uint8_t statValueX = osdDisplayIsHD() ? 34 : 24; if (statsConfig()->stats_enabled) { displayWrite(osdDisplayPort, statNameX, ++y, "ODOMETER:"); @@ -3829,8 +3840,8 @@ static void osdShowStatsPage1(void) { const char * disarmReasonStr[DISARM_REASON_COUNT] = { "UNKNOWN", "TIMEOUT", "STICKS", "SWITCH", "SWITCH", "KILLSW", "FAILSAFE", "NAV SYS", "LANDING"}; uint8_t top = 1; /* first fully visible line */ - const uint8_t statNameX = osdDisplayIsHD() ? 7 : 1; - const uint8_t statValuesX = osdDisplayIsHD() ? 33 : 20; + const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; + const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; char buff[10]; statsPagesCheck = 1; @@ -3904,8 +3915,8 @@ static void osdShowStatsPage1(void) static void osdShowStatsPage2(void) { uint8_t top = 1; /* first fully visible line */ - const uint8_t statNameX = osdDisplayIsHD() ? 7 : 1; - const uint8_t statValuesX = osdDisplayIsHD() ? 33 : 20; + const uint8_t statNameX = osdDisplayIsHD() ? 11 : 1; + const uint8_t statValuesX = osdDisplayIsHD() ? 30 : 20; char buff[10]; statsPagesCheck = 1; @@ -4408,7 +4419,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_RTH_CANCEL); } if (navGetCurrentStateFlags() & NAV_AUTO_WP_DONE) { - messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); + messages[messageCount++] = STATE(LANDING_DETECTED) ? OSD_MESSAGE_STR(OSD_MSG_WP_LANDED) : OSD_MESSAGE_STR(OSD_MSG_WP_FINISHED); } else if (NAV_Status.state == MW_NAV_STATE_WP_ENROUTE) { // Countdown display for remaining Waypoints char buf[6]; @@ -4524,6 +4535,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter } /* Messages that are shown regardless of Arming state */ + #ifdef USE_DEV_TOOLS if (systemConfig()->groundTestMode) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_GRD_TEST_MODE); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 525adc921b..d150b4e417 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -94,6 +94,7 @@ #define OSD_MSG_RTH_TRACKBACK "RTH BACK TRACKING" #define OSD_MSG_HEADING_HOME "EN ROUTE TO HOME" #define OSD_MSG_WP_FINISHED "WP END>HOLDING POSITION" +#define OSD_MSG_WP_LANDED "WP END>LANDED" #define OSD_MSG_PREPARE_NEXT_WP "PREPARING FOR NEXT WAYPOINT" #define OSD_MSG_ADJUSTING_WP_ALT "ADJUSTING WP ALTITUDE" #define OSD_MSG_MISSION_PLANNER "(WP MISSION PLANNER)" @@ -264,6 +265,9 @@ typedef enum { OSD_GLIDE_TIME_REMAINING, OSD_GLIDE_RANGE, OSD_CLIMB_EFFICIENCY, + OSD_NAV_WP_MULTI_MISSION_INDEX, + OSD_GROUND_COURSE, // 140 + OSD_CROSS_TRACK_ERROR, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -425,6 +429,7 @@ typedef struct osdConfig_s { uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. uint16_t system_msg_display_time; // system message display time for multiple messages (ms) uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh + uint8_t ahi_pitch_interval; // redraws AHI at set pitch interval (Not pixel OSD) char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. uint8_t osd_switch_indicator0_channel; // RC Channel to use for switch indicator 0. char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. @@ -455,6 +460,7 @@ void osdOverrideLayout(int layout, timeMs_t duration); // set by the user configuration (modes, etc..) or by overriding it. int osdGetActiveLayout(bool *overridden); bool osdItemIsFixed(osd_items_e item); +uint8_t osdIncElementIndex(uint8_t elementIndex); displayPort_t *osdGetDisplayPort(void); displayCanvas_t *osdGetDisplayPortCanvas(void); diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 361dce12fc..d9ac344c7b 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -438,7 +438,7 @@ void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *can void osdCanvasDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, int heading) { - static const uint16_t graph[] = { + static const uint8_t graph[] = { SYM_HEADING_W, SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 987334f4a1..119b2b4691 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -953,7 +953,7 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) tfp_sprintf(buff, "VZD %3d", pidBankMutable()->pid[PID_VEL_Z].D); break; case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE: - tfp_sprintf(buff, "MTDPA %4d", currentBatteryProfileMutable->fwMinThrottleDownPitchAngle); + tfp_sprintf(buff, "MTDPA %4d", navConfigMutable()->fw.minThrottleDownPitchAngle); break; case ADJUSTMENT_TPA: tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID); @@ -964,6 +964,11 @@ static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction) case ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS: tfp_sprintf(buff, "CSM %3d", navConfigMutable()->fw.control_smoothness); break; +#ifdef USE_MULTI_MISSION + case ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX: + tfp_sprintf(buff, "WPI %3d", navConfigMutable()->general.waypoint_multi_mission_index); + break; +#endif default: tfp_sprintf(buff, "UNSUPPORTED"); break; diff --git a/src/main/io/osd_grid.c b/src/main/io/osd_grid.c index 680f8a9999..9e79194498 100644 --- a/src/main/io/osd_grid.c +++ b/src/main/io/osd_grid.c @@ -140,12 +140,27 @@ void osdGridDrawArtificialHorizon(displayPort_t *display, unsigned gx, unsigned } } + int8_t ahiPitchAngleDatum; // sets the pitch datum AHI is drawn relative to (degrees) + int8_t ahiLineEndPitchOffset; // AHI end of line offset in degrees when ahiPitchAngleDatum > 0 + + if (osdConfig()->ahi_pitch_interval) { + ahiPitchAngleDatum = osdConfig()->ahi_pitch_interval * (int8_t)(RADIANS_TO_DEGREES(pitchAngle) / osdConfig()->ahi_pitch_interval); + pitchAngle -= DEGREES_TO_RADIANS(ahiPitchAngleDatum); + } else { + ahiPitchAngleDatum = 0; + } + if (fabsf(ky) < fabsf(kx)) { previous_orient = 0; + /* ahi line ends drawn with 3 deg offset when ahiPitchAngleDatum > 0 + * Line end offset increased by 1 deg with every 20 deg pitch increase */ + const int8_t ahiLineEndOffsetFactor = ahiPitchAngleDatum / 20; + for (int8_t dx = -OSD_AHI_WIDTH / 2; dx <= OSD_AHI_WIDTH / 2; dx++) { - float fy = (ratio * dx) * (ky / kx) + pitchAngle * pitch_rad_to_char + 0.49f; + ahiLineEndPitchOffset = ahiPitchAngleDatum && (dx == -OSD_AHI_WIDTH / 2 || dx == OSD_AHI_WIDTH / 2) ? -(ahiLineEndOffsetFactor + 3 * ABS(ahiPitchAngleDatum) / ahiPitchAngleDatum) : 0; + float fy = (ratio * dx) * (ky / kx) + (pitchAngle + DEGREES_TO_RADIANS(ahiLineEndPitchOffset)) * pitch_rad_to_char + 0.49f; int8_t dy = floorf(fy); const uint8_t chX = elemPosX + dx, chY = elemPosY - dy; uint16_t c; diff --git a/src/main/io/piniobox.h b/src/main/io/piniobox.h index a74f77cfe8..42499fffcf 100644 --- a/src/main/io/piniobox.h +++ b/src/main/io/piniobox.h @@ -29,7 +29,8 @@ #define BOX_PERMANENT_ID_USER1 47 #define BOX_PERMANENT_ID_USER2 48 -#define BOX_PERMANENT_ID_USER3 49 +#define BOX_PERMANENT_ID_USER3 57 +#define BOX_PERMANENT_ID_USER4 58 #define BOX_PERMANENT_ID_NONE 255 // A permanent ID for no box mode diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 3b2b5d68a6..4f727fd100 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -55,8 +55,8 @@ typedef enum { FUNCTION_DJI_HD_OSD = (1 << 21), // 2097152 FUNCTION_SERVO_SERIAL = (1 << 22), // 4194304 FUNCTION_TELEMETRY_SMARTPORT_MASTER = (1 << 23), // 8388608 - FUNCTION_IMU2 = (1 << 24), // 16777216 - FUNCTION_HDZERO_OSD = (1 << 25), // 33554432 + FUNCTION_UNUSED_2 = (1 << 24), // 16777216 + FUNCTION_MSP_OSD = (1 << 25), // 33554432 } serialPortFunction_e; typedef enum { diff --git a/src/main/io/smartport_master.c b/src/main/io/smartport_master.c index 4c46628ff2..08f52e7593 100644 --- a/src/main/io/smartport_master.c +++ b/src/main/io/smartport_master.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/io/smartport_master.h b/src/main/io/smartport_master.h index c499b490e5..3ea39e4cd4 100644 --- a/src/main/io/smartport_master.h +++ b/src/main/io/smartport_master.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav + * This file is part of INAV * - * iNav free software. You can redistribute + * INAV free software. You can redistribute * this software and/or modify this software 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 distributed in the hope that it + * 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. diff --git a/src/main/io/vtx_ffpv24g.c b/src/main/io/vtx_ffpv24g.c index 3cac3acf04..87c29418da 100644 --- a/src/main/io/vtx_ffpv24g.c +++ b/src/main/io/vtx_ffpv24g.c @@ -203,7 +203,7 @@ static void vtxProtoSend(uint8_t cmd, const uint8_t * data) memcpy(vtxState.sendPkt.data, data, sizeof(vtxState.sendPkt.data)); } else { - memset(vtxState.sendPkt.data, 0, sizeof(vtxState.sendPkt.data)); + ZERO_FARRAY(vtxState.sendPkt.data); } vtxState.sendPkt.checksum = vtxCalcChecksum(&vtxState.sendPkt); diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c index d498f3e816..9901db409e 100644 --- a/src/main/io/vtx_smartaudio.c +++ b/src/main/io/vtx_smartaudio.c @@ -183,18 +183,18 @@ static uint8_t CRC8(const uint8_t *data, const int8_t len) static void saPrintSettings(void) { - LOG_D(VTX, "Current status: version: %d", saDevice.version); - LOG_D(VTX, " mode(0x%x): fmode=%s", saDevice.mode, (saDevice.mode & 1) ? "freq" : "chan"); - LOG_D(VTX, " pit=%s ", (saDevice.mode & 2) ? "on " : "off"); - LOG_D(VTX, " inb=%s", (saDevice.mode & 4) ? "on " : "off"); - LOG_D(VTX, " outb=%s", (saDevice.mode & 8) ? "on " : "off"); - LOG_D(VTX, " lock=%s", (saDevice.mode & 16) ? "unlocked" : "locked"); - LOG_D(VTX, " deferred=%s", (saDevice.mode & 32) ? "on" : "off"); - LOG_D(VTX, " channel: %d ", saDevice.channel); - LOG_D(VTX, "freq: %d ", saDevice.freq); - LOG_D(VTX, "power: %d ", saDevice.power); - LOG_D(VTX, "pitfreq: %d ", saDevice.orfreq); - LOG_D(VTX, "BootIntoPitMode: %s", saDevice.willBootIntoPitMode ? "yes" : "no"); + LOG_DEBUG(VTX, "Current status: version: %d", saDevice.version); + LOG_DEBUG(VTX, " mode(0x%x): fmode=%s", saDevice.mode, (saDevice.mode & 1) ? "freq" : "chan"); + LOG_DEBUG(VTX, " pit=%s ", (saDevice.mode & 2) ? "on " : "off"); + LOG_DEBUG(VTX, " inb=%s", (saDevice.mode & 4) ? "on " : "off"); + LOG_DEBUG(VTX, " outb=%s", (saDevice.mode & 8) ? "on " : "off"); + LOG_DEBUG(VTX, " lock=%s", (saDevice.mode & 16) ? "unlocked" : "locked"); + LOG_DEBUG(VTX, " deferred=%s", (saDevice.mode & 32) ? "on" : "off"); + LOG_DEBUG(VTX, " channel: %d ", saDevice.channel); + LOG_DEBUG(VTX, "freq: %d ", saDevice.freq); + LOG_DEBUG(VTX, "power: %d ", saDevice.power); + LOG_DEBUG(VTX, "pitfreq: %d ", saDevice.orfreq); + LOG_DEBUG(VTX, "BootIntoPitMode: %s", saDevice.willBootIntoPitMode ? "yes" : "no"); } int saDacToPowerIndex(int dac) @@ -243,19 +243,19 @@ static void saAutobaud(void) return; } - LOG_D(VTX, "autobaud: adjusting"); + LOG_DEBUG(VTX, "autobaud: adjusting"); if ((sa_adjdir == 1) && (sa_smartbaud == SMARTBAUD_MAX)) { sa_adjdir = -1; - LOG_D(VTX, "autobaud: now going down"); + LOG_DEBUG(VTX, "autobaud: now going down"); } else if ((sa_adjdir == -1 && sa_smartbaud == SMARTBAUD_MIN)) { sa_adjdir = 1; - LOG_D(VTX, "autobaud: now going up"); + LOG_DEBUG(VTX, "autobaud: now going up"); } sa_smartbaud += sa_baudstep * sa_adjdir; - LOG_D(VTX, "autobaud: %d", sa_smartbaud); + LOG_DEBUG(VTX, "autobaud: %d", sa_smartbaud); smartAudioSerialPort->vTable->serialSetBaudRate(smartAudioSerialPort, sa_smartbaud); @@ -280,7 +280,7 @@ static void saProcessResponse(uint8_t *buf, int len) sa_outstanding = SA_CMD_NONE; } else { saStat.ooopresp++; - LOG_D(VTX, "processResponse: outstanding %d got %d", sa_outstanding, resp); + LOG_DEBUG(VTX, "processResponse: outstanding %d got %d", sa_outstanding, resp); } switch (resp) { @@ -307,7 +307,7 @@ static void saProcessResponse(uint8_t *buf, int len) if (saDevice.mode & SA_MODE_GET_PITMODE) { bool newBootMode = (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) || (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE); if (newBootMode != saDevice.willBootIntoPitMode) { - LOG_D(VTX, "saProcessResponse: willBootIntoPitMode is now %s\r\n", newBootMode ? "true" : "false"); + LOG_DEBUG(VTX, "saProcessResponse: willBootIntoPitMode is now %s\r\n", newBootMode ? "true" : "false"); } saDevice.willBootIntoPitMode = newBootMode; } @@ -315,7 +315,7 @@ static void saProcessResponse(uint8_t *buf, int len) if(saDevice.version == SA_2_1) { //read dbm based power levels if(len < 10) { //current power level in dbm field missing or power level length field missing or zero power levels reported - LOG_D(VTX, "processResponse: V2.1 vtx didn't report any power levels\r\n"); + LOG_DEBUG(VTX, "processResponse: V2.1 vtx didn't report any power levels\r\n"); break; } saPowerCount = constrain((int8_t)buf[8], 0, VTX_SMARTAUDIO_MAX_POWER_COUNT); @@ -324,7 +324,7 @@ static void saProcessResponse(uint8_t *buf, int len) //zero is indeed a valid power level to set the vtx to, but it activates pit mode. //crucially, after sending 0 dbm, the vtx does NOT report its power level to be 0 dbm. //instead, it reports whatever value was set previously and it reports to be in pit mode. - //for this reason, zero shouldn't be used as a normal power level in iNav. + //for this reason, zero shouldn't be used as a normal power level in INAV. for (int8_t i = 0; i < saPowerCount; i++ ) { saPowerTable[i].dbi = buf[9 + i + 1]; //+ 1 to skip the first power level, as mentioned above saPowerTable[i].mW = saDbiToMw(saPowerTable[i].dbi); @@ -336,14 +336,14 @@ static void saProcessResponse(uint8_t *buf, int len) } } - LOG_D(VTX, "processResponse: %d power values: %d, %d, %d, %d\r\n", + LOG_DEBUG(VTX, "processResponse: %d power values: %d, %d, %d, %d\r\n", saPowerCount, saPowerTable[0].dbi, saPowerTable[1].dbi, saPowerTable[2].dbi, saPowerTable[3].dbi); - //LOG_D(VTX, "processResponse: V2.1 received vtx power value %d\r\n",buf[7]); + //LOG_DEBUG(VTX, "processResponse: V2.1 received vtx power value %d\r\n",buf[7]); rawPowerValue = buf[7]; saDevice.power = 0; //set to unknown power level if the reported one doesnt match any of the known ones - LOG_D(VTX, "processResponse: rawPowerValue is %d, legacy power is %d\r\n", rawPowerValue, buf[3]); + LOG_DEBUG(VTX, "processResponse: rawPowerValue is %d, legacy power is %d\r\n", rawPowerValue, buf[3]); for (int8_t i = 0; i < saPowerCount; i++) { if (rawPowerValue == saPowerTable[i].dbi) { saDevice.power = i + 1; @@ -374,18 +374,18 @@ static void saProcessResponse(uint8_t *buf, int len) if (freq & SA_FREQ_GETPIT) { saDevice.orfreq = freq & SA_FREQ_MASK; - LOG_D(VTX, "saProcessResponse: GETPIT freq %d", saDevice.orfreq); + LOG_DEBUG(VTX, "saProcessResponse: GETPIT freq %d", saDevice.orfreq); } else if (freq & SA_FREQ_SETPIT) { saDevice.orfreq = freq & SA_FREQ_MASK; - LOG_D(VTX, "saProcessResponse: SETPIT freq %d", saDevice.orfreq); + LOG_DEBUG(VTX, "saProcessResponse: SETPIT freq %d", saDevice.orfreq); } else { saDevice.freq = freq; - LOG_D(VTX, "saProcessResponse: SETFREQ freq %d", freq); + LOG_DEBUG(VTX, "saProcessResponse: SETFREQ freq %d", freq); } break; case SA_CMD_SET_MODE: // Set Mode - LOG_D(VTX, "saProcessResponse: SET_MODE 0x%x, (pir %s, por %s, pitdsbl %s, %s)\r\n", + LOG_DEBUG(VTX, "saProcessResponse: SET_MODE 0x%x, (pir %s, por %s, pitdsbl %s, %s)\r\n", buf[2], (buf[2] & 1) ? "on" : "off", (buf[2] & 2) ? "on" : "off", (buf[3] & 4) ? "on" : "off", (buf[4] & 8) ? "unlocked" : "locked"); break; @@ -595,7 +595,7 @@ static void saGetSettings(void) { static uint8_t bufGetSettings[5] = {0xAA, 0x55, SACMD(SA_CMD_GET_SETTINGS), 0x00, 0x9F}; - LOG_D(VTX, "smartAudioGetSettings\r\n"); + LOG_DEBUG(VTX, "smartAudioGetSettings\r\n"); saQueueCmd(bufGetSettings, 5); } @@ -605,11 +605,11 @@ void saSetFreq(uint16_t freq) static uint8_t switchBuf[7]; if (freq & SA_FREQ_GETPIT) { - LOG_D(VTX, "smartAudioSetFreq: GETPIT"); + LOG_DEBUG(VTX, "smartAudioSetFreq: GETPIT"); } else if (freq & SA_FREQ_SETPIT) { - LOG_D(VTX, "smartAudioSetFreq: SETPIT %d", freq & SA_FREQ_MASK); + LOG_DEBUG(VTX, "smartAudioSetFreq: SETPIT %d", freq & SA_FREQ_MASK); } else { - LOG_D(VTX, "smartAudioSetFreq: SET %d", freq); + LOG_DEBUG(VTX, "smartAudioSetFreq: SET %d", freq); } buf[4] = (freq >> 8) & 0xff; @@ -649,7 +649,7 @@ void saSetBandAndChannel(uint8_t band, uint8_t channel) buf[4] = SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel); buf[5] = CRC8(buf, 5); - LOG_D(VTX, "vtxSASetBandAndChannel set index band %d channel %d value sent 0x%x\r\n", band, channel, buf[4]); + LOG_DEBUG(VTX, "vtxSASetBandAndChannel set index band %d channel %d value sent 0x%x\r\n", band, channel, buf[4]); //this will clear saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ saQueueCmd(buf, 6); @@ -666,7 +666,7 @@ void saSetMode(int mode) //the response will just say pit=off but the device will still go into pitmode on reboot. //therefore we have to memorize this change here. } - LOG_D(VTX, "saSetMode(0x%x): pir=%s por=%s pitdsbl=%s %s\r\n", mode, (mode & 1) ? "on " : "off", (mode & 2) ? "on " : "off", + LOG_DEBUG(VTX, "saSetMode(0x%x): pir=%s por=%s pitdsbl=%s %s\r\n", mode, (mode & 1) ? "on " : "off", (mode & 2) ? "on " : "off", (mode & 4)? "on " : "off", (mode & 8) ? "locked" : "unlocked"); buf[5] = CRC8(buf, 5); @@ -735,7 +735,7 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs) if (saDevice.version >= SA_2_0 ) { //did the device boot up in pit mode on its own? saDevice.willBootIntoPitMode = (saDevice.mode & SA_MODE_GET_PITMODE) ? true : false; - LOG_D(VTX, "sainit: willBootIntoPitMode is %s\r\n", saDevice.willBootIntoPitMode ? "true" : "false"); + LOG_DEBUG(VTX, "sainit: willBootIntoPitMode is %s\r\n", saDevice.willBootIntoPitMode ? "true" : "false"); } } break; @@ -757,17 +757,17 @@ static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs) if ((sa_outstanding != SA_CMD_NONE) && (nowMs - sa_lastTransmissionMs > SMARTAUDIO_CMD_TIMEOUT)) { // Last command timed out - // LOG_D(VTX, "process: resending 0x%x", sa_outstanding); + // LOG_DEBUG(VTX, "process: resending 0x%x", sa_outstanding); // XXX Todo: Resend termination and possible offline transition saResendCmd(); lastCommandSentMs = nowMs; } else if (!saQueueEmpty()) { // Command pending. Send it. - // LOG_D(VTX, "process: sending queue"); + // LOG_DEBUG(VTX, "process: sending queue"); saSendQueue(); lastCommandSentMs = nowMs; } else if ((nowMs - lastCommandSentMs < SMARTAUDIO_POLLING_WINDOW) && (nowMs - sa_lastTransmissionMs >= SMARTAUDIO_POLLING_INTERVAL)) { - //LOG_D(VTX, "process: sending status change polling"); + //LOG_DEBUG(VTX, "process: sending status change polling"); saGetSettings(); saSendQueue(); } @@ -803,16 +803,16 @@ void vtxSASetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channe } if (index == 0) { - LOG_D(VTX, "SmartAudio doesn't support power off"); + LOG_DEBUG(VTX, "SmartAudio doesn't support power off"); return; } if (index > saPowerCount) { - LOG_D(VTX, "Invalid power level"); + LOG_DEBUG(VTX, "Invalid power level"); return; } - LOG_D(VTX, "saSetPowerByIndex: index %d, value %d\r\n", index, buf[4]); + LOG_DEBUG(VTX, "saSetPowerByIndex: index %d, value %d\r\n", index, buf[4]); index--; switch (saDevice.version) { @@ -853,10 +853,10 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff) buf[4] = 0 | 128; buf[5] = CRC8(buf, 5); saQueueCmd(buf, 6); - LOG_D(VTX, "vtxSASetPitMode: set power to 0 dbm\r\n"); + LOG_DEBUG(VTX, "vtxSASetPitMode: set power to 0 dbm\r\n"); } else { saSetMode(SA_MODE_CLR_PITMODE); - LOG_D(VTX, "vtxSASetPitMode: clear pitmode permanently"); + LOG_DEBUG(VTX, "vtxSASetPitMode: clear pitmode permanently"); } return; } @@ -871,7 +871,7 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff) // ensure when turning on pit mode that pit mode gets actually enabled newMode |= SA_MODE_SET_IN_RANGE_PITMODE; } - LOG_D(VTX, "vtxSASetPitMode %s with stored mode 0x%x por %s, pir %s, newMode 0x%x\r\n", onoff ? "on" : "off", saDevice.mode, + LOG_DEBUG(VTX, "vtxSASetPitMode %s with stored mode 0x%x por %s, pir %s, newMode 0x%x\r\n", onoff ? "on" : "off", saDevice.mode, (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE) ? "on" : "off", (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) ? "on" : "off" , newMode); diff --git a/src/main/msc/emfat_file.c b/src/main/msc/emfat_file.c index c6bad38a26..6fc99a1423 100644 --- a/src/main/msc/emfat_file.c +++ b/src/main/msc/emfat_file.c @@ -42,7 +42,7 @@ static const char autorun_file[] = "[autorun]\r\n" "icon=icon.ico\r\n" - "label=iNav Onboard Flash\r\n" ; + "label=INAV Onboard Flash\r\n" ; #define AUTORUN_SIZE (sizeof(autorun_file) - 1) #define EMFAT_INCR_AUTORUN 1 #else diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index e14403ff2c..a6ba0c891d 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -15,7 +15,7 @@ * along with INAV. If not, see . */ -// iNav specific IDs start from 0x2000 +// INAV specific IDs start from 0x2000 // See https://github.com/iNavFlight/inav/wiki/MSP-V2#msp-v2-message-catalogue #define MSP2_INAV_STATUS 0x2000 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 5917ed16cb..6eaf8cec53 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -40,6 +40,7 @@ #include "fc/rc_modes.h" #include "fc/runtime_config.h" #ifdef USE_MULTI_MISSION +#include "fc/rc_adjustments.h" #include "fc/cli.h" #endif #include "fc/settings.h" @@ -98,7 +99,7 @@ STATIC_ASSERT(NAV_MAX_WAYPOINTS < 254, NAV_MAX_WAYPOINTS_exceeded_allowable_rang PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 2); #endif -PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(navConfig_t, navConfig, PG_NAV_CONFIG, 3); PG_RESET_TEMPLATE(navConfig_t, navConfig, .general = { @@ -126,7 +127,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, // General navigation parameters .pos_failure_timeout = SETTING_NAV_POSITION_TIMEOUT_DEFAULT, // 5 sec .waypoint_radius = SETTING_NAV_WP_RADIUS_DEFAULT, // 2m diameter - .waypoint_safe_distance = SETTING_NAV_WP_SAFE_DISTANCE_DEFAULT, // centimeters - first waypoint should be closer than this + .waypoint_safe_distance = SETTING_NAV_WP_MAX_SAFE_DISTANCE_DEFAULT, // Metres - first waypoint should be closer than this #ifdef USE_MULTI_MISSION .waypoint_multi_mission_index = SETTING_NAV_WP_MULTI_MISSION_INDEX_DEFAULT, // mission index selected from multi mission WP entry #endif @@ -151,12 +152,13 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .max_altitude = SETTING_NAV_MAX_ALTITUDE_DEFAULT, .rth_trackback_distance = SETTING_NAV_RTH_TRACKBACK_DISTANCE_DEFAULT, // Max distance allowed for RTH trackback .waypoint_enforce_altitude = SETTING_NAV_WP_ENFORCE_ALTITUDE_DEFAULT, // Forces set wp altitude to be achieved + .land_detect_sensitivity = SETTING_NAV_LAND_DETECT_SENSITIVITY_DEFAULT, // Changes sensitivity of landing detection + .auto_disarm_delay = SETTING_NAV_AUTO_DISARM_DELAY_DEFAULT, // 2000 ms - time delay to disarm when auto disarm after landing enabled }, // MC-specific .mc = { .max_bank_angle = SETTING_NAV_MC_BANK_ANGLE_DEFAULT, // degrees - .auto_disarm_delay = SETTING_NAV_MC_AUTO_DISARM_DELAY_DEFAULT, // milliseconds - time before disarming when auto disarm is enabled and landing is confirmed #ifdef USE_MR_BRAKING_MODE .braking_speed_threshold = SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT, // Braking can become active above 1m/s @@ -183,7 +185,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .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_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT, //Fixed wing landing .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default @@ -203,21 +207,23 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .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 .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 CR67 + .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 } ); +/* NAV variables */ static navWapointHeading_t wpHeadingControl; -navigationPosControl_t posControl; -navSystemStatus_t NAV_Status; +navigationPosControl_t posControl; +navSystemStatus_t NAV_Status; + EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients; // Blackbox states @@ -657,7 +663,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_RTH_FINISHING, .onEntry = navOnEnteringState_NAV_STATE_RTH_FINISHING, .timeoutMs = 0, - .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, + .stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_CTL_LAND | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE, .mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwError = MW_NAV_ERROR_LANDING, @@ -671,7 +677,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = { .persistentId = NAV_PERSISTENT_ID_RTH_FINISHED, .onEntry = navOnEnteringState_NAV_STATE_RTH_FINISHED, .timeoutMs = 10, - .stateFlags = NAV_CTL_ALT | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, + .stateFlags = NAV_CTL_ALT | NAV_CTL_LAND | NAV_REQUIRE_ANGLE | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH, .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE, .mwState = MW_NAV_STATE_LANDED, .mwError = MW_NAV_ERROR_NONE, @@ -1462,6 +1468,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF } float descentVelLimited = 0; + int32_t landingElevation = posControl.rthState.homeTmpWaypoint.z; // A safeguard - if surface altitude sensors is available and it is reading < 50cm altitude - drop to low descend speed if ((posControl.flags.estAglStatus == EST_TRUSTED) && posControl.actualState.agl.pos.z < 50.0f) { @@ -1471,8 +1478,9 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_LANDING(navigationF } else { // Ramp down descent velocity from 100% at maxAlt altitude to 25% from minAlt to 0cm. float descentVelScaled = scaleRangef(navGetCurrentActualPositionAndVelocity()->pos.z, - navConfig()->general.land_slowdown_minalt, navConfig()->general.land_slowdown_maxalt, - navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd); + navConfig()->general.land_slowdown_minalt + landingElevation, + navConfig()->general.land_slowdown_maxalt + landingElevation, + navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd); descentVelLimited = constrainf(descentVelScaled, navConfig()->general.land_minalt_vspd, navConfig()->general.land_maxalt_vspd); } @@ -1526,14 +1534,14 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_INITIALIZE(nav Use p3 as the volatile jump counter, allowing embedded, rearmed jumps Using p3 minimises the risk of saving an invalid counter if a mission is aborted. */ - if (posControl.activeWaypointIndex == 0 || posControl.wpMissionRestart) { + if (posControl.activeWaypointIndex == posControl.startWpIndex || posControl.wpMissionRestart) { setupJumpCounters(); - posControl.activeWaypointIndex = 0; + posControl.activeWaypointIndex = posControl.startWpIndex; wpHeadingControl.mode = NAV_WP_HEAD_MODE_NONE; } if (navConfig()->general.flags.waypoint_mission_restart == WP_MISSION_SWITCH) { - posControl.wpMissionRestart = posControl.activeWaypointIndex ? !posControl.wpMissionRestart : false; + posControl.wpMissionRestart = posControl.activeWaypointIndex > posControl.startWpIndex ? !posControl.wpMissionRestart : false; } else { posControl.wpMissionRestart = navConfig()->general.flags.waypoint_mission_restart == WP_MISSION_START; } @@ -1544,14 +1552,10 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_INITIALIZE(nav static navigationFSMEvent_t nextForNonGeoStates(void) { - /* simple helper for non-geographical states that just set other data */ - const bool isLastWaypoint = (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST) || (posControl.activeWaypointIndex >= (posControl.waypointCount - 1)); - - if (isLastWaypoint) { - // non-geo state is the last waypoint, switch to finish. + /* simple helper for non-geographical states that just set other data */ + if (isLastMissionWaypoint()) { // non-geo state is the last waypoint, switch to finish. return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; - } else { - // Finished non-geo, move to next WP + } else { // Finished non-geo, move to next WP posControl.activeWaypointIndex++; return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP } @@ -1574,8 +1578,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav // We use p3 as the volatile jump counter (p2 is the static value) case NAV_WP_ACTION_JUMP: - if(posControl.waypointList[posControl.activeWaypointIndex].p3 != -1){ - if(posControl.waypointList[posControl.activeWaypointIndex].p3 == 0){ + if (posControl.waypointList[posControl.activeWaypointIndex].p3 != -1) { + if (posControl.waypointList[posControl.activeWaypointIndex].p3 == 0) { resetJumpCounter(); return nextForNonGeoStates(); } @@ -1584,7 +1588,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav posControl.waypointList[posControl.activeWaypointIndex].p3--; } } - posControl.activeWaypointIndex = posControl.waypointList[posControl.activeWaypointIndex].p1; + posControl.activeWaypointIndex = posControl.waypointList[posControl.activeWaypointIndex].p1 + posControl.startWpIndex; return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP case NAV_WP_ACTION_SET_POI: @@ -1809,8 +1813,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_EMERGENCY_LANDING_FINIS { UNUSED(previousState); - rcCommand[THROTTLE] = getThrottleIdleValue(); - ENABLE_STATE(NAV_MOTOR_STOP_OR_IDLE); + disarm(DISARM_NAVIGATION); return NAV_FSM_EVENT_NONE; } @@ -1931,7 +1934,7 @@ static void navProcessFSMEvents(navigationFSMEvent_t injectedEvent) if (posControl.flags.isAdjustingPosition) NAV_Status.flags |= MW_NAV_FLAG_ADJUSTING_POSITION; if (posControl.flags.isAdjustingAltitude) NAV_Status.flags |= MW_NAV_FLAG_ADJUSTING_ALTITUDE; - NAV_Status.activeWpNumber = posControl.activeWaypointIndex + 1; + NAV_Status.activeWpNumber = posControl.activeWaypointIndex - posControl.startWpIndex + 1; NAV_Status.activeWpAction = 0; if ((posControl.activeWaypointIndex >= 0) && (posControl.activeWaypointIndex < NAV_MAX_WAYPOINTS)) { NAV_Status.activeWpAction = posControl.waypointList[posControl.activeWaypointIndex].action; @@ -2116,7 +2119,7 @@ void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, flo /*----------------------------------------------------------- * Processes an update to estimated heading *-----------------------------------------------------------*/ -void updateActualHeading(bool headingValid, int32_t newHeading) +void updateActualHeading(bool headingValid, int32_t newHeading, int32_t newGroundCourse) { /* Update heading. Check if we're acquiring a valid heading for the * first time and update home heading accordingly. @@ -2147,7 +2150,9 @@ void updateActualHeading(bool headingValid, int32_t newHeading) } posControl.rthState.homeFlags |= NAV_HOME_VALID_HEADING; } + /* Use course over ground for fixed wing nav "heading" when valid - TODO use heading and cog as specifically required for FW and MR */ posControl.actualState.yaw = newHeading; + posControl.actualState.cog = newGroundCourse; // currently only used for OSD display posControl.flags.estHeadingStatus = newEstHeading; /* Precompute sin/cos of yaw angle */ @@ -2222,7 +2227,7 @@ bool navCalculatePathToDestination(navDestinationPath_t *result, const fpVector3 static bool getLocalPosNextWaypoint(fpVector3_t * nextWpPos) { // Only for WP Mode not Trackback. Ignore non geo waypoints except RTH and JUMP. - if (FLIGHT_MODE(NAV_WP_MODE) && !isLastMissionWaypoint()) { + if (navGetStateFlags(posControl.navState) & NAV_AUTO_WP && !isLastMissionWaypoint()) { navWaypointActions_e nextWpAction = posControl.waypointList[posControl.activeWaypointIndex + 1].action; if (!(nextWpAction == NAV_WP_ACTION_SET_POI || nextWpAction == NAV_WP_ACTION_SET_HEAD)) { @@ -2230,8 +2235,8 @@ static bool getLocalPosNextWaypoint(fpVector3_t * nextWpPos) if (nextWpAction == NAV_WP_ACTION_JUMP) { if (posControl.waypointList[posControl.activeWaypointIndex + 1].p3 != 0 || posControl.waypointList[posControl.activeWaypointIndex + 1].p2 == -1) { - nextWpIndex = posControl.waypointList[posControl.activeWaypointIndex + 1].p1; - } else if (posControl.activeWaypointIndex + 2 <= posControl.waypointCount - 1) { + nextWpIndex = posControl.waypointList[posControl.activeWaypointIndex + 1].p1 + posControl.startWpIndex; + } else if (posControl.activeWaypointIndex + 2 <= posControl.startWpIndex + posControl.waypointCount - 1) { if (posControl.waypointList[posControl.activeWaypointIndex + 2].action != NAV_WP_ACTION_JUMP) { nextWpIndex++; } else { @@ -2262,6 +2267,11 @@ static bool isWaypointReached(const fpVector3_t * waypointPos, const int32_t * w } if (navGetStateFlags(posControl.navState) & NAV_AUTO_WP || posControl.flags.rthTrackbackActive) { + // If WP turn smoothing CUT option used WP is reached when start of turn is initiated + if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_CUT && posControl.flags.wpTurnSmoothingActive) { + posControl.flags.wpTurnSmoothingActive = false; + return true; + } // Check if waypoint was missed based on bearing to WP exceeding 100 degrees relative to waypoint Yaw // Same method for turn smoothing option but relative bearing set at 60 degrees uint16_t relativeBearing = posControl.flags.wpTurnSmoothingActive ? 6000 : 10000; @@ -2648,10 +2658,17 @@ static bool rthAltControlStickOverrideCheck(unsigned axis) * Reverts to normal RTH heading direct to home when end of track reached. * Trackpoints logged with precedence for course/altitude changes. Distance based changes * only logged if no course/altitude changes logged over an extended distance. + * Tracking suspended during fixed wing loiter (PosHold and WP Mode timed hold). * --------------------------------------------------------------------------------- */ static void updateRthTrackback(bool forceSaveTrackPoint) { - if (navConfig()->general.flags.rth_trackback_mode == RTH_TRACKBACK_OFF || FLIGHT_MODE(NAV_RTH_MODE) || !ARMING_FLAG(ARMED)) { + static bool suspendTracking = false; + bool fwLoiterIsActive = STATE(AIRPLANE) && (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED || FLIGHT_MODE(NAV_POSHOLD_MODE)); + if (!fwLoiterIsActive && suspendTracking) { + suspendTracking = false; + } + + if (navConfig()->general.flags.rth_trackback_mode == RTH_TRACKBACK_OFF || FLIGHT_MODE(NAV_RTH_MODE) || !ARMING_FLAG(ARMED || suspendTracking)) { return; } @@ -2700,6 +2717,11 @@ static bool rthAltControlStickOverrideCheck(unsigned axis) saveTrackpoint = calculateDistanceToDestination(&posControl.rthTBPointsList[posControl.activeRthTBPointIndex]) > METERS_TO_CENTIMETERS(20); previousTBTripDist = posControl.totalTripDistance; } + + // Suspend tracking during loiter on fixed wing. Save trackpoint at start of loiter. + if (distanceCounter && fwLoiterIsActive) { + saveTrackpoint = suspendTracking = true; + } } // when trackpoint store full, overwrite from start of store using 'rthTBWrapAroundCounter' to track overwrite position @@ -2899,9 +2921,16 @@ void updateClimbRateToAltitudeController(float desiredClimbRate, climbRateToAlti // Fixed wing climb rate controller is open-loop. We simply move the known altitude target float timeDelta = US2S(currentTimeUs - lastUpdateTimeUs); - if (timeDelta <= HZ2S(MIN_POSITION_UPDATE_RATE_HZ)) { - posControl.desiredState.pos.z += desiredClimbRate * timeDelta; - posControl.desiredState.pos.z = constrainf(posControl.desiredState.pos.z, altitudeToUse - 500, altitudeToUse + 500); // FIXME: calculate sanity limits in a smarter way + if (timeDelta <= HZ2S(MIN_POSITION_UPDATE_RATE_HZ) && desiredClimbRate) { + static bool targetHoldActive = false; + // Update target altitude only if actual altitude moving in same direction and lagging by < 5 m, otherwise hold target + if (navGetCurrentActualPositionAndVelocity()->vel.z * desiredClimbRate >= 0 && fabsf(posControl.desiredState.pos.z - altitudeToUse) < 500) { + posControl.desiredState.pos.z += desiredClimbRate * timeDelta; + targetHoldActive = false; + } else if (!targetHoldActive) { // Reset and hold target to actual + climb rate boost until actual catches up + posControl.desiredState.pos.z = altitudeToUse + desiredClimbRate; + targetHoldActive = true; + } } } else { @@ -2951,7 +2980,7 @@ static bool adjustAltitudeFromRCInput(void) *-----------------------------------------------------------*/ static void setupJumpCounters(void) { - for (uint8_t wp = 0; wp < posControl.waypointCount ; wp++) { + for (uint8_t wp = posControl.startWpIndex; wp < posControl.waypointCount + posControl.startWpIndex; wp++) { if (posControl.waypointList[wp].action == NAV_WP_ACTION_JUMP){ posControl.waypointList[wp].p3 = posControl.waypointList[wp].p2; } @@ -2961,13 +2990,12 @@ static void setupJumpCounters(void) static void resetJumpCounter(void) { // reset the volatile counter from the set / static value - posControl.waypointList[posControl.activeWaypointIndex].p3 = - posControl.waypointList[posControl.activeWaypointIndex].p2; + posControl.waypointList[posControl.activeWaypointIndex].p3 = posControl.waypointList[posControl.activeWaypointIndex].p2; } static void clearJumpCounters(void) { - for (uint8_t wp = 0; wp < posControl.waypointCount ; wp++) { + for (uint8_t wp = posControl.startWpIndex; wp < posControl.waypointCount + posControl.startWpIndex; wp++) { if (posControl.waypointList[wp].action == NAV_WP_ACTION_JUMP) { posControl.waypointList[wp].p3 = 0; } @@ -3086,12 +3114,11 @@ void getWaypoint(uint8_t wpNumber, navWaypoint_t * wpData) } // WP #1 - #60 - common waypoints - pre-programmed mission else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS)) { - if (wpNumber <= posControl.waypointCount) { - *wpData = posControl.waypointList[wpNumber - 1]; + if (wpNumber <= getWaypointCount()) { + *wpData = posControl.waypointList[wpNumber - 1 + (ARMING_FLAG(ARMED) ? posControl.startWpIndex : 0)]; if(wpData->action == NAV_WP_ACTION_JUMP) { wpData->p1 += 1; // make WP # (vice index) } - } } } @@ -3164,17 +3191,15 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) void resetWaypointList(void) { - /* Can only reset waypoint list if not armed */ - if (!ARMING_FLAG(ARMED)) { - posControl.waypointCount = 0; - posControl.waypointListValid = false; - posControl.geoWaypointCount = 0; + posControl.waypointCount = 0; + posControl.waypointListValid = false; + posControl.geoWaypointCount = 0; + posControl.startWpIndex = 0; #ifdef USE_MULTI_MISSION - posControl.loadedMultiMissionIndex = 0; - posControl.loadedMultiMissionStartWP = 0; - posControl.loadedMultiMissionWPCount = 0; + posControl.totalMultiMissionWpCount = 0; + posControl.loadedMultiMissionIndex = 0; + posControl.multiMissionCount = 0; #endif - } } bool isWaypointListValid(void) @@ -3184,31 +3209,85 @@ bool isWaypointListValid(void) int getWaypointCount(void) { - return posControl.waypointCount; + uint8_t waypointCount = posControl.waypointCount; +#ifdef USE_MULTI_MISSION + if (!ARMING_FLAG(ARMED) && posControl.totalMultiMissionWpCount) { + waypointCount = posControl.totalMultiMissionWpCount; + } +#endif + return waypointCount; } + #ifdef USE_MULTI_MISSION void selectMultiMissionIndex(int8_t increment) { if (posControl.multiMissionCount > 1) { // stick selection only active when multi mission loaded - navConfigMutable()->general.waypoint_multi_mission_index = constrain(navConfigMutable()->general.waypoint_multi_mission_index + increment, 0, posControl.multiMissionCount); + navConfigMutable()->general.waypoint_multi_mission_index = constrain(navConfigMutable()->general.waypoint_multi_mission_index + increment, 1, posControl.multiMissionCount); } } -void setMultiMissionOnArm(void) +void loadSelectedMultiMission(uint8_t missionIndex) { - if (posControl.multiMissionCount > 1 && posControl.loadedMultiMissionWPCount) { - posControl.waypointCount = posControl.loadedMultiMissionWPCount; + uint8_t missionCount = 1; + posControl.waypointCount = 0; + posControl.geoWaypointCount = 0; - for (int8_t i = 0; i < NAV_MAX_WAYPOINTS; i++) { - posControl.waypointList[i] = posControl.waypointList[i + posControl.loadedMultiMissionStartWP]; - if (i == posControl.waypointCount - 1) { + for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) { + if ((missionCount == missionIndex)) { + /* store details of selected mission: start wp index, mission wp count, geo wp count */ + if (!(posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || + posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || + posControl.waypointList[i].action == NAV_WP_ACTION_JUMP)) { + posControl.geoWaypointCount++; + } + // mission start WP + if (posControl.waypointCount == 0) { + posControl.waypointCount = 1; // start marker only, value unimportant (but not 0) + posControl.startWpIndex = i; + } + // mission end WP + if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) { + posControl.waypointCount = i - posControl.startWpIndex + 1; break; } + } else if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) { + missionCount++; } - - posControl.loadedMultiMissionStartWP = 0; - posControl.loadedMultiMissionWPCount = 0; } + + posControl.loadedMultiMissionIndex = posControl.multiMissionCount ? missionIndex : 0; + posControl.activeWaypointIndex = posControl.startWpIndex; +} + +bool updateWpMissionChange(void) +{ + /* Function only called when ARMED */ + + if (posControl.multiMissionCount < 2 || posControl.wpPlannerActiveWPIndex || FLIGHT_MODE(NAV_WP_MODE)) { + return true; + } + + uint8_t setMissionIndex = navConfig()->general.waypoint_multi_mission_index; + if (!(IS_RC_MODE_ACTIVE(BOXCHANGEMISSION) || isAdjustmentFunctionSelected(ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX))) { + /* reload mission if mission index changed */ + if (posControl.loadedMultiMissionIndex != setMissionIndex) { + loadSelectedMultiMission(setMissionIndex); + } + return true; + } + + static bool toggleFlag = false; + if (IS_RC_MODE_ACTIVE(BOXNAVWP) && toggleFlag) { + if (setMissionIndex == posControl.multiMissionCount) { + navConfigMutable()->general.waypoint_multi_mission_index = 1; + } else { + selectMultiMissionIndex(1); + } + toggleFlag = false; + } else if (!IS_RC_MODE_ACTIVE(BOXNAVWP)) { + toggleFlag = true; + } + return false; // block WP mode while changing mission when armed } bool checkMissionCount(int8_t waypoint) @@ -3227,13 +3306,8 @@ bool checkMissionCount(int8_t waypoint) #ifdef NAV_NON_VOLATILE_WAYPOINT_STORAGE bool loadNonVolatileWaypointList(bool clearIfLoaded) { -#ifdef USE_MULTI_MISSION - /* multi_mission_index 0 only used for non NVM missions - don't load. - * Don't load if mission planner WP count > 0 */ - if (ARMING_FLAG(ARMED) || !navConfig()->general.waypoint_multi_mission_index || posControl.wpPlannerActiveWPIndex) { -#else + /* Don't load if armed or mission planner active */ if (ARMING_FLAG(ARMED) || posControl.wpPlannerActiveWPIndex) { -#endif return false; } @@ -3247,46 +3321,28 @@ bool loadNonVolatileWaypointList(bool clearIfLoaded) if (navConfig()->general.waypoint_multi_mission_index > posControl.multiMissionCount) { navConfigMutable()->general.waypoint_multi_mission_index = 1; } - posControl.multiMissionCount = 0; - posControl.loadedMultiMissionWPCount = 0; - int8_t loadedMultiMissionGeoWPCount; #endif for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) { setWaypoint(i + 1, nonVolatileWaypointList(i)); #ifdef USE_MULTI_MISSION - /* store details of selected mission */ - if ((posControl.multiMissionCount + 1 == navConfig()->general.waypoint_multi_mission_index)) { - // mission start WP - if (posControl.loadedMultiMissionWPCount == 0) { - posControl.loadedMultiMissionWPCount = 1; // start marker only, value here unimportant (but not 0) - posControl.loadedMultiMissionStartWP = i; - loadedMultiMissionGeoWPCount = posControl.geoWaypointCount; - } - // mission end WP - if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) { - posControl.loadedMultiMissionWPCount = i - posControl.loadedMultiMissionStartWP + 1; - loadedMultiMissionGeoWPCount = posControl.geoWaypointCount - loadedMultiMissionGeoWPCount + 1; - } - } - - /* count up number of missions */ + /* count up number of missions and exit after last multi mission */ if (checkMissionCount(i)) { break; } } - - posControl.geoWaypointCount = loadedMultiMissionGeoWPCount; - posControl.loadedMultiMissionIndex = posControl.multiMissionCount ? navConfig()->general.waypoint_multi_mission_index : 0; + posControl.totalMultiMissionWpCount = posControl.waypointCount; + loadSelectedMultiMission(navConfig()->general.waypoint_multi_mission_index); /* Mission sanity check failed - reset the list * Also reset if no selected mission loaded (shouldn't happen) */ - if (!posControl.waypointListValid || !posControl.loadedMultiMissionWPCount) { + if (!posControl.waypointListValid || !posControl.waypointCount) { #else // check this is the last waypoint if (nonVolatileWaypointList(i)->flag == NAV_WP_FLAG_LAST) { break; } } + // Mission sanity check failed - reset the list if (!posControl.waypointListValid) { #endif @@ -3357,7 +3413,7 @@ static void calculateAndSetActiveWaypointToLocalPosition(const fpVector3_t * pos geoAltitudeConversionMode_e waypointMissionAltConvMode(geoAltitudeDatumFlag_e datumFlag) { - return datumFlag == NAV_WP_MSL_DATUM ? GEO_ALT_ABSOLUTE : GEO_ALT_RELATIVE; + return ((datumFlag & NAV_WP_MSL_DATUM) == NAV_WP_MSL_DATUM) ? GEO_ALT_ABSOLUTE : GEO_ALT_RELATIVE; } static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint) @@ -3378,7 +3434,7 @@ static void calculateAndSetActiveWaypoint(const navWaypoint_t * waypoint) /* Checks if active waypoint is last in mission */ bool isLastMissionWaypoint(void) { - return FLIGHT_MODE(NAV_WP_MODE) && (posControl.activeWaypointIndex >= (posControl.waypointCount - 1) || + return FLIGHT_MODE(NAV_WP_MODE) && (posControl.activeWaypointIndex >= (posControl.startWpIndex + posControl.waypointCount - 1) || (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST)); } @@ -3490,7 +3546,7 @@ void applyWaypointNavigationAndAltitudeHold(void) posControl.flags.forcedRTHActivated = false; posControl.flags.forcedEmergLandingActivated = false; // ensure WP missions always restart from first waypoint after disarm - posControl.activeWaypointIndex = 0; + posControl.activeWaypointIndex = posControl.startWpIndex; // Reset RTH trackback posControl.activeRthTBPointIndex = -1; posControl.flags.rthTrackbackActive = false; @@ -3680,7 +3736,12 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) // Pilot-activated waypoint mission. Fall-back to RTH in case of no mission loaded // Block activation if using WP Mission Planner + // Also check multimission mission change status before activating WP mode +#ifdef USE_MULTI_MISSION + if (updateWpMissionChange() && IS_RC_MODE_ACTIVE(BOXNAVWP) && !posControl.flags.wpMissionPlannerActive) { +#else if (IS_RC_MODE_ACTIVE(BOXNAVWP) && !posControl.flags.wpMissionPlannerActive) { +#endif if (FLIGHT_MODE(NAV_WP_MODE) || (canActivateWaypoint && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT; } @@ -3791,11 +3852,7 @@ bool navigationTerrainFollowingEnabled(void) uint32_t distanceToFirstWP(void) { fpVector3_t startingWaypointPos; -#ifdef USE_MULTI_MISSION - mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[posControl.loadedMultiMissionStartWP], GEO_ALT_RELATIVE); -#else - mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[0], GEO_ALT_RELATIVE); -#endif + mapWaypointToLocalPosition(&startingWaypointPos, &posControl.waypointList[posControl.startWpIndex], GEO_ALT_RELATIVE); return calculateDistanceToDestination(&startingWaypointPos); } @@ -3832,7 +3889,7 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) // Don't allow arming if first waypoint is farther than configured safe distance if ((posControl.waypointCount > 0) && (navConfig()->general.waypoint_safe_distance != 0)) { - if (distanceToFirstWP() > navConfig()->general.waypoint_safe_distance && !checkStickPosition(YAW_HI)) { + if (distanceToFirstWP() > METERS_TO_CENTIMETERS(navConfig()->general.waypoint_safe_distance) && !checkStickPosition(YAW_HI)) { return NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR; } } @@ -3844,20 +3901,17 @@ navArmingBlocker_e navigationIsBlockingArming(bool *usedBypass) * Can't jump beyond WP list * Only jump to geo-referenced WP types */ -#ifdef USE_MULTI_MISSION - // Only perform check when mission loaded at start of posControl.waypointList - if (posControl.waypointCount && !posControl.loadedMultiMissionStartWP) { -#else if (posControl.waypointCount) { -#endif - for (uint8_t wp = 0; wp < posControl.waypointCount; wp++){ + for (uint8_t wp = posControl.startWpIndex; wp < posControl.waypointCount + posControl.startWpIndex; wp++){ if (posControl.waypointList[wp].action == NAV_WP_ACTION_JUMP){ - if((wp == 0) || ((posControl.waypointList[wp].p1 > (wp-2)) && (posControl.waypointList[wp].p1 < (wp+2)) ) || (posControl.waypointList[wp].p1 >= posControl.waypointCount) || (posControl.waypointList[wp].p2 < -1)) { + if (wp == posControl.startWpIndex || posControl.waypointList[wp].p1 >= posControl.waypointCount || + (posControl.waypointList[wp].p1 > (wp - posControl.startWpIndex - 2) && posControl.waypointList[wp].p1 < (wp - posControl.startWpIndex + 2)) || posControl.waypointList[wp].p2 < -1) { return NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR; } + /* check for target geo-ref sanity */ - uint16_t target = posControl.waypointList[wp].p1; - if(!(posControl.waypointList[target].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[target].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[target].action == NAV_WP_ACTION_LAND)) { + uint16_t target = posControl.waypointList[wp].p1 + posControl.startWpIndex; + if (!(posControl.waypointList[target].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[target].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[target].action == NAV_WP_ACTION_LAND)) { return NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR; } } @@ -3941,7 +3995,7 @@ void missionPlannerSetWaypoint(void) posControl.waypointList[posControl.wpPlannerActiveWPIndex].lon = wpLLH.lon; posControl.waypointList[posControl.wpPlannerActiveWPIndex].alt = wpLLH.alt; posControl.waypointList[posControl.wpPlannerActiveWPIndex].p1 = posControl.waypointList[posControl.wpPlannerActiveWPIndex].p2 = 0; - posControl.waypointList[posControl.wpPlannerActiveWPIndex].p3 = 1; // use absolute altitude datum + posControl.waypointList[posControl.wpPlannerActiveWPIndex].p3 |= NAV_WP_ALTMODE; // use absolute altitude datum posControl.waypointList[posControl.wpPlannerActiveWPIndex].flag = NAV_WP_FLAG_LAST; posControl.waypointListValid = true; @@ -4112,9 +4166,9 @@ void navigationInit(void) posControl.waypointListValid = false; posControl.wpPlannerActiveWPIndex = 0; posControl.flags.wpMissionPlannerActive = false; + posControl.startWpIndex = 0; #ifdef USE_MULTI_MISSION posControl.multiMissionCount = 0; - posControl.loadedMultiMissionStartWP = 0; #endif /* Set initial surface invalid */ posControl.actualState.surfaceMin = -1.0f; @@ -4274,7 +4328,7 @@ bool navigationRTHAllowsLanding(void) { // WP mission RTH landing setting if (isWaypointMissionRTHActive() && isWaypointMissionValid()) { - return posControl.waypointList[posControl.waypointCount - 1].p1 > 0; + return posControl.waypointList[posControl.startWpIndex + posControl.waypointCount - 1].p1 > 0; } // normal RTH landing setting @@ -4291,8 +4345,7 @@ bool isNavLaunchEnabled(void) bool abortLaunchAllowed(void) { // allow NAV_LAUNCH_MODE to be aborted if throttle is low or throttle stick position is < launch idle throttle setting - throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); - return throttleStatus == THROTTLE_LOW || throttleStickMixedValue() < currentBatteryProfile->nav.fw.launch_idle_throttle; + return throttleStickIsLow() || throttleStickMixedValue() < currentBatteryProfile->nav.fw.launch_idle_throttle; } int32_t navigationGetHomeHeading(void) diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 0b0a393a46..a9d07e3b41 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -265,11 +265,12 @@ typedef struct navConfig_s { uint16_t max_altitude; // Max altitude when in AltHold mode (not Surface Following) uint16_t rth_trackback_distance; // RTH trackback maximum distance [m] uint16_t waypoint_enforce_altitude; // Forces waypoint altitude to be achieved + uint8_t land_detect_sensitivity; // Sensitivity of landing detector + uint16_t auto_disarm_delay; // safety time delay for landing detector } general; struct { uint8_t max_bank_angle; // multicopter max banking angle (deg) - uint16_t auto_disarm_delay; // multicopter safety delay for landing detector #ifdef USE_MR_BRAKING_MODE uint16_t braking_speed_threshold; // above this speed braking routine might kick in @@ -292,11 +293,13 @@ typedef struct navConfig_s { uint8_t max_climb_angle; // Fixed wing max banking angle (deg) uint8_t max_dive_angle; // Fixed wing max banking angle (deg) uint16_t cruise_speed; // Speed at cruise throttle (cm/s), used for time/distance left before RTH - uint8_t control_smoothness; // The amount of smoothing to apply to controls for navigation + uint8_t control_smoothness; // The amount of smoothing to apply to controls for navigation uint16_t pitch_to_throttle_smooth; // How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh. uint8_t pitch_to_throttle_thresh; // Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees] + uint16_t minThrottleDownPitchAngle; // Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle. [decidegrees] uint16_t loiter_radius; // Loiter radius when executing PH on a fixed wing - int8_t land_dive_angle; + uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise) + int8_t land_dive_angle; uint16_t launch_velocity_thresh; // Velocity threshold for swing launch detection uint16_t launch_accel_thresh; // Acceleration threshold for launch detection (cm/s/s) uint16_t launch_time_thresh; // Time threshold for launch detection (ms) @@ -316,7 +319,6 @@ typedef struct navConfig_s { bool useFwNavYawControl; uint8_t yawControlDeadband; uint8_t soaring_pitch_deadband; // soaring mode pitch angle deadband (deg) - uint16_t auto_disarm_delay; // fixed wing disarm delay for landing detector uint8_t wp_tracking_accuracy; // fixed wing tracking accuracy response factor uint8_t wp_tracking_max_angle; // fixed wing tracking accuracy max alignment angle [degs] uint8_t wp_turn_smoothing; // WP mission turn smoothing options @@ -354,6 +356,15 @@ typedef enum { NAV_WP_FLAG_LAST = 0xA5 } navWaypointFlags_e; +/* A reminder that P3 is a bitfield */ +typedef enum { + NAV_WP_ALTMODE = (1<<0), + NAV_WP_USER1 = (1<<1), + NAV_WP_USER2 = (1<<2), + NAV_WP_USER3 = (1<<3), + NAV_WP_USER4 = (1<<4) +} navWaypointP3Flags_e; + typedef struct { int32_t lat; int32_t lon; @@ -517,7 +528,6 @@ bool loadNonVolatileWaypointList(bool clearIfLoaded); bool saveNonVolatileWaypointList(void); #ifdef USE_MULTI_MISSION void selectMultiMissionIndex(int8_t increment); -void setMultiMissionOnArm(void); #endif float getFinalRTHAltitude(void); int16_t fixedWingPitchToThrottleCorrection(int16_t pitch, timeUs_t currentTimeUs); @@ -601,6 +611,7 @@ void updateLandingStatus(void); const navigationPIDControllers_t* getNavigationPIDControllers(void); int32_t navigationGetHeadingError(void); +float navigationGetCrossTrackError(void); int32_t getCruiseHeadingAdjustment(void); bool isAdjustingPosition(void); bool isAdjustingHeading(void); diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 7bb14df80b..452966856e 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -72,6 +72,7 @@ static bool isYawAdjustmentValid = false; static float throttleSpeedAdjustment = 0; static bool isAutoThrottleManuallyIncreased = false; static int32_t navHeadingError; +static float navCrossTrackError; static int8_t loiterDirYaw = 1; bool needToCalculateCircularLoiter; @@ -240,11 +241,11 @@ void resetFixedWingPositionController(void) static int8_t loiterDirection(void) { int8_t dir = 1; //NAV_LOITER_RIGHT - if (pidProfile()->loiter_direction == NAV_LOITER_LEFT) { + if (navConfig()->fw.loiter_direction == NAV_LOITER_LEFT) { dir = -1; } - if (pidProfile()->loiter_direction == NAV_LOITER_YAW) { + if (navConfig()->fw.loiter_direction == NAV_LOITER_YAW) { if (rcCommand[YAW] < -250) { loiterDirYaw = 1; //RIGHT //yaw is contrariwise @@ -285,30 +286,28 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) (distanceToActualTarget <= (navLoiterRadius / TAN_15DEG)) && (distanceToActualTarget > 50.0f); - /* WP turn smoothing option - switches to loiter path around waypoint using navLoiterRadius. + /* WP turn smoothing with 2 options, 1: pass through WP, 2: cut inside turn missing WP + * Works for turns > 30 degs and < 160 degs. + * Option 1 switches to loiter path around waypoint using navLoiterRadius. * Loiter centered on point inside turn at required distance from waypoint and * on a bearing midway between current and next waypoint course bearings. - * Works for turns > 30 degs and < 120 degs. - * 2 options, 1 = pass through WP, 2 = cut inside turn missing WP */ + * Option 2 simply uses a normal turn once the turn initiation point is reached */ int32_t waypointTurnAngle = posControl.activeWaypoint.nextTurnAngle == -1 ? -1 : ABS(posControl.activeWaypoint.nextTurnAngle); posControl.flags.wpTurnSmoothingActive = false; - if (waypointTurnAngle > 3000 && waypointTurnAngle < 12000 && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { - // turnFactor adjusts start of loiter based on turn angle - float turnFactor = 0.0f; + if (waypointTurnAngle > 3000 && waypointTurnAngle < 16000 && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { + // turnStartFactor adjusts start of loiter based on turn angle + float turnStartFactor; if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_ON) { // passes through WP - turnFactor = waypointTurnAngle / 6000.0f; - } else { - turnFactor = tan_approx(CENTIDEGREES_TO_RADIANS(waypointTurnAngle / 2.0f)); // cut inside turn missing WP + turnStartFactor = waypointTurnAngle / 6000.0f; + } else { // // cut inside turn missing WP + turnStartFactor = constrainf(tan_approx(CENTIDEGREES_TO_RADIANS(waypointTurnAngle / 2.0f)), 1.0f, 2.0f); } - constrainf(turnFactor, 0.5f, 2.0f); - if (posControl.wpDistance < navLoiterRadius * turnFactor) { + // velXY provides additional turn initiation distance based on an assumed 1 second delayed turn response time + if (posControl.wpDistance < (posControl.actualState.velXY + navLoiterRadius * turnStartFactor)) { + if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_ON) { int32_t loiterCenterBearing = wrap_36000(((wrap_18000(posControl.activeWaypoint.nextTurnAngle - 18000)) / 2) + posControl.activeWaypoint.yaw + 18000); - float distToTurnCentre = navLoiterRadius; - if (navConfig()->fw.wp_turn_smoothing == WP_TURN_SMOOTHING_CUT) { - distToTurnCentre = navLoiterRadius / cos_approx(CENTIDEGREES_TO_RADIANS(waypointTurnAngle / 2.0f)); - } - loiterCenterPos.x = posControl.activeWaypoint.pos.x + distToTurnCentre * cos_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing)); - loiterCenterPos.y = posControl.activeWaypoint.pos.y + distToTurnCentre * sin_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing)); + loiterCenterPos.x = posControl.activeWaypoint.pos.x + navLoiterRadius * cos_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing)); + loiterCenterPos.y = posControl.activeWaypoint.pos.y + navLoiterRadius * sin_approx(CENTIDEGREES_TO_RADIANS(loiterCenterBearing)); posErrorX = loiterCenterPos.x - navGetCurrentActualPositionAndVelocity()->pos.x; posErrorY = loiterCenterPos.y - navGetCurrentActualPositionAndVelocity()->pos.y; @@ -316,8 +315,10 @@ static void calculateVirtualPositionTarget_FW(float trackingPeriod) // turn direction to next waypoint loiterTurnDirection = posControl.activeWaypoint.nextTurnAngle > 0 ? 1 : -1; // 1 = right - needToCalculateCircularLoiter = posControl.flags.wpTurnSmoothingActive = true; + needToCalculateCircularLoiter = true; } + posControl.flags.wpTurnSmoothingActive = true; + } } // We are closing in on a waypoint, calculate circular loiter if required @@ -396,26 +397,31 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta /* If waypoint tracking enabled quickly force craft toward waypoint course line and closely track along it */ if (navConfig()->fw.wp_tracking_accuracy && isWaypointNavTrackingActive() && !needToCalculateCircularLoiter) { - // only apply course tracking correction if target bearing error < 90 degs or when close to waypoint (within 10m) - if (ABS(wrap_18000(virtualTargetBearing - posControl.actualState.yaw)) < 9000 || posControl.wpDistance < 1000.0f) { // courseVirtualCorrection initially used to determine current position relative to course line for later use int32_t courseVirtualCorrection = wrap_18000(posControl.activeWaypoint.yaw - virtualTargetBearing); - float distToCourseLine = ABS(posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection))); + navCrossTrackError = ABS(posControl.wpDistance * sin_approx(CENTIDEGREES_TO_RADIANS(courseVirtualCorrection))); + + // tracking only active when certain distance and heading conditions are met + if ((ABS(wrap_18000(virtualTargetBearing - posControl.actualState.yaw)) < 9000 || posControl.wpDistance < 1000.0f) && navCrossTrackError > 200) { + int32_t courseHeadingError = wrap_18000(posControl.activeWaypoint.yaw - posControl.actualState.yaw); + + // captureFactor adjusts distance/heading sensitivity balance when closing in on course line. + // Closing distance threashold based on speed and an assumed 1 second response time. + float captureFactor = navCrossTrackError < posControl.actualState.velXY ? constrainf(2.0f - ABS(courseHeadingError) / 500.0f, 0.0f, 2.0f) : 1.0f; // bias between reducing distance to course line and aligning with course heading adjusted by waypoint_tracking_accuracy // initial courseCorrectionFactor based on distance to course line - float courseCorrectionFactor = constrainf(distToCourseLine / (1000.0f * navConfig()->fw.wp_tracking_accuracy), 0.0f, 1.0f); + float courseCorrectionFactor = constrainf(captureFactor * navCrossTrackError / (1000.0f * navConfig()->fw.wp_tracking_accuracy), 0.0f, 1.0f); courseCorrectionFactor = courseVirtualCorrection < 0 ? -courseCorrectionFactor : courseCorrectionFactor; // course heading alignment factor - int32_t courseHeadingError = wrap_18000(posControl.activeWaypoint.yaw - posControl.actualState.yaw); - float courseHeadingFactor = constrainf(sq(courseHeadingError / 18000.0f), 0.0f, 1.0f); + float courseHeadingFactor = constrainf(courseHeadingError / 18000.0f, 0.0f, 1.0f); courseHeadingFactor = courseHeadingError < 0 ? -courseHeadingFactor : courseHeadingFactor; // final courseCorrectionFactor combining distance and heading factors courseCorrectionFactor = constrainf(courseCorrectionFactor - courseHeadingFactor, -1.0f, 1.0f); - // final courseVirtualCorrection using max 80 deg heading adjustment toward course line + // final courseVirtualCorrection value courseVirtualCorrection = DEGREES_TO_CENTIDEGREES(navConfig()->fw.wp_tracking_max_angle) * courseCorrectionFactor; virtualTargetBearing = wrap_36000(posControl.activeWaypoint.yaw - courseVirtualCorrection); } @@ -635,9 +641,11 @@ void applyFixedWingPitchRollThrottleController(navigationFSMStateFlags_t navStat * Then altitude is below landing slowdown min. altitude, enable final approach procedure * TODO refactor conditions in this metod if logic is proven to be correct */ - if (navStateFlags & NAV_CTL_LAND) { - if ( ((posControl.flags.estAltStatus >= EST_USABLE) && (navGetCurrentActualPositionAndVelocity()->pos.z <= navConfig()->general.land_slowdown_minalt)) || - ((posControl.flags.estAglStatus == EST_TRUSTED) && (posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) ) { + if (navStateFlags & NAV_CTL_LAND || STATE(LANDING_DETECTED)) { + int32_t finalAltitude = navConfig()->general.land_slowdown_minalt + posControl.rthState.homeTmpWaypoint.z; + + if ((posControl.flags.estAltStatus >= EST_USABLE && navGetCurrentActualPositionAndVelocity()->pos.z <= finalAltitude) || + (posControl.flags.estAglStatus == EST_TRUSTED && posControl.actualState.agl.pos.z <= navConfig()->general.land_slowdown_minalt)) { // Set motor to min. throttle and stop it when MOTOR_STOP feature is enabled rcCommand[THROTTLE] = getThrottleIdleValue(); @@ -678,12 +686,11 @@ bool isFixedWingLandingDetected(void) { DEBUG_SET(DEBUG_LANDING, 4, 0); static bool fixAxisCheck = false; - const bool throttleIsLow = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW; // Basic condition to start looking for landing bool startCondition = (navGetCurrentStateFlags() & (NAV_CTL_LAND | NAV_CTL_EMERG)) || FLIGHT_MODE(FAILSAFE_MODE) - || (!navigationIsControllingThrottle() && throttleIsLow); + || (!navigationIsControllingThrottle() && throttleStickIsLow()); if (!startCondition || posControl.flags.resetLandingDetector) { return fixAxisCheck = posControl.flags.resetLandingDetector = false; @@ -693,13 +700,15 @@ bool isFixedWingLandingDetected(void) static timeMs_t fwLandingTimerStartAt; static int16_t fwLandSetRollDatum; static int16_t fwLandSetPitchDatum; + const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f; timeMs_t currentTimeMs = millis(); - // Check horizontal and vertical volocities are low (cm/s) - bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < 50.0f && ((posControl.actualState.velXY < 100.0f) || STATE(GPS_ESTIMATED_FIX)); + // Check horizontal and vertical velocities are low (cm/s) + bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (50.0f * sensitivity) && + ( posControl.actualState.velXY < (100.0f * sensitivity) || STATE(GPS_ESTIMATED_FIX)); // Check angular rates are low (degs/s) - bool gyroCondition = averageAbsGyroRates() < 2.0f; + bool gyroCondition = averageAbsGyroRates() < (2.0f * sensitivity); DEBUG_SET(DEBUG_LANDING, 2, velCondition); DEBUG_SET(DEBUG_LANDING, 3, gyroCondition); @@ -712,13 +721,14 @@ bool isFixedWingLandingDetected(void) fixAxisCheck = true; fwLandingTimerStartAt = currentTimeMs; } else { - bool isRollAxisStatic = ABS(fwLandSetRollDatum - attitude.values.roll) < 5; - bool isPitchAxisStatic = ABS(fwLandSetPitchDatum - attitude.values.pitch) < 5; + const uint8_t angleLimit = 5 * sensitivity; + bool isRollAxisStatic = ABS(fwLandSetRollDatum - attitude.values.roll) < angleLimit; + bool isPitchAxisStatic = ABS(fwLandSetPitchDatum - attitude.values.pitch) < angleLimit; DEBUG_SET(DEBUG_LANDING, 6, isRollAxisStatic); DEBUG_SET(DEBUG_LANDING, 7, isPitchAxisStatic); if (isRollAxisStatic && isPitchAxisStatic) { // Probably landed, low horizontal and vertical velocities and no axis rotation in Roll and Pitch - timeMs_t safetyTimeDelay = 2000 + navConfig()->fw.auto_disarm_delay; + timeMs_t safetyTimeDelay = 2000 + navConfig()->general.auto_disarm_delay; return currentTimeMs - fwLandingTimerStartAt > safetyTimeDelay; // check conditions stable for 2s + optional extra delay } else { fixAxisCheck = false; @@ -815,3 +825,8 @@ int32_t navigationGetHeadingError(void) { return navHeadingError; } + +float navigationGetCrossTrackError(void) +{ + return navCrossTrackError; +} diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 1515f46004..134e649dfa 100644 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -248,11 +248,6 @@ static void applyThrottleIdleLogic(bool forceMixerIdle) } } -static inline bool isThrottleLow(void) -{ - return calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW; -} - static inline bool isLaunchMaxAltitudeReached(void) { return (navConfig()->fw.launch_max_altitude > 0) && (getEstimatedActualPosition(Z) >= navConfig()->fw.launch_max_altitude); @@ -272,7 +267,7 @@ static inline bool isProbablyNotFlying(void) static void resetPidsIfNeeded(void) { // Don't use PID I-term and reset TPA filter until motors are started or until flight is detected - if (isProbablyNotFlying() || fwLaunch.currentState < FW_LAUNCH_STATE_MOTOR_SPINUP || (navConfig()->fw.launch_manual_throttle && isThrottleLow())) { + if (isProbablyNotFlying() || fwLaunch.currentState < FW_LAUNCH_STATE_MOTOR_SPINUP || (navConfig()->fw.launch_manual_throttle && throttleStickIsLow())) { pidResetErrorAccumulators(); pidResetTPAFilter(); } @@ -292,7 +287,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs { UNUSED(currentTimeUs); - if (!isThrottleLow()) { + if (!throttleStickIsLow()) { if (isThrottleIdleEnabled()) { return FW_LAUNCH_EVENT_SUCCESS; } @@ -312,7 +307,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs) { - if (isThrottleLow()) { + if (throttleStickIsLow()) { return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE } @@ -330,7 +325,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(tim static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs) { - if (isThrottleLow()) { + if (throttleStickIsLow()) { return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE } @@ -349,7 +344,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeUs_t currentTimeUs) { - if (isThrottleLow()) { + if (throttleStickIsLow()) { return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE } @@ -427,7 +422,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IN_PROGRESS(timeUs_t if (navConfig()->fw.launch_manual_throttle) { // reset timers when throttle is low or until flight detected and abort launch regardless of launch settings - if (isThrottleLow()) { + if (throttleStickIsLow()) { fwLaunch.currentStateTimeUs = currentTimeUs; fwLaunch.pitchAngle = 0; if (isRollPitchStickDeflected(navConfig()->fw.launch_abort_deadband)) { diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index d74b8e34b6..b40282961f 100644 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -176,14 +176,14 @@ bool adjustMulticopterAltitudeFromRCInput(void) void setupMulticopterAltitudeController(void) { - const throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); + const bool throttleIsLow = throttleStickIsLow(); if (navConfig()->general.flags.use_thr_mid_for_althold) { altHoldThrottleRCZero = rcLookupThrottleMid(); } else { - // If throttle status is THROTTLE_LOW - use Thr Mid anyway - if (throttleStatus == THROTTLE_LOW) { + // If throttle is LOW - use Thr Mid anyway + if (throttleIsLow) { altHoldThrottleRCZero = rcLookupThrottleMid(); } else { @@ -198,7 +198,7 @@ void setupMulticopterAltitudeController(void) // Force AH controller to initialize althold integral for pending takeoff on reset // Signal for that is low throttle _and_ low actual altitude - if (throttleStatus == THROTTLE_LOW && fabsf(navGetCurrentActualPositionAndVelocity()->pos.z) <= 50.0f) { + if (throttleIsLow && fabsf(navGetCurrentActualPositionAndVelocity()->pos.z) <= 50.0f) { prepareForTakeoffOnReset = true; } } @@ -724,24 +724,25 @@ bool isMulticopterLandingDetected(void) { DEBUG_SET(DEBUG_LANDING, 4, 0); static timeUs_t landingDetectorStartedAt; - const bool throttleIsLow = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC) == THROTTLE_LOW; /* Basic condition to start looking for landing * Prevent landing detection if WP mission allowed during Failsafe (except landing states) */ bool startCondition = (navGetCurrentStateFlags() & (NAV_CTL_LAND | NAV_CTL_EMERG)) || (FLIGHT_MODE(FAILSAFE_MODE) && !FLIGHT_MODE(NAV_WP_MODE)) - || (!navigationIsFlyingAutonomousMode() && throttleIsLow); + || (!navigationIsFlyingAutonomousMode() && throttleStickIsLow()); if (!startCondition || posControl.flags.resetLandingDetector) { landingDetectorStartedAt = 0; return posControl.flags.resetLandingDetector = false; } + const float sensitivity = navConfig()->general.land_detect_sensitivity / 5.0f; + // check vertical and horizontal velocities are low (cm/s) - bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < MC_LAND_CHECK_VEL_Z_MOVING && - posControl.actualState.velXY < MC_LAND_CHECK_VEL_XY_MOVING; + bool velCondition = fabsf(navGetCurrentActualPositionAndVelocity()->vel.z) < (MC_LAND_CHECK_VEL_Z_MOVING * sensitivity) && + posControl.actualState.velXY < (MC_LAND_CHECK_VEL_XY_MOVING * sensitivity); // check gyro rates are low (degs/s) - bool gyroCondition = averageAbsGyroRates() < 2.0f; + bool gyroCondition = averageAbsGyroRates() < (4.0f * sensitivity); DEBUG_SET(DEBUG_LANDING, 2, velCondition); DEBUG_SET(DEBUG_LANDING, 3, gyroCondition); @@ -797,7 +798,7 @@ bool isMulticopterLandingDetected(void) DEBUG_SET(DEBUG_LANDING, 5, possibleLandingDetected); if (possibleLandingDetected) { - timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->mc.auto_disarm_delay); // check conditions stable for 2s + optional extra delay + timeUs_t safetyTimeDelay = MS2US(2000 + navConfig()->general.auto_disarm_delay); // check conditions stable for 2s + optional extra delay return (currentTimeUs - landingDetectorStartedAt > safetyTimeDelay); } else { landingDetectorStartedAt = currentTimeUs; diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 0d1192e3ff..c9f7049856 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -36,9 +36,9 @@ #include "fc/config.h" #include "fc/settings.h" +#include "fc/rc_modes.h" #include "flight/imu.h" -#include "flight/secondary_imu.h" #include "io/gps.h" @@ -226,9 +226,6 @@ void onNewGPSData(void) if (positionEstimationConfig()->automatic_mag_declination && !magDeclinationSet) { const float declination = geoCalculateMagDeclination(&newLLH); imuSetMagneticDeclination(declination); -#ifdef USE_SECONDARY_IMU - secondaryImuSetMagneticDeclination(declination); -#endif magDeclinationSet = true; } } @@ -369,11 +366,11 @@ static void restartGravityCalibration(void) } static bool gravityCalibrationComplete(void) -{ +{ if (!gyroConfig()->init_gyro_cal_enabled) { return true; } - + return zeroCalibrationIsCompleteS(&posEstimator.imu.gravityCalibration); } @@ -447,7 +444,7 @@ static void updateIMUTopic(timeUs_t currentTimeUs) if (gravityCalibrationComplete()) { zeroCalibrationGetZeroS(&posEstimator.imu.gravityCalibration, &posEstimator.imu.calibratedGravityCMSS); setGravityCalibrationAndWriteEEPROM(posEstimator.imu.calibratedGravityCMSS); - LOG_D(POS_ESTIMATOR, "Gravity calibration complete (%d)", (int)lrintf(posEstimator.imu.calibratedGravityCMSS)); + LOG_DEBUG(POS_ESTIMATOR, "Gravity calibration complete (%d)", (int)lrintf(posEstimator.imu.calibratedGravityCMSS)); } } } else { @@ -699,6 +696,20 @@ static bool estimationCalculateCorrection_XY_GPS(estimationContext_t * ctx) return false; } +static void estimationCalculateGroundCourse(timeUs_t currentTimeUs) +{ + if (STATE(GPS_FIX) && navIsHeadingUsable()) { + static timeUs_t lastUpdateTimeUs = 0; + + if (currentTimeUs - lastUpdateTimeUs >= HZ2US(INAV_COG_UPDATE_RATE_HZ)) { // limit update rate + const float dt = US2S(currentTimeUs - lastUpdateTimeUs); + uint32_t groundCourse = wrap_36000(RADIANS_TO_CENTIDEGREES(atan2_approx(posEstimator.est.vel.y * dt, posEstimator.est.vel.x * dt))); + posEstimator.est.cog = CENTIDEGREES_TO_DECIDEGREES(groundCourse); + lastUpdateTimeUs = currentTimeUs; + } + } +} + /** * Calculate next estimate using IMU and apply corrections from reference sensors (GPS, BARO etc) * Function is called at main loop rate @@ -771,6 +782,9 @@ static void updateEstimatedTopic(timeUs_t currentTimeUs) } } + /* Update ground course */ + estimationCalculateGroundCourse(currentTimeUs); + /* Update uncertainty */ posEstimator.est.eph = ctx.newEPH; posEstimator.est.epv = ctx.newEPV; @@ -787,8 +801,10 @@ static void publishEstimatedTopic(timeUs_t currentTimeUs) { static navigationTimer_t posPublishTimer; - /* IMU operates in decidegrees while INAV operates in deg*100 */ - updateActualHeading(navIsHeadingUsable(), DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)); + /* IMU operates in decidegrees while INAV operates in deg*100 + * Use course over ground for fixed wing navigation yaw/"heading" */ + int16_t yawValue = isGPSHeadingValid() && STATE(AIRPLANE) ? posEstimator.est.cog : attitude.values.yaw; + updateActualHeading(navIsHeadingUsable(), DECIDEGREES_TO_CENTIDEGREES(yawValue), DECIDEGREES_TO_CENTIDEGREES(posEstimator.est.cog)); /* Position and velocity are published with INAV_POSITION_PUBLISH_RATE_HZ */ if (updateTimer(&posPublishTimer, HZ2US(INAV_POSITION_PUBLISH_RATE_HZ), currentTimeUs)) { @@ -813,6 +829,23 @@ static void publishEstimatedTopic(timeUs_t currentTimeUs) //Update Blackbox states navEPH = posEstimator.est.eph; navEPV = posEstimator.est.epv; + + DEBUG_SET(DEBUG_POS_EST, 0, (int32_t) posEstimator.est.pos.x*1000.0F); // Position estimate X + DEBUG_SET(DEBUG_POS_EST, 1, (int32_t) posEstimator.est.pos.y*1000.0F); // Position estimate Y + if (IS_RC_MODE_ACTIVE(BOXSURFACE) && posEstimator.est.aglQual!=SURFACE_QUAL_LOW){ + // SURFACE (following) MODE + DEBUG_SET(DEBUG_POS_EST, 2, (int32_t) posControl.actualState.agl.pos.z*1000.0F); // Position estimate Z + DEBUG_SET(DEBUG_POS_EST, 5, (int32_t) posControl.actualState.agl.vel.z*1000.0F); // Speed estimate VZ + } else { + DEBUG_SET(DEBUG_POS_EST, 2, (int32_t) posEstimator.est.pos.z*1000.0F); // Position estimate Z + DEBUG_SET(DEBUG_POS_EST, 5, (int32_t) posEstimator.est.vel.z*1000.0F); // Speed estimate VZ + } + DEBUG_SET(DEBUG_POS_EST, 3, (int32_t) posEstimator.est.vel.x*1000.0F); // Speed estimate VX + DEBUG_SET(DEBUG_POS_EST, 4, (int32_t) posEstimator.est.vel.y*1000.0F); // Speed estimate VY + DEBUG_SET(DEBUG_POS_EST, 6, (int32_t) attitude.values.yaw); // Yaw estimate (4 bytes still available here) + DEBUG_SET(DEBUG_POS_EST, 7, (int32_t) (posEstimator.flags & 0b1111111)<<20 | // navPositionEstimationFlags fit into 8bits + (MIN(navEPH, 1000) & 0x3FF)<<10 | + (MIN(navEPV, 1000) & 0x3FF)); // Horizontal and vertical uncertainties (max value = 1000, fit into 20bits) } } diff --git a/src/main/navigation/navigation_pos_estimator_private.h b/src/main/navigation/navigation_pos_estimator_private.h index 80c66d2fc0..dd171fa8e6 100644 --- a/src/main/navigation/navigation_pos_estimator_private.h +++ b/src/main/navigation/navigation_pos_estimator_private.h @@ -39,6 +39,7 @@ #define INAV_POSITION_PUBLISH_RATE_HZ 50 // Publish position updates at this rate #define INAV_PITOT_UPDATE_RATE 10 +#define INAV_COG_UPDATE_RATE_HZ 20 // ground course update rate #define INAV_GPS_TIMEOUT_MS 1500 // GPS timeout #define INAV_BARO_TIMEOUT_MS 200 // Baro timeout @@ -125,6 +126,9 @@ typedef struct { // FLOW float flowCoordinates[2]; + + // COURSE + int16_t cog; // course over ground (decidegrees) } navPositionEstimatorESTIMATE_t; typedef struct { diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index b7b8d0f863..4effe253bd 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -40,7 +40,7 @@ #define MC_POS_CONTROL_JERK_LIMIT_CMSSS 1700.0f // jerk limit on horizontal acceleration (cm/s^3) #define MC_LAND_CHECK_VEL_XY_MOVING 100.0f // cm/s -#define MC_LAND_CHECK_VEL_Z_MOVING 25.0f // cm/s +#define MC_LAND_CHECK_VEL_Z_MOVING 100.0f // cm/s #define MC_LAND_THR_STABILISE_DELAY 1 // seconds #define MC_LAND_DESCEND_THROTTLE 40 // uS #define MC_LAND_SAFE_SURFACE 5.0f // cm @@ -96,9 +96,9 @@ typedef struct navigationFlags_s { bool isAdjustingHeading; // Behaviour modifiers - bool isGCSAssistedNavigationEnabled; // Does iNav accept WP#255 - follow-me etc. + bool isGCSAssistedNavigationEnabled; // Does INAV accept WP#255 - follow-me etc. bool isGCSAssistedNavigationReset; // GCS control was disabled - indicate that so code could take action accordingly - bool isTerrainFollowEnabled; // Does iNav use rangefinder for terrain following (adjusting baro altitude target according to rangefinders readings) + bool isTerrainFollowEnabled; // Does INAV use rangefinder for terrain following (adjusting baro altitude target according to rangefinders readings) // Failsafe actions bool forcedRTHActivated; @@ -124,6 +124,7 @@ typedef struct { navEstimatedPosVel_t abs; navEstimatedPosVel_t agl; int32_t yaw; + int32_t cog; // Service values float sinYaw; @@ -382,7 +383,8 @@ typedef struct { /* Waypoint list */ navWaypoint_t waypointList[NAV_MAX_WAYPOINTS]; bool waypointListValid; - int8_t waypointCount; + int8_t waypointCount; // number of WPs in loaded mission + int8_t startWpIndex; // index of first waypoint in mission int8_t geoWaypointCount; // total geospatial WPs in mission bool wpMissionRestart; // mission restart from first waypoint @@ -393,8 +395,7 @@ typedef struct { /* Multi Missions */ int8_t multiMissionCount; // number of missions in multi mission entry int8_t loadedMultiMissionIndex; // index of selected multi mission - int8_t loadedMultiMissionStartWP; // selected multi mission start WP - int8_t loadedMultiMissionWPCount; // number of WPs in selected multi mission + int8_t totalMultiMissionWpCount; // total number of waypoints in all multi missions #endif navWaypointPosition_t activeWaypoint; // Local position, current bearing and turn angle to next WP, filled on waypoint activation int8_t activeWaypointIndex; @@ -455,7 +456,7 @@ bool isLastMissionWaypoint(void); float getActiveWaypointSpeed(void); bool isWaypointNavTrackingActive(void); -void updateActualHeading(bool headingValid, int32_t newHeading); +void updateActualHeading(bool headingValid, int32_t newHeading, int32_t newGroundCourse); void updateActualHorizontalPositionAndVelocity(bool estPosValid, bool estVelValid, float newX, float newY, float newVelX, float newVelY); void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, float newVelocity, float surfaceDistance, float surfaceVelocity, navigationEstimateStatus_e surfaceStatus); diff --git a/src/main/navigation/sqrt_controller.c b/src/main/navigation/sqrt_controller.c index 42b6a2bf35..569df14d70 100644 --- a/src/main/navigation/sqrt_controller.c +++ b/src/main/navigation/sqrt_controller.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/navigation/sqrt_controller.h b/src/main/navigation/sqrt_controller.h index 37375f96ec..fa6f1d4f70 100644 --- a/src/main/navigation/sqrt_controller.h +++ b/src/main/navigation/sqrt_controller.h @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #pragma once diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 8493db1a9e..9f7e68735d 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -35,6 +35,7 @@ #include "rx/rx.h" #include "common/maths.h" #include "fc/config.h" +#include "fc/cli.h" #include "fc/fc_core.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" @@ -85,10 +86,11 @@ void pgResetFn_logicConditions(logicCondition_t *instance) logicConditionState_t logicConditionStates[MAX_LOGIC_CONDITIONS]; static int logicConditionCompute( - int32_t currentVaue, + int32_t currentValue, logicOperation_e operation, int32_t operandA, - int32_t operandB + int32_t operandB, + uint8_t lcIndex ) { int temporaryValue; vtxDeviceCapability_t vtxDeviceCapability; @@ -103,6 +105,13 @@ static int logicConditionCompute( return operandA == operandB; break; + case LOGIC_CONDITION_APPROX_EQUAL: + { + uint16_t offest = operandA / 100; + return ((operandB >= (operandA - offest)) && (operandB <= (operandA + offest))); + } + break; + case LOGIC_CONDITION_GREATER_THAN: return operandA > operandB; break; @@ -158,7 +167,67 @@ static int logicConditionCompute( } //When both operands are not met, keep current value - return currentVaue; + return currentValue; + break; + + case LOGIC_CONDITION_EDGE: + if (operandA && logicConditionStates[lcIndex].timeout == 0 && !(logicConditionStates[lcIndex].flags & LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED)) { + if (operandB < 100) { + logicConditionStates[lcIndex].timeout = millis(); + } else { + logicConditionStates[lcIndex].timeout = millis() + operandB; + } + logicConditionStates[lcIndex].flags |= LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED; + return true; + } else if (logicConditionStates[lcIndex].timeout > 0) { + if (logicConditionStates[lcIndex].timeout < millis()) { + logicConditionStates[lcIndex].timeout = 0; + } else { + return true; + } + } + + if (!operandA) { + logicConditionStates[lcIndex].flags &= ~LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED; + } + return false; + break; + + case LOGIC_CONDITION_DELAY: + if (operandA) { + if (logicConditionStates[lcIndex].timeout == 0) { + logicConditionStates[lcIndex].timeout = millis() + operandB; + } else if (millis() > logicConditionStates[lcIndex].timeout ) { + logicConditionStates[lcIndex].flags |= LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED; + return true; + } else if (logicConditionStates[lcIndex].flags & LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED) { + return true; + } + } else { + logicConditionStates[lcIndex].timeout = 0; + logicConditionStates[lcIndex].flags &= ~LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED; + } + + return false; + break; + + case LOGIC_CONDITION_TIMER: + if ((logicConditionStates[lcIndex].timeout == 0) || (millis() > logicConditionStates[lcIndex].timeout && !currentValue)) { + logicConditionStates[lcIndex].timeout = millis() + operandA; + return true; + } else if (millis() > logicConditionStates[lcIndex].timeout && currentValue) { + logicConditionStates[lcIndex].timeout = millis() + operandB; + return false; + } + return currentValue; + break; + + case LOGIC_CONDITION_DELTA: + { + int difference = logicConditionStates[lcIndex].lastValue - operandA; + logicConditionStates[lcIndex].lastValue = operandA; + return ABS(difference) >= operandB; + } break; case LOGIC_CONDITION_GVAR_SET: @@ -400,6 +469,15 @@ static int logicConditionCompute( return false; } break; + + case LOGIC_CONDITION_DISABLE_GPS_FIX: + if (operandA > 0) { + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX); + } else { + LOGIC_CONDITION_GLOBAL_FLAG_DISABLE(LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX); + } + return true; + break; default: return false; @@ -411,7 +489,7 @@ void logicConditionProcess(uint8_t i) { const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); - if (logicConditions(i)->enabled && activatorValue) { + if (logicConditions(i)->enabled && activatorValue && !cliMode) { /* * Process condition only when latch flag is not set @@ -424,7 +502,8 @@ void logicConditionProcess(uint8_t i) { logicConditionStates[i].value, logicConditions(i)->operation, operandAValue, - operandBValue + operandBValue, + i ); logicConditionStates[i].value = newValue; @@ -687,6 +766,10 @@ static int logicConditionGetFlightModeOperandValue(int operand) { return IS_RC_MODE_ACTIVE(BOXUSER3); break; + case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4: + return IS_RC_MODE_ACTIVE(BOXUSER4); + break; + default: return 0; break; @@ -780,7 +863,9 @@ void logicConditionUpdateTask(timeUs_t currentTimeUs) { void logicConditionReset(void) { for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) { logicConditionStates[i].value = 0; + logicConditionStates[i].lastValue = 0; logicConditionStates[i].flags = 0; + logicConditionStates[i].timeout = 0; } } diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 0025602984..4e7d792c32 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -76,7 +76,13 @@ typedef enum { LOGIC_CONDITION_MAX = 44, LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE = 45, LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE = 46, - LOGIC_CONDITION_LAST = 47, + LOGIC_CONDITION_EDGE = 47, + LOGIC_CONDITION_DELAY = 48, + LOGIC_CONDITION_TIMER = 49, + LOGIC_CONDITION_DELTA = 50, + LOGIC_CONDITION_APPROX_EQUAL = 51, + LOGIC_CONDITION_DISABLE_GPS_FIX = 52, + LOGIC_CONDITION_LAST = 53, } logicOperation_e; typedef enum logicOperandType_s { @@ -148,6 +154,7 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER2, // 10 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD, // 11 LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3, // 12 + LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4, // 13 } logicFlightModeOperands_e; typedef enum { @@ -162,10 +169,12 @@ typedef enum { LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL = (1 << 8), LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS = (1 << 9), LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_FLIGHT_AXIS = (1 << 10), + LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX = (1 << 11), } logicConditionsGlobalFlags_t; typedef enum { - LOGIC_CONDITION_FLAG_LATCH = 1 << 0, + LOGIC_CONDITION_FLAG_LATCH = 1 << 0, + LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED = 1 << 1, } logicConditionFlags_e; typedef struct logicOperand_s { @@ -186,7 +195,9 @@ PG_DECLARE_ARRAY(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions); typedef struct logicConditionState_s { int value; + int32_t lastValue; uint8_t flags; + timeMs_t timeout; } logicConditionState_t; typedef struct rcChannelOverride_s { diff --git a/src/main/rx/fport2.c b/src/main/rx/fport2.c index c8efdf670d..b9dcda7247 100644 --- a/src/main/rx/fport2.c +++ b/src/main/rx/fport2.c @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav are free software. You can redistribute + * INAV are free software. You can redistribute * this software and/or modify this software 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 + * 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. diff --git a/src/main/rx/frsky_crc.c b/src/main/rx/frsky_crc.c index 32411ecc39..44002c5824 100644 --- a/src/main/rx/frsky_crc.c +++ b/src/main/rx/frsky_crc.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/rx/frsky_crc.h b/src/main/rx/frsky_crc.h index c0a026ba47..0a4dce38d6 100644 --- a/src/main/rx/frsky_crc.h +++ b/src/main/rx/frsky_crc.h @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/rx/msp_override.c b/src/main/rx/msp_override.c index 7a3a3445bd..376eba49e5 100755 --- a/src/main/rx/msp_override.c +++ b/src/main/rx/msp_override.c @@ -167,7 +167,7 @@ bool mspOverrideCalculateChannels(timeUs_t currentTimeUs) uint16_t sample = (*rxRuntimeConfigMSP.rcReadRawFn)(&rxRuntimeConfigMSP, rawChannel); // apply the rx calibration to flight channel - if (channel < NON_AUX_CHANNEL_COUNT && sample != PPM_RCVR_TIMEOUT) { + if (channel < NON_AUX_CHANNEL_COUNT && sample != 0) { sample = scaleRange(sample, rxChannelRangeConfigs(channel)->min, rxChannelRangeConfigs(channel)->max, PWM_RANGE_MIN, PWM_RANGE_MAX); sample = MIN(MAX(PWM_PULSE_MIN, sample), PWM_PULSE_MAX); } diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index eb8f517748..7491d20e70 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -166,7 +166,8 @@ static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t { UNUSED(rxRuntimeConfig); UNUSED(channel); - return PPM_RCVR_TIMEOUT; + + return 0; } static uint8_t nullFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) @@ -474,7 +475,7 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs) uint16_t sample = (*rxRuntimeConfig.rcReadRawFn)(&rxRuntimeConfig, rawChannel); // apply the rx calibration to flight channel - if (channel < NON_AUX_CHANNEL_COUNT && sample != PPM_RCVR_TIMEOUT) { + if (channel < NON_AUX_CHANNEL_COUNT && sample != 0) { sample = scaleRange(sample, rxChannelRangeConfigs(channel)->min, rxChannelRangeConfigs(channel)->max, PWM_RANGE_MIN, PWM_RANGE_MAX); sample = MIN(MAX(PWM_PULSE_MIN, sample), PWM_PULSE_MAX); } diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index d675b359c0..4880c4c4fe 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -51,8 +51,6 @@ #define RSSI_MAX_VALUE 1023 -#define PPM_RCVR_TIMEOUT 0 - typedef enum { RX_FRAME_PENDING = 0, // No new data available from receiver RX_FRAME_COMPLETE = (1 << 0), // There is new data available @@ -83,7 +81,6 @@ typedef enum { SERIALRX_MAVLINK, } rxSerialReceiverType_e; -#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 16 #define MAX_SUPPORTED_RC_CHANNEL_COUNT 18 #define NON_AUX_CHANNEL_COUNT 4 diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index 028ed1b662..df81c55c4b 100755 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -198,7 +198,6 @@ void schedulerResetTaskStatistics(cfTaskId_e taskId) } else if (taskId < TASK_COUNT) { cfTasks[taskId].movingSumExecutionTime = 0; cfTasks[taskId].totalExecutionTime = 0; - cfTasks[taskId].totalExecutionTime = 0; } } diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 92118eef55..57707c725b 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -118,9 +118,6 @@ typedef enum { #endif #ifdef USE_IRLOCK TASK_IRLOCK, -#endif -#ifdef USE_SECONDARY_IMU - TASK_SECONDARY_IMU, #endif /* Count of real tasks */ TASK_COUNT, diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 34a5dca47d..45be068a39 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -620,7 +620,7 @@ void accInitFilters(void) accSoftLpfFilterApplyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { accSoftLpfFilter[axis] = &accFilter[axis].pt1; - pt1FilterInit(accSoftLpfFilter[axis], accelerometerConfig()->acc_lpf_hz, acc.accTargetLooptime * 1e-6f); + pt1FilterInit(accSoftLpfFilter[axis], accelerometerConfig()->acc_lpf_hz, US2S(acc.accTargetLooptime)); } break; case FILTER_BIQUAD: @@ -634,7 +634,7 @@ void accInitFilters(void) } - const float accDt = acc.accTargetLooptime * 1e-6f; + const float accDt = US2S(acc.accTargetLooptime); for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { pt1FilterInit(&accVibeFloorFilter[axis], ACC_VIBE_FLOOR_FILT_HZ, accDt); pt1FilterInit(&accVibeFilter[axis], ACC_VIBE_FILT_HZ, accDt); diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index dc7240f426..ac229de7d4 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -50,8 +50,6 @@ #include "sensors/barometer.h" #include "sensors/sensors.h" -#include "flight/hil.h" - #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif @@ -282,7 +280,7 @@ uint32_t baroUpdate(void) baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); } #else - baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); + baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); #endif state = BAROMETER_NEEDS_SAMPLES; return baro.dev.ut_delay; @@ -319,18 +317,12 @@ int32_t baroCalculateAltitude(void) if (zeroCalibrationIsCompleteS(&zeroCalibration)) { zeroCalibrationGetZeroS(&zeroCalibration, &baroGroundPressure); baroGroundAltitude = pressureToAltitude(baroGroundPressure); - LOG_D(BARO, "Barometer calibration complete (%d)", (int)lrintf(baroGroundAltitude)); + LOG_DEBUG(BARO, "Barometer calibration complete (%d)", (int)lrintf(baroGroundAltitude)); } baro.BaroAlt = 0; } else { -#ifdef HIL - if (hilActive) { - baro.BaroAlt = hilToFC.baroAlt; - return baro.BaroAlt; - } -#endif // calculates height from ground via baro readings baro.BaroAlt = pressureToAltitude(baro.baroPressure) - baroGroundAltitude; } diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 34cc5cb721..9652e15c4f 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -94,7 +94,7 @@ static int32_t mWhDrawn = 0; // energy (milliWatt hours) draw batteryState_e batteryState; const batteryProfile_t *currentBatteryProfile; -PG_REGISTER_ARRAY_WITH_RESET_FN(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles, PG_BATTERY_PROFILES, 1); +PG_REGISTER_ARRAY_WITH_RESET_FN(batteryProfile_t, MAX_BATTERY_PROFILE_COUNT, batteryProfiles, PG_BATTERY_PROFILES, 2); void pgResetFn_batteryProfiles(batteryProfile_t *instance) { @@ -130,8 +130,6 @@ void pgResetFn_batteryProfiles(batteryProfile_t *instance) .failsafe_throttle = SETTING_FAILSAFE_THROTTLE_DEFAULT, // default throttle off. - .fwMinThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT, - .nav = { .mc = { @@ -292,8 +290,8 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected) } #ifdef USE_SIMULATOR if (ARMING_FLAG(SIMULATOR_MODE)) { - if (simulatorData.flags & SIMU_SIMULATE_BATTERY) { - vbat = ((uint16_t)simulatorData.vbat)*10; + if (SIMULATOR_HAS_OPTION(HITL_SIMULATE_BATTERY)) { + vbat = ((uint16_t)simulatorData.vbat) * 10; batteryFullVoltage = 1260; batteryWarningVoltage = 1020; batteryCriticalVoltage = 960; @@ -303,7 +301,7 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected) if (justConnected) { pt1FilterReset(&vbatFilterState, vbat); } else { - vbat = pt1FilterApply4(&vbatFilterState, vbat, VBATT_LPF_FREQ, timeDelta * 1e-6f); + vbat = pt1FilterApply4(&vbatFilterState, vbat, VBATT_LPF_FREQ, US2S(timeDelta)); } } @@ -543,13 +541,12 @@ void currentMeterUpdate(timeUs_t timeDelta) switch (batteryMetersConfig()->current.type) { case CURRENT_SENSOR_ADC: { - amperage = pt1FilterApply4(&erageFilterState, getAmperageSample(), AMPERAGE_LPF_FREQ, timeDelta * 1e-6f); + amperage = pt1FilterApply4(&erageFilterState, getAmperageSample(), AMPERAGE_LPF_FREQ, US2S(timeDelta)); break; } case CURRENT_SENSOR_VIRTUAL: amperage = batteryMetersConfig()->current.offset; if (ARMING_FLAG(ARMED)) { - throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); bool allNav = navConfig()->general.flags.nav_overrides_motor_stop == NOMS_ALL_NAV && posControl.navState != NAV_STATE_IDLE; bool autoNav = navConfig()->general.flags.nav_overrides_motor_stop == NOMS_AUTO_ONLY && (stateFlags & (NAV_AUTO_RTH | NAV_AUTO_WP)); @@ -558,7 +555,7 @@ void currentMeterUpdate(timeUs_t timeDelta) if (allNav || autoNav) { // account for motors running in Nav modes with throttle low + motor stop throttleOffset = (int32_t)rcCommand[THROTTLE] - 1000; } else { - throttleOffset = ((throttleStatus == THROTTLE_LOW) && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000; + throttleOffset = (throttleStickIsLow() && feature(FEATURE_MOTOR_STOP)) ? 0 : (int32_t)rcCommand[THROTTLE] - 1000; } int32_t throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50); amperage += throttleFactor * batteryMetersConfig()->current.scale / 1000; @@ -569,7 +566,7 @@ void currentMeterUpdate(timeUs_t timeDelta) { escSensorData_t * escSensor = escSensorGetData(); if (escSensor && escSensor->dataAge <= ESC_DATA_MAX_AGE) { - amperage = pt1FilterApply4(&erageFilterState, escSensor->current, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f); + amperage = pt1FilterApply4(&erageFilterState, escSensor->current, AMPERAGE_LPF_FREQ, US2S(timeDelta)); } else { amperage = 0; diff --git a/src/main/sensors/battery_config_structs.h b/src/main/sensors/battery_config_structs.h index 6443b886a4..9ce524fa77 100644 --- a/src/main/sensors/battery_config_structs.h +++ b/src/main/sensors/battery_config_structs.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav + * This file is part of INAV * - * iNav free software. You can redistribute + * INAV free software. You can redistribute * this software and/or modify this software 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 distributed in the hope that it + * INAV 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. @@ -106,8 +106,6 @@ typedef struct batteryProfile_s { uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500. - uint16_t fwMinThrottleDownPitchAngle; - struct { struct { diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 5461841b01..9bee826c12 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -80,7 +80,7 @@ PG_RESET_TEMPLATE(compassConfig_t, compassConfig, .magGain = {SETTING_MAGGAIN_X_DEFAULT, SETTING_MAGGAIN_Y_DEFAULT, SETTING_MAGGAIN_Z_DEFAULT}, ); -static uint8_t magUpdatedAtLeastOnce = 0; +static bool magUpdatedAtLeastOnce = false; bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse) { @@ -358,7 +358,7 @@ void compassUpdate(timeUs_t currentTimeUs) { #ifdef USE_SIMULATOR if (ARMING_FLAG(SIMULATOR_MODE)) { - magUpdatedAtLeastOnce = 1; + magUpdatedAtLeastOnce = true; return; } #endif @@ -479,6 +479,6 @@ void compassUpdate(timeUs_t currentTimeUs) applyBoardAlignment(mag.magADC); } - magUpdatedAtLeastOnce = 1; + magUpdatedAtLeastOnce = true; } #endif diff --git a/src/main/sensors/diagnostics.c b/src/main/sensors/diagnostics.c index 0e94d60410..0702f78991 100644 --- a/src/main/sensors/diagnostics.c +++ b/src/main/sensors/diagnostics.c @@ -24,7 +24,6 @@ #include "sensors/rangefinder.h" #include "sensors/pitotmeter.h" #include "sensors/opflow.h" -#include "flight/secondary_imu.h" extern uint8_t requestedSensors[SENSOR_INDEX_COUNT]; extern uint8_t detectedSensors[SENSOR_INDEX_COUNT]; @@ -232,11 +231,6 @@ bool isHardwareHealthy(void) const hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus(); const hardwareSensorStatus_e gpsStatus = getHwGPSStatus(); const hardwareSensorStatus_e opflowStatus = getHwOpticalFlowStatus(); -#ifdef USE_SECONDARY_IMU - const hardwareSensorStatus_e imu2Status = getHwSecondaryImuStatus(); -#else - const hardwareSensorStatus_e imu2Status = HW_SENSOR_NONE; -#endif // Sensor is considered failing if it's either unavailable (selected but not detected) or unhealthy (returning invalid readings) if (gyroStatus == HW_SENSOR_UNAVAILABLE || gyroStatus == HW_SENSOR_UNHEALTHY) @@ -263,8 +257,5 @@ bool isHardwareHealthy(void) if (opflowStatus == HW_SENSOR_UNAVAILABLE || opflowStatus == HW_SENSOR_UNHEALTHY) return false; - if (imu2Status == HW_SENSOR_UNAVAILABLE || opflowStatus == HW_SENSOR_UNHEALTHY) - return false; - return true; } diff --git a/src/main/sensors/esc_sensor.h b/src/main/sensors/esc_sensor.h index e205af981d..a5958c85c1 100644 --- a/src/main/sensors/esc_sensor.h +++ b/src/main/sensors/esc_sensor.h @@ -26,7 +26,7 @@ typedef struct { uint8_t dataAge; - int8_t temperature; + int16_t temperature; int16_t voltage; int32_t current; uint32_t rpm; diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 1f731d44b5..872d189db4 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -235,7 +235,7 @@ static void initGyroFilter(filterApplyFnPtr *applyFn, filter_t state[], uint8_t case FILTER_PT1: *applyFn = (filterApplyFnPtr)pt1FilterApply; for (int axis = 0; axis < 3; axis++) { - pt1FilterInit(&state[axis].pt1, cutoff, looptime * 1e-6f); + pt1FilterInit(&state[axis].pt1, cutoff, US2S(looptime)); } break; case FILTER_BIQUAD: @@ -365,7 +365,7 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroDev_t *dev, zeroCalibrationVe setGyroCalibrationAndWriteEEPROM(dev->gyroZero); #endif - LOG_D(GYRO, "Gyro calibration complete (%d, %d, %d)", dev->gyroZero[X], dev->gyroZero[Y], dev->gyroZero[Z]); + LOG_DEBUG(GYRO, "Gyro calibration complete (%d, %d, %d)", dev->gyroZero[X], dev->gyroZero[Y], dev->gyroZero[Z]); schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics } else { dev->gyroZero[X] = 0; diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 6fe022daea..d6edf7c1ba 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -39,10 +39,9 @@ #include "sensors/sensors.h" #include "sensors/temperature.h" #include "sensors/temperature.h" -#include "flight/secondary_imu.h" -uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_AUTODETECT, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE, SECONDARY_IMU_NONE }; -uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE, SECONDARY_IMU_NONE }; +uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_AUTODETECT, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE }; +uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE, PITOT_NONE, OPFLOW_NONE }; bool sensorsAutodetect(void) { diff --git a/src/main/sensors/irlock.c b/src/main/sensors/irlock.c index 456ff26f0d..8484a78386 100644 --- a/src/main/sensors/irlock.c +++ b/src/main/sensors/irlock.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include "stdbool.h" diff --git a/src/main/sensors/irlock.h b/src/main/sensors/irlock.h index b8bfb63375..f39da22ace 100644 --- a/src/main/sensors/irlock.h +++ b/src/main/sensors/irlock.h @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #pragma once diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index 6dfd04b750..eb2cad13f0 100644 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -177,7 +177,7 @@ static void performPitotCalibrationCycle(void) if (zeroCalibrationIsCompleteS(&pitot.zeroCalibration)) { zeroCalibrationGetZeroS(&pitot.zeroCalibration, &pitot.pressureZero); - LOG_D(PITOT, "Pitot calibration complete (%d)", (int)lrintf(pitot.pressureZero)); + LOG_DEBUG(PITOT, "Pitot calibration complete (%d)", (int)lrintf(pitot.pressureZero)); } } @@ -190,7 +190,7 @@ STATIC_PROTOTHREAD(pitotThread) // Init filter pitot.lastMeasurementUs = micros(); - pt1FilterInit(&pitot.lpfState, pitotmeterConfig()->pitot_lpf_milli_hz / 1000.0f, 0); + pt1FilterInit(&pitot.lpfState, pitotmeterConfig()->pitot_lpf_milli_hz / 1000.0f, 0.0f); while(1) { // Start measurement @@ -207,7 +207,7 @@ STATIC_PROTOTHREAD(pitotThread) pitot.dev.calculate(&pitot.dev, &pitotPressureTmp, NULL); #ifdef USE_SIMULATOR - if (simulatorData.flags & SIMU_AIRSPEED) { + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { pitotPressureTmp = sq(simulatorData.airSpeed) * SSL_AIR_DENSITY / 20000.0f + SSL_AIR_PRESSURE; } #endif @@ -215,7 +215,7 @@ STATIC_PROTOTHREAD(pitotThread) // Filter pressure currentTimeUs = micros(); - pitot.pressure = pt1FilterApply3(&pitot.lpfState, pitotPressureTmp, (currentTimeUs - pitot.lastMeasurementUs) * 1e-6f); + pitot.pressure = pt1FilterApply3(&pitot.lpfState, pitotPressureTmp, US2S(currentTimeUs - pitot.lastMeasurementUs)); pitot.lastMeasurementUs = currentTimeUs; ptDelayUs(pitot.dev.delay); @@ -235,7 +235,7 @@ STATIC_PROTOTHREAD(pitotThread) pitot.airSpeed = 0.0f; } #ifdef USE_SIMULATOR - if (simulatorData.flags & SIMU_AIRSPEED) { + if (SIMULATOR_HAS_OPTION(HITL_AIRSPEED)) { pitot.airSpeed = simulatorData.airSpeed; } #endif diff --git a/src/main/sensors/sensors.h b/src/main/sensors/sensors.h index 6d8bbea298..1a6ab0b8b2 100644 --- a/src/main/sensors/sensors.h +++ b/src/main/sensors/sensors.h @@ -25,7 +25,6 @@ typedef enum { SENSOR_INDEX_RANGEFINDER, SENSOR_INDEX_PITOT, SENSOR_INDEX_OPFLOW, - SENSOR_INDEX_IMU2, SENSOR_INDEX_COUNT } sensorIndex_e; diff --git a/src/main/target/AIKONF4/target.h b/src/main/target/AIKONF4/target.h index d1fa28b2aa..22ee824e5f 100644 --- a/src/main/target/AIKONF4/target.h +++ b/src/main/target/AIKONF4/target.h @@ -27,10 +27,6 @@ #define BEEPER PB4 #define BEEPER_INVERTED -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW0_DEG #define MPU6000_CS_PIN SPI1_NSS_PIN diff --git a/src/main/target/AIRBOTF4/target.h b/src/main/target/AIRBOTF4/target.h index 12925b18e6..db9c2ba7e1 100644 --- a/src/main/target/AIRBOTF4/target.h +++ b/src/main/target/AIRBOTF4/target.h @@ -29,11 +29,6 @@ #define USE_I2C_DEVICE_2 #define I2C_DEVICE_2_SHARES_UART3 -// MPU6000 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_CS_PIN PA4 diff --git a/src/main/target/AIRBOTF7/target.c b/src/main/target/AIRBOTF7/target.c index cc167ca23f..a81988d0a6 100644 --- a/src/main/target/AIRBOTF7/target.c +++ b/src/main/target/AIRBOTF7/target.c @@ -32,13 +32,13 @@ #include "drivers/sensor.h" // Board hardware definitions -BUSDEV_REGISTER_SPI_TAG(busdev_imu0_mpu6000, DEVHW_MPU6000, GYRO_0_SPI_BUS, GYRO_0_CS_PIN, GYRO_0_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_0_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_imu0_mpu6500, DEVHW_MPU6500, GYRO_0_SPI_BUS, GYRO_0_CS_PIN, GYRO_0_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_0_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu0_mpu6000, DEVHW_MPU6000, GYRO_0_SPI_BUS, GYRO_0_CS_PIN, NONE, 0, DEVFLAGS_NONE, GYRO_0_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu0_mpu6500, DEVHW_MPU6500, GYRO_0_SPI_BUS, GYRO_0_CS_PIN, NONE, 0, DEVFLAGS_NONE, GYRO_0_ALIGN); // OMNIBUSF7NANOV7 doesn't have a second gyro #ifndef OMNIBUSF7NANOV7 -BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6000, DEVHW_MPU6000, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_1_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6500, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6000, DEVHW_MPU6000, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, GYRO_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu1_mpu6500, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, GYRO_1_ALIGN); #endif timerHardware_t timerHardware[] = { diff --git a/src/main/target/AIRBOTF7/target_abf7.h b/src/main/target/AIRBOTF7/target_abf7.h index 258d4d30d7..fe84878c8e 100644 --- a/src/main/target/AIRBOTF7/target_abf7.h +++ b/src/main/target/AIRBOTF7/target_abf7.h @@ -37,12 +37,10 @@ #define GYRO_0_CS_PIN PD2 #define GYRO_0_SPI_BUS BUS_SPI3 -#define GYRO_0_EXTI_PIN NONE #define GYRO_0_ALIGN CW90_DEG #define GYRO_1_CS_PIN PC4 #define GYRO_1_SPI_BUS BUS_SPI1 -#define GYRO_1_EXTI_PIN NONE #define GYRO_1_ALIGN CW0_DEG // *************** FLASH ************************** diff --git a/src/main/target/AIRBOTF7/target_o7v7.h b/src/main/target/AIRBOTF7/target_o7v7.h index c808ef6cdb..1c38f3d036 100644 --- a/src/main/target/AIRBOTF7/target_o7v7.h +++ b/src/main/target/AIRBOTF7/target_o7v7.h @@ -36,7 +36,6 @@ #define GYRO_0_CS_PIN PD2 #define GYRO_0_SPI_BUS BUS_SPI3 -#define GYRO_0_EXTI_PIN NONE #define GYRO_0_ALIGN CW0_DEG // *************** FLASH ************************** diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 1500374618..09a2757642 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -32,13 +32,6 @@ #define INVERTER_PIN_USART2 PC15 -// MPU interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PC14 -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_BUS BUS_SPI1 diff --git a/src/main/target/ALIENFLIGHTNGF7/target.h b/src/main/target/ALIENFLIGHTNGF7/target.h index 7fcd08e573..59ad543c3b 100644 --- a/src/main/target/ALIENFLIGHTNGF7/target.h +++ b/src/main/target/ALIENFLIGHTNGF7/target.h @@ -30,12 +30,6 @@ #define BEEPER PC13 #define BEEPER_INVERTED -// MPU interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PC14 -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_BUS BUS_SPI1 diff --git a/src/main/target/ANYFC/target.h b/src/main/target/ANYFC/target.h index 68208000df..1bda97600d 100644 --- a/src/main/target/ANYFC/target.h +++ b/src/main/target/ANYFC/target.h @@ -33,12 +33,6 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG -// MPU6000 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL -#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) - #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 #define USE_MAG_HMC5883 @@ -100,8 +94,6 @@ #define I2C_DEVICE_2_SHARES_UART3 //#define USE_I2C_PULLUP -//#define HIL - #define USE_ADC #define ADC_CHANNEL_1_PIN PC0 #define ADC_CHANNEL_2_PIN PC1 diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index 6869a98e63..b09890a7ef 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -33,11 +33,6 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG -// MPU6000 interrupts -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PC4 -#define USE_EXTI - #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 #define USE_MAG_HMC5883 diff --git a/src/main/target/ANYFCM7/target.h b/src/main/target/ANYFCM7/target.h index c996f1164b..e058ed7a28 100644 --- a/src/main/target/ANYFCM7/target.h +++ b/src/main/target/ANYFCM7/target.h @@ -33,11 +33,6 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG -// MPU6000 interrupts -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PC4 -#define USE_EXTI - #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 #define USE_MAG_HMC5883 diff --git a/src/main/target/AOCODARCF4V2/CMakeLists.txt b/src/main/target/AOCODARCF4V2/CMakeLists.txt new file mode 100644 index 0000000000..410ed8ac42 --- /dev/null +++ b/src/main/target/AOCODARCF4V2/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(AOCODARCF4V2) diff --git a/src/main/target/AOCODARCF4V2/target.c b/src/main/target/AOCODARCF4V2/target.c new file mode 100644 index 0000000000..bdadda24de --- /dev/null +++ b/src/main/target/AOCODARCF4V2/target.c @@ -0,0 +1,46 @@ +/* + * 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/io.h" +#include "drivers/timer.h" +#include "drivers/pwm_mapping.h" +#include "drivers/bus.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0 ), // PPM IN + + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1 ), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S4 + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S6 + + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8 + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_LED, 0, 0 ), // LED_STRIP + + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF4V2/target.h b/src/main/target/AOCODARCF4V2/target.h new file mode 100644 index 0000000000..f9de9dafb5 --- /dev/null +++ b/src/main/target/AOCODARCF4V2/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 USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "AOF4V2" +#define USBD_PRODUCT_STRING "AocodaRCF4V2" + +// ******** Board LEDs ********************** +#define LED0 PC13 + +// ******* Beeper *********** +#define BEEPER PB8 +#define BEEPER_INVERTED + + +// ******* GYRO and ACC ******** +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW0_DEG +#define MPU6500_SPI_BUS BUS_SPI1 +#define MPU6500_CS_PIN PA4 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + + +// *************** Baro ************************** +#define USE_I2C +#define USE_I2C_DEVICE_1 + +#define I2C1_SCL PB6 // SCL +#define I2C1_SDA PB7 // SDA +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS + +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_LIS3MDL + +// ******* SERIAL ******** +#define USE_VCP +#define VBUS_SENSING_PIN PB12 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC11 +#define UART3_RX_PIN PC10 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + + +#define SERIAL_PORT_COUNT 6 + + +// ******* SPI ******** +#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_SPI_DEVICE_2 +#define SPI2_NSS_PIN PA13 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PC0 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// ******* ADC ******** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 + +#define VBAT_SCALE_DEFAULT 1100 + +// ******* OSD ******** +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PA13 + +//******* FLASH ******** +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PC0 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +//************ LEDSTRIP ***************** +#define USE_LED_STRIP +#define WS2811_PIN PB1 + +// ******* FEATURES ******** +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART2 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 10 + +// ESC-related features +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/AOCODARCF7DUAL/target.c b/src/main/target/AOCODARCF7DUAL/target.c index d4c4143bec..f48fb445aa 100644 --- a/src/main/target/AOCODARCF7DUAL/target.c +++ b/src/main/target/AOCODARCF7DUAL/target.c @@ -26,25 +26,23 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6000_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_BMI270_ALIGN); - +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); timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 D(2, 2, 7) - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 D(2, 3, 7) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S3 D(2, 4, 7) - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(2, 7, 7) - - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S5 D(1, 7, 5) - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 2, 5) - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2) + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 D(2, 2, 7) + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 D(2, 3, 7) + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 D(2, 4, 7) + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(2, 7, 7) + + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S5 D(1, 7, 5) + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 2, 5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2) DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S8 D(1, 3, 2) - DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LED_TRIP + DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LED_TRIP }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF7DUAL/target.h b/src/main/target/AOCODARCF7DUAL/target.h index 25d618c5a4..71d38f174d 100644 --- a/src/main/target/AOCODARCF7DUAL/target.h +++ b/src/main/target/AOCODARCF7DUAL/target.h @@ -27,36 +27,26 @@ #define BEEPER PC13 #define BEEPER_INVERTED -// *************** SPI1 Gyro & ACC ******************* +// *************** SPI2 Gyro & ACC ******************* #define USE_SPI #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 #define SPI2_MISO_PIN PB14 #define SPI2_MOSI_PIN PB15 -#define USE_EXTI #define USE_DUAL_GYRO -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW + #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_CS_PIN PB12 #define MPU6000_SPI_BUS BUS_SPI2 -#define MPU6000_EXTI_PIN PC4 - -#define USE_IMU_MPU6500 -#define IMU_MPU6500_ALIGN CW270_DEG -#define MPU6500_CS_PIN PB12 -#define MPU6500_SPI_BUS BUS_SPI2 -#define MPU6500_EXTI_PIN PC4 #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW180_DEG #define BMI270_CS_PIN PA13 #define BMI270_SPI_BUS BUS_SPI2 -#define BMI270_EXTI_PIN PA8 // *************** I2C /Baro/Mag ********************* #define USE_I2C @@ -92,7 +82,7 @@ #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C2 -// *************** SPI2 OSD *********************** +// *************** SPI1 OSD *********************** #define USE_SPI_DEVICE_1 #define SPI1_SCK_PIN PA5 #define SPI1_MISO_PIN PA6 diff --git a/src/main/target/ASGARD32F4/target.h b/src/main/target/ASGARD32F4/target.h index 6c34118f8a..fe801b5efd 100644 --- a/src/main/target/ASGARD32F4/target.h +++ b/src/main/target/ASGARD32F4/target.h @@ -35,10 +35,6 @@ #define BEEPER PC13 #define BEEPER_INVERTED -// #define USE_EXTI -// #define GYRO_INT_EXTI PC8 -// #define USE_MPU_DATA_READY_SIGNAL // Not connected on FireworksV2 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW90_DEG #define MPU6000_CS_PIN PA4 diff --git a/src/main/target/ASGARD32F7/target.h b/src/main/target/ASGARD32F7/target.h index 232e9a7827..ddfc11f15b 100644 --- a/src/main/target/ASGARD32F7/target.h +++ b/src/main/target/ASGARD32F7/target.h @@ -35,10 +35,6 @@ #define BEEPER PC13 #define BEEPER_INVERTED -// #define USE_EXTI -// #define GYRO_INT_EXTI PC8 -// #define USE_MPU_DATA_READY_SIGNAL // Not connected on FireworksV2 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW90_DEG #define MPU6000_CS_PIN PA4 diff --git a/src/main/target/ATOMRCF405NAVI/CMakeLists.txt b/src/main/target/ATOMRCF405NAVI/CMakeLists.txt new file mode 100644 index 0000000000..507c76c8b3 --- /dev/null +++ b/src/main/target/ATOMRCF405NAVI/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(ATOMRCF405NAVI) diff --git a/src/main/target/ATOMRCF405NAVI/target.c b/src/main/target/ATOMRCF405NAVI/target.c new file mode 100644 index 0000000000..fa23597e92 --- /dev/null +++ b/src/main/target/ATOMRCF405NAVI/target.c @@ -0,0 +1,49 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#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(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S8 + + DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED, 0, 0), // LED_STRIP +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/ATOMRCF405NAVI/target.h b/src/main/target/ATOMRCF405NAVI/target.h new file mode 100644 index 0000000000..6f07009afe --- /dev/null +++ b/src/main/target/ATOMRCF405NAVI/target.h @@ -0,0 +1,189 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once +#define TARGET_BOARD_IDENTIFIER "ATF4" + +#define USBD_PRODUCT_STRING "AtomRCF405NAVI" + +#define LED0 PA13 +#define LED1 PA14 + +#define BEEPER PC5 +#define BEEPER_INVERTED + +/* + * SPI defines + */ +#define USE_SPI + +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#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 PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +/* + * I2C defines + */ +#define USE_I2C +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +//BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +/* + * Magnetometer + */ +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +/* + * Barometer + */ +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +/* + * Serial ports + */ +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 + +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 7 + +/* + * ADC + */ +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 + +#define VBAT_ADC_CHANNEL ADC_CHN_3 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_1 + +/* + * OSD + */ +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +/* + * SD Card + */ +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PB6 +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +/* + * LED Strip + */ +#define USE_LED_STRIP +#define WS2811_PIN PB7 + +/* + * Other configs + */ +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT ) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS +#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS +#define PITOT_I2C_BUS DEFAULT_I2C_BUS + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index 362d3a5cc0..4ebde46875 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -25,14 +25,6 @@ #define BEEPER PB3 #define BEEPER_INVERTED -// ICM20689 interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PA8 -#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_BUS BUS_SPI1 diff --git a/src/main/target/BETAFLIGHTF4/target.h b/src/main/target/BETAFLIGHTF4/target.h index e3474d4981..13e7dd3265 100755 --- a/src/main/target/BETAFLIGHTF4/target.h +++ b/src/main/target/BETAFLIGHTF4/target.h @@ -33,12 +33,6 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG - -// MPU6000 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_BARO #define USE_BARO_BMP280 diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h index 85c709edab..290f009b46 100755 --- a/src/main/target/BETAFPVF722/target.h +++ b/src/main/target/BETAFPVF722/target.h @@ -40,11 +40,6 @@ #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** I2C/Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 6949c0474f..689dba9282 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -24,7 +24,6 @@ #define HW_PIN PB2 #define BOARD_HAS_VOLTAGE_DIVIDER -#define USE_EXTI #define LED0 PB6 #define LED1 PB5 @@ -34,12 +33,9 @@ #define BEEPER_OPT PB7 #define BEEPER_INVERTED -// MPU6500 interrupt -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PC5 +// MPU6500 #define MPU6500_CS_PIN PC4 #define MPU6500_SPI_BUS BUS_SPI1 - #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN CW0_DEG diff --git a/src/main/target/CLRACINGF4AIR/target.h b/src/main/target/CLRACINGF4AIR/target.h index 45faf0c2c0..14e5f1d3d5 100644 --- a/src/main/target/CLRACINGF4AIR/target.h +++ b/src/main/target/CLRACINGF4AIR/target.h @@ -53,11 +53,6 @@ #define USE_MAG #define USE_MAG_MPU9250 -// MPU6 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_BARO #define USE_BARO_BMP280 #define USE_BARO_SPI_BMP280 diff --git a/src/main/target/COLIBRI/target.h b/src/main/target/COLIBRI/target.h index 4d45d5d1d2..c76b91b499 100755 --- a/src/main/target/COLIBRI/target.h +++ b/src/main/target/COLIBRI/target.h @@ -38,14 +38,8 @@ #define MPU6000_CS_PIN PC4 #define MPU6000_SPI_BUS BUS_SPI1 - #define USE_IMU_MPU6000 -// MPU6000 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC0 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_MAG #define MAG_I2C_BUS BUS_I2C3 #define USE_MAG_HMC5883 diff --git a/src/main/target/DALRCF405/target.h b/src/main/target/DALRCF405/target.h index ef4dc08f4f..449be6a715 100644 --- a/src/main/target/DALRCF405/target.h +++ b/src/main/target/DALRCF405/target.h @@ -32,10 +32,6 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_BUS BUS_SPI1 #define USE_IMU_MPU6500 diff --git a/src/main/target/DALRCF722DUAL/target.h b/src/main/target/DALRCF722DUAL/target.h index 15ac89cf04..b7d2b4a0d1 100644 --- a/src/main/target/DALRCF722DUAL/target.h +++ b/src/main/target/DALRCF722DUAL/target.h @@ -32,10 +32,6 @@ #define MPU6000_CS_PIN PB0 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PB10 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_VCP #define USE_UART1 diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index e42656a3f9..f72f78f20e 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -27,12 +27,6 @@ #define BEEPER PE5 #define BEEPER_INVERTED - -// MPU6000 interrupts -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PB0 -#define USE_EXTI - #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 #define ICM20689_CS_PIN PA4 diff --git a/src/main/target/FF_F35_LIGHTNING/README.md b/src/main/target/FF_F35_LIGHTNING/README.md index 3a4d7ba6c5..8d63d82b64 100644 --- a/src/main/target/FF_F35_LIGHTNING/README.md +++ b/src/main/target/FF_F35_LIGHTNING/README.md @@ -6,7 +6,7 @@ will be available at: http://furiousfpv.com - Rugged & Robust Aluminum Case for Maximum Crash Protection - Exclusively Designed for INAV Firmware - Ultra Simplistic to Install with Standing USB Ports & Pads -- Fully Supported iNav Firmware +- Fully Supported INAV Firmware - Integrated OSD for Maximum Data Feedback - Built In Camera & VTx Port with Peripheral Pass - Maximum (6) Port UART Layout diff --git a/src/main/target/FF_F35_LIGHTNING/target.h b/src/main/target/FF_F35_LIGHTNING/target.h index f23c8ffbdd..b67dcd1d50 100644 --- a/src/main/target/FF_F35_LIGHTNING/target.h +++ b/src/main/target/FF_F35_LIGHTNING/target.h @@ -29,11 +29,6 @@ #define USE_DSHOT -// MPU interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define MPU9250_CS_PIN PC0 #define MPU9250_SPI_BUS BUS_SPI3 diff --git a/src/main/target/FF_FORTINIF4/target.h b/src/main/target/FF_FORTINIF4/target.h index 00c154dd94..60f9c4cf15 100644 --- a/src/main/target/FF_FORTINIF4/target.h +++ b/src/main/target/FF_FORTINIF4/target.h @@ -34,14 +34,6 @@ //#define CAMERA_CONTROL_PIN PB7 /*---------------------------------*/ -/*------------SENSORS--------------*/ -// MPU interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define MPU6500_CS_PIN PA8 #define MPU6500_SPI_BUS BUS_SPI1 diff --git a/src/main/target/FF_PIKOF4/target.h b/src/main/target/FF_PIKOF4/target.h index 244ddec53b..f786467209 100644 --- a/src/main/target/FF_PIKOF4/target.h +++ b/src/main/target/FF_PIKOF4/target.h @@ -42,14 +42,6 @@ // #define CAMERA_CONTROL_PIN PB7 /*---------------------------------*/ -/*------------SENSORS--------------*/ -// MPU interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #if defined(FF_PIKOF4OSD) #define MPU6000_CS_PIN PA15 #define MPU6000_SPI_BUS BUS_SPI3 diff --git a/src/main/target/FIREWORKSV2/target.h b/src/main/target/FIREWORKSV2/target.h index 827d622024..ce8831f4a9 100644 --- a/src/main/target/FIREWORKSV2/target.h +++ b/src/main/target/FIREWORKSV2/target.h @@ -58,10 +58,6 @@ #define I2C_DEVICE_2_SHARES_UART3 #endif -#define USE_EXTI -#define GYRO_INT_EXTI PC8 -// #define USE_MPU_DATA_READY_SIGNAL // Not connected on FireworksV2 - #define USE_DUAL_GYRO #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS // Don't use common busdev descriptors for IMU #define USE_IMU_MPU6500 diff --git a/src/main/target/FISHDRONEF4/target.h b/src/main/target/FISHDRONEF4/target.h index 661d8d844e..741a8aded8 100644 --- a/src/main/target/FISHDRONEF4/target.h +++ b/src/main/target/FISHDRONEF4/target.h @@ -44,12 +44,6 @@ #define USE_IMU_MPU9250 #define IMU_MPU9250_ALIGN CW180_DEG -// MPU6500 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - // *************** Compass ***************************** #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/FLYWOOF411/target.h b/src/main/target/FLYWOOF411/target.h index 8188bc6715..286b986373 100644 --- a/src/main/target/FLYWOOF411/target.h +++ b/src/main/target/FLYWOOF411/target.h @@ -56,14 +56,6 @@ #define ICM20689_SPI_BUS BUS_SPI1 #define IMU_ICM20689_ALIGN CW180_DEG -#define USE_EXTI -#ifdef FLYWOOF411_V2 -#define GYRO_INT_EXTI PB5 -#else -#define GYRO_INT_EXTI PB3 -#endif -#define USE_MPU_DATA_READY_SIGNAL - // *************** Baro ***************************** #define USE_I2C diff --git a/src/main/target/FLYWOOF745/target.h b/src/main/target/FLYWOOF745/target.h index 8aa522c299..e0e012aa60 100644 --- a/src/main/target/FLYWOOF745/target.h +++ b/src/main/target/FLYWOOF745/target.h @@ -28,62 +28,57 @@ #define USBD_PRODUCT_STRING "FLYWOOF745NANO" #endif -#define LED0 PA2// +#define LED0 PA2 -#define BEEPER PD15// +#define BEEPER PD15 #define BEEPER_INVERTED #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_MPU_DATA_READY_SIGNAL -#define USE_EXTI - #define USE_IMU_MPU6000 -#define IMU_MPU6000_ALIGN CW270_DEG// -#define GYRO_INT_EXTI PE1// -#define MPU6000_CS_PIN SPI4_NSS_PIN// -#define MPU6000_SPI_BUS BUS_SPI4// - +#define IMU_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN SPI4_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI4 #define USB_IO #define USE_VCP #define VBUS_SENSING_ENABLED -#define VBUS_SENSING_PIN PA8// +#define VBUS_SENSING_PIN PA8 #define USE_UART1 -#define UART1_TX_PIN PA9// -#define UART1_RX_PIN PA10// +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 #define USE_UART2 -#define UART2_TX_PIN PD5// -#define UART2_RX_PIN PD6// +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 #define USE_UART3 #ifdef FLYWOOF745 -#define UART3_TX_PIN PB10// -#define UART3_RX_PIN PB11// +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #else -#define UART3_TX_PIN PD8// -#define UART3_RX_PIN PD9// +#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 #endif #define USE_UART4 -#define UART4_TX_PIN PA0// -#define UART4_RX_PIN PA1// +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 #define USE_UART5 -#define UART5_TX_PIN PC12// -#define UART5_RX_PIN PD2// +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 #define USE_UART6 -#define UART6_TX_PIN PC6// -#define UART6_RX_PIN PC7// +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 #define USE_UART7 -#define UART7_TX_PIN PE8// -#define UART7_RX_PIN PE7// +#define UART7_TX_PIN PE8 +#define UART7_RX_PIN PE7 #define SERIAL_PORT_COUNT 8 //VCP,UART1,UART2,UART3,UART4,UART5,UART6,UART7 @@ -107,7 +102,6 @@ #define SPI4_MISO_PIN PE5 #define SPI4_MOSI_PIN PE6 - #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 #define MAX7456_CS_PIN SPI2_NSS_PIN @@ -173,7 +167,7 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define USE_LED_STRIP -#define WS2811_PIN PD12 // //TIM4_CH1 +#define WS2811_PIN PD12 //TIM4_CH1 #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c index 1f769ea1d0..1af1457249 100644 --- a/src/main/target/FLYWOOF7DUAL/target.c +++ b/src/main/target/FLYWOOF7DUAL/target.c @@ -30,12 +30,12 @@ #include "io/piniobox.h" // IMU 1 -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_1, DEVHW_MPU6000, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_1, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_1, DEVHW_MPU6000, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, NONE, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_1, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, NONE, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); // IMU 2 -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_2, DEVHW_MPU6000, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, GYRO_2_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_2_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, GYRO_2_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_2_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_2, DEVHW_MPU6000, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, GYRO_2_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, NONE, 1, DEVFLAGS_NONE, GYRO_2_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS diff --git a/src/main/target/FLYWOOF7DUAL/target.h b/src/main/target/FLYWOOF7DUAL/target.h index 19f2db96a4..58630efe7e 100644 --- a/src/main/target/FLYWOOF7DUAL/target.h +++ b/src/main/target/FLYWOOF7DUAL/target.h @@ -23,12 +23,9 @@ #define BEEPER PC14 #define BEEPER_INVERTED -/*** IMU sensors ***/ -#define USE_EXTI - // We use dual IMU sensors, they have to be described in the target file #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS -#define USE_MPU_DATA_READY_SIGNAL + #define USE_DUAL_GYRO #define USE_IMU_MPU6000 @@ -36,12 +33,10 @@ #define GYRO_1_SPI_BUS BUS_SPI1 #define GYRO_1_CS_PIN PA4 -#define GYRO_1_EXTI_PIN PC3 #define GYRO_1_ALIGN CW180_DEG_FLIP #define GYRO_2_SPI_BUS BUS_SPI1 #define GYRO_2_CS_PIN PB2 -#define GYRO_2_EXTI_PIN PC4 #define GYRO_2_ALIGN CW270_DEG /*** SPI/I2C bus ***/ diff --git a/src/main/target/FOXEERF405/target.h b/src/main/target/FOXEERF405/target.h index e95e9b0ce4..8ee53eeb70 100644 --- a/src/main/target/FOXEERF405/target.h +++ b/src/main/target/FOXEERF405/target.h @@ -25,12 +25,6 @@ #define BEEPER PA4 #define BEEPER_INVERTED -/*** IMU sensors ***/ -#define USE_EXTI - -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - // MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW90_DEG diff --git a/src/main/target/FOXEERF722DUAL/target.c b/src/main/target/FOXEERF722DUAL/target.c index 52badd7fe8..fca041e07a 100644 --- a/src/main/target/FOXEERF722DUAL/target.c +++ b/src/main/target/FOXEERF722DUAL/target.c @@ -23,9 +23,9 @@ #include "drivers/sensor.h" #include "drivers/pwm_mapping.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); #if defined(FOXEERF722DUAL) -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); #endif timerHardware_t timerHardware[] = { diff --git a/src/main/target/FOXEERF722DUAL/target.h b/src/main/target/FOXEERF722DUAL/target.h index 739043f9a8..7698fe1abf 100644 --- a/src/main/target/FOXEERF722DUAL/target.h +++ b/src/main/target/FOXEERF722DUAL/target.h @@ -25,12 +25,8 @@ #define BEEPER PA4 #define BEEPER_INVERTED -/*** IMU sensors ***/ -#define USE_EXTI - // We use dual IMU sensors, they have to be described in the target file #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS -#define USE_MPU_DATA_READY_SIGNAL #ifdef FOXEERF722DUAL #define USE_DUAL_GYRO @@ -41,7 +37,6 @@ #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_CS_PIN PB2 #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PC4 // ICM20602 - handled by MPU6500 driver #ifdef FOXEERF722DUAL @@ -49,7 +44,6 @@ #define IMU_MPU6500_ALIGN CW180_DEG #define MPU6500_CS_PIN PB1 #define MPU6500_SPI_BUS BUS_SPI1 -#define MPU6500_EXTI_PIN PB0 #endif /*** SPI/I2C bus ***/ diff --git a/src/main/target/FOXEERF722V4/CMakeLists.txt b/src/main/target/FOXEERF722V4/CMakeLists.txt new file mode 100644 index 0000000000..82f5b3e319 --- /dev/null +++ b/src/main/target/FOXEERF722V4/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f722xe(FOXEERF722V4) +target_stm32f722xe(FOXEERF722V4_X8) \ No newline at end of file diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c new file mode 100644 index 0000000000..2cadae4d77 --- /dev/null +++ b/src/main/target/FOXEERF722V4/target.c @@ -0,0 +1,44 @@ +/* + * 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 +#include "drivers/io.h" +#include "drivers/bus.h" +#include "drivers/timer.h" +#include "drivers/sensor.h" +#include "drivers/pwm_mapping.h" + +timerHardware_t timerHardware[] = { + + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 - D(2, 1, 6) + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 - D(2, 1, 6) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(2, 7, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(2, 4, 7) + +#ifdef FOXEERF722V4_X8 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 +#endif + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED STRIP(1,5) + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FOXEERF722V4/target.h b/src/main/target/FOXEERF722V4/target.h new file mode 100644 index 0000000000..208b1f9a07 --- /dev/null +++ b/src/main/target/FOXEERF722V4/target.h @@ -0,0 +1,160 @@ +/* + * 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 "FX74" +#define USBD_PRODUCT_STRING "FOXEER F722 V4" + +/*** Indicators ***/ +#define LED0 PC15 +#define BEEPER PA4 +#define BEEPER_INVERTED + +/*** IMU sensors ***/ +#define USE_EXTI + +#define USE_MPU_DATA_READY_SIGNAL + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PB2 +#define ICM42605_EXTI_PIN PC4 + +/*** SPI/I2C bus ***/ +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#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 PB5 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +/*** Onboard flash ***/ +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_BUS BUS_SPI2 + +/*** OSD ***/ +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI3 +#define MAX7456_CS_PIN PC3 + +/*** Serial ports ***/ +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + + + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#ifdef FOXEERF722V4_X8 +//X8 variant without UART2 and UART6 +#define SERIAL_PORT_COUNT 5 +#else +//Standard variant +#define SERIAL_PORT_COUNT 7 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#endif + + +/*** BARO & MAG ***/ +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define BNO055_I2C_BUS BUS_I2C1 + +/*** ADC ***/ +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PA0 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +/*** LED STRIP ***/ +#define USE_LED_STRIP +#define WS2811_PIN PA15 + +/*** Default settings ***/ +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define SERIALRX_UART SERIAL_PORT_USART1 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +/*** Timer/PWM output ***/ +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define MAX_PWM_OUTPUT_PORTS 4 +#define USE_DSHOT +#define USE_ESC_SENSOR + +/*** Used pins ***/ +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + diff --git a/src/main/target/FOXEERF745AIO/CMakeLists.txt b/src/main/target/FOXEERF745AIO/CMakeLists.txt index a0c1257288..297cb5e167 100644 --- a/src/main/target/FOXEERF745AIO/CMakeLists.txt +++ b/src/main/target/FOXEERF745AIO/CMakeLists.txt @@ -1 +1,2 @@ target_stm32f745xg(FOXEERF745AIO) +target_stm32f745xg(FOXEERF745AIO_V3) \ No newline at end of file diff --git a/src/main/target/FOXEERF745AIO/target.h b/src/main/target/FOXEERF745AIO/target.h index dd1f307a3e..498fc7e3a5 100644 --- a/src/main/target/FOXEERF745AIO/target.h +++ b/src/main/target/FOXEERF745AIO/target.h @@ -31,13 +31,22 @@ #define USE_MPU_DATA_READY_SIGNAL +#ifdef FOXEERF745AIO_V3 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_SPI_BUS BUS_SPI3 +#define ICM42605_CS_PIN PA15 + +#else + // MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG #define MPU6000_CS_PIN PA15 #define MPU6000_SPI_BUS BUS_SPI3 -#define MPU6000_EXTI_PIN PD0 +#endif /*** SPI/I2C bus ***/ #define USE_SPI diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index 222153b964..c014283f33 100755 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -24,14 +24,9 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_BARO #define USE_BARO_BMP280 #define BMP280_SPI_BUS BUS_SPI3 diff --git a/src/main/target/FRSKYPILOT/target.c b/src/main/target/FRSKYPILOT/target.c index 13013c0865..8594a6f757 100644 --- a/src/main/target/FRSKYPILOT/target.c +++ b/src/main/target/FRSKYPILOT/target.c @@ -26,8 +26,8 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S1 diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index 5a558f101f..d8100f2610 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -67,26 +67,15 @@ #define USE_IMU_MPU6000 #define USE_IMU_MPU6500 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - -//#define USE_ONBOARD_IMU -//#define USE_BOX_IMU #define USE_DUAL_GYRO -//#if defined(USE_ONBOARD_IMU) -#define MPU6500_EXTI_PIN PE8 #define MPU6500_SPI_BUS BUS_SPI3 #define MPU6500_CS_PIN SPI3_NSS_PIN #define IMU_MPU6500_ALIGN CW0_DEG_FLIP -//#elif defined(USE_BOX_IMU) -#define MPU6000_EXTI_PIN NONE #define MPU6000_SPI_BUS BUS_SPI2 #define MPU6000_CS_PIN SPI2_NSS_PIN -#define IMU_MPU6000_ALIGN CW270_DEG_FLIP // XXX check - -//#endif // IMU SELECTION +#define IMU_MPU6000_ALIGN CW270_DEG_FLIP // *************** SPI4: SDCARD ******************* @@ -199,7 +188,7 @@ #ifdef FRSKYPILOT_LED #define USE_LED_STRIP - #define WS2811_PIN PA1 // S10 pad for iNav + #define WS2811_PIN PA1 // S10 pad for INAV #define MAX_PWM_OUTPUT_PORTS 9 #else diff --git a/src/main/target/FRSKY_ROVERF7/target.h b/src/main/target/FRSKY_ROVERF7/target.h index 60e734843a..ea1c62e0d1 100755 --- a/src/main/target/FRSKY_ROVERF7/target.h +++ b/src/main/target/FRSKY_ROVERF7/target.h @@ -39,11 +39,6 @@ #define MPU6000_CS_PIN PC4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PA4 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** I2C/Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 diff --git a/src/main/target/FURYF4OSD/target.h b/src/main/target/FURYF4OSD/target.h index 375a6ee15b..46eec2422f 100644 --- a/src/main/target/FURYF4OSD/target.h +++ b/src/main/target/FURYF4OSD/target.h @@ -45,10 +45,6 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT #define USE_SPI_DEVICE_3 #define SPI3_SCK_PIN PC10 diff --git a/src/main/target/HAKRCF405D/CMakeLists.txt b/src/main/target/HAKRCF405D/CMakeLists.txt new file mode 100644 index 0000000000..a8350a22b6 --- /dev/null +++ b/src/main/target/HAKRCF405D/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(HAKRCF405D) diff --git a/src/main/target/HAKRCF405D/config.c b/src/main/target/HAKRCF405D/config.c new file mode 100644 index 0000000000..b963bfbfa5 --- /dev/null +++ b/src/main/target/HAKRCF405D/config.c @@ -0,0 +1,28 @@ +/* + * 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 + +#include "fc/fc_msp_box.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/HAKRCF405D/target.c b/src/main/target/HAKRCF405D/target.c new file mode 100644 index 0000000000..3e4e0f763c --- /dev/null +++ b/src/main/target/HAKRCF405D/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 + +#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" + +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + + DEF_TIM(TIM4, CH1, PB8, TIM_USE_LED, 0, 0), // LED STRIP(2,6) + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_PWM, 0, 0), // PWM1 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_PWM, 0, 0), // PWM2 + DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0), // PWM3 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/HAKRCF405D/target.h b/src/main/target/HAKRCF405D/target.h new file mode 100644 index 0000000000..002fd191c3 --- /dev/null +++ b/src/main/target/HAKRCF405D/target.h @@ -0,0 +1,175 @@ +/* + * 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 "H40D" +#define USBD_PRODUCT_STRING "HAKRCF405D" + +#define USE_TARGET_CONFIG + +/*** Indicators ***/ +#define LED0 PB9 +#define LED1 PA14 +#define BEEPER PC13 +#define BEEPER_INVERTED + +/*** SPI & I2C ***/ +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PC2 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB10 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PC0 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +/*** IMU sensors ***/ +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +// MPU6000 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN SPI1_NSS_PIN + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN + +//BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW270_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN + +/*** OSD ***/ +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +/*** Onboard flash ***/ +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN SPI3_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI3 + +/*** PINIO ***/ +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC14 +#define PINIO2_PIN PC15 + +/*** Serial ports ***/ +#define USE_VCP +#define USB_DETECT_PIN PB12 +#define USE_USB_DETECT + +#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 + +/*** BARO & MAG ***/ +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_SPL06 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +/*** ADC ***/ +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC5 +#define ADC_CHANNEL_2_PIN PB1 +#define ADC_CHANNEL_3_PIN PC4 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 +#define RSSI_METER_ADC_CHANNEL ADC_CHN_2 + +/*** LED STRIP ***/ +#define USE_LED_STRIP +#define WS2811_PIN PB8 + +/*** Default settings ***/ +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define CURRENT_METER_SCALE 179 + + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) + +/*** Timer/PWM output ***/ +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define MAX_PWM_OUTPUT_PORTS 6 +#define USE_DSHOT +#define USE_ESC_SENSOR + +/*** Optical Flow & Lidar ***/ +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +/*** Misc ***/ +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) diff --git a/src/main/target/HAKRCF411D/CMakeLists.txt b/src/main/target/HAKRCF411D/CMakeLists.txt new file mode 100644 index 0000000000..4125ec3184 --- /dev/null +++ b/src/main/target/HAKRCF411D/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f411xe(HAKRCF411D) diff --git a/src/main/target/HAKRCF411D/config.c b/src/main/target/HAKRCF411D/config.c new file mode 100644 index 0000000000..a953ffbecc --- /dev/null +++ b/src/main/target/HAKRCF411D/config.c @@ -0,0 +1,31 @@ +/* + * 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 "fc/fc_msp_box.h" +#include "io/piniobox.h" +#include "sensors/boardalignment.h" + +void targetConfiguration(void) +{ + boardAlignmentMutable()->yawDeciDegrees = -900; + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/HAKRCF411D/target.c b/src/main/target/HAKRCF411D/target.c new file mode 100644 index 0000000000..7f1abaf76a --- /dev/null +++ b/src/main/target/HAKRCF411D/target.c @@ -0,0 +1,39 @@ +/* + * 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 + +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM IN + + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_TX_PIN + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // SOFTSERIAL_1_RX_PIN + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // 2812LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/HAKRCF411D/target.h b/src/main/target/HAKRCF411D/target.h new file mode 100644 index 0000000000..96ea1a7c77 --- /dev/null +++ b/src/main/target/HAKRCF411D/target.h @@ -0,0 +1,156 @@ +/* + * 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 "H41D" +#define USBD_PRODUCT_STRING "HAKRCF411D" + +#define USE_TARGET_CONFIG + +/*** Indicators ***/ +#define LED0 PC13 +#define LED1 PC14 +#define BEEPER PB2 +#define BEEPER_INVERTED + +/*** SPI & I2C ***/ +#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_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +/*** IMU sensors ***/ + +// MPU6000 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN SPI1_NSS_PIN + +// ICM42605/ICM42688P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN + +//BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN SPI1_NSS_PIN + +/*** OSD ***/ +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +/*** Onboard flash ***/ +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PA0 +#define M25P16_SPI_BUS BUS_SPI2 + +/*** UARTs ***/ +#define USE_VCP +#define VBUS_SENSING_PIN PC15 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA15 +#define SOFTSERIAL_1_RX_PIN PB3 + +#define SERIAL_PORT_COUNT 4 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +/*** I2C (Baro/Mag/Pitot) ***/ +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_SPL06 +#define USE_BARO_DPS310 + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define PITOT_I2C_BUS BUS_I2C1 + +/*** PINIO ***/ +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PB10 +#define PINIO2_PIN PC14 + +/*** ADC ***/ +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PB0 +#define ADC_CHANNEL_2_PIN PB1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +/*** WS2812 LEDs ***/ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +/*** Misc ***/ +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) + +#define USE_DSHOT +//#define USE_ESC_SENSOR + +#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 (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 4 diff --git a/src/main/target/HAKRCKD722/CMakeLists.txt b/src/main/target/HAKRCKD722/CMakeLists.txt new file mode 100644 index 0000000000..e914b7f8b2 --- /dev/null +++ b/src/main/target/HAKRCKD722/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(HAKRCKD722) diff --git a/src/main/target/HAKRCKD722/config.c b/src/main/target/HAKRCKD722/config.c new file mode 100644 index 0000000000..caaec66ef2 --- /dev/null +++ b/src/main/target/HAKRCKD722/config.c @@ -0,0 +1,28 @@ +/* + * 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 "fc/fc_msp_box.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; // VTX power switch + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +} diff --git a/src/main/target/HAKRCKD722/target.c b/src/main/target/HAKRCKD722/target.c new file mode 100644 index 0000000000..eb9b4d87c2 --- /dev/null +++ b/src/main/target/HAKRCKD722/target.c @@ -0,0 +1,47 @@ +/* + * 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" + +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/HAKRCKD722/target.h b/src/main/target/HAKRCKD722/target.h new file mode 100644 index 0000000000..5b4869951d --- /dev/null +++ b/src/main/target/HAKRCKD722/target.h @@ -0,0 +1,177 @@ +/* + * 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 "KD7D" +#define USBD_PRODUCT_STRING "HAKRCKD722" + +#define LED0 PA14 +#define LED1 PA13 + +#define USE_BEEPER +#define BEEPER PC13 +#define BEEPER_INVERTED + +/*** PINIO ***/ + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC8 +#define PINIO2_PIN PC9 + +/*** UART ***/ +#define USB_IO +#define USE_VCP + +#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 PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 6 + +/*** Gyro & Acc ***/ +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW180_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PB2 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PB2 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PB2 + +/*** I2C (Baro & Mag) ***/ +#define USE_I2C + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// Baro +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 +#define BARO_I2C_BUS BUS_I2C1 + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +/*** Onboard Flash ***/ +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PD2 + +#define W25N01G_SPI_BUS BUS_SPI3 +#define W25N01G_CS_PIN PD2 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +/*** OSD ***/ +#define USE_OSD +#define USE_SPI_DEVICE_2 +#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 PB12 + +/*** ADC ***/ +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC0 +#define ADC_CHANNEL_3_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 +#define RSSI_ADC_CHANNEL ADC_CHN_2 + +/*** LED ***/ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +/*** Optical Flow & Lidar ***/ +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +/*** Misc ***/ +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define SERIALRX_UART SERIAL_PORT_USART2 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define CURRENT_METER_SCALE 250 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) diff --git a/src/main/target/HGLRCF722/target.c b/src/main/target/HGLRCF722/target.c index 82ba088bc2..faf6725705 100644 --- a/src/main/target/HGLRCF722/target.c +++ b/src/main/target/HGLRCF722/target.c @@ -33,8 +33,8 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +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); timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) diff --git a/src/main/target/HGLRCF722/target.h b/src/main/target/HGLRCF722/target.h index 71da34c814..3cf2986f75 100644 --- a/src/main/target/HGLRCF722/target.h +++ b/src/main/target/HGLRCF722/target.h @@ -49,16 +49,11 @@ #define IMU_MPU6000_ALIGN CW180_DEG_FLIP #define MPU6000_CS_PIN PB2 #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PC4 #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW180_DEG_FLIP #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PB2 -#define BMI270_EXTI_PIN PC4 - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL // *************** I2C /Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.h b/src/main/target/IFLIGHTF4_SUCCEXD/target.h index da06c7aa77..2d9d7bb535 100644 --- a/src/main/target/IFLIGHTF4_SUCCEXD/target.h +++ b/src/main/target/IFLIGHTF4_SUCCEXD/target.h @@ -39,10 +39,6 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PA1 -#define USE_MPU_DATA_READY_SIGNAL - // *************** SPI2 OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/IFLIGHTF4_TWING/target.c b/src/main/target/IFLIGHTF4_TWING/target.c index 1a97fb19af..a321b88cee 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.c +++ b/src/main/target/IFLIGHTF4_TWING/target.c @@ -26,8 +26,8 @@ #include "drivers/sensor.h" // Board hardware definitions -BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6500_0_CS_PIN, MPU6500_0_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_0_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, MPU6500_1_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6500_0_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_0_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_1_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM diff --git a/src/main/target/IFLIGHTF4_TWING/target.h b/src/main/target/IFLIGHTF4_TWING/target.h index e75e1bd308..77dd3992e0 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.h +++ b/src/main/target/IFLIGHTF4_TWING/target.h @@ -42,14 +42,9 @@ #define MPU6500_0_CS_PIN PA4 #define MPU6500_0_SPI_BUS BUS_SPI1 -#define MPU6500_0_EXTI_PIN PC4 #define MPU6500_1_CS_PIN PC3 #define MPU6500_1_SPI_BUS BUS_SPI1 -#define MPU6500_1_EXTI_PIN PA8 - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL // *************** I2C/Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/IFLIGHTF7_TWING/target.c b/src/main/target/IFLIGHTF7_TWING/target.c index 4971c81279..d596849dd5 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.c +++ b/src/main/target/IFLIGHTF7_TWING/target.c @@ -26,8 +26,8 @@ #include "drivers/sensor.h" // Board hardware definitions -BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6500_0_CS_PIN, MPU6500_0_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_0_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, MPU6500_1_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6500, MPU6500_0_SPI_BUS, MPU6500_0_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_0_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_1_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), diff --git a/src/main/target/IFLIGHTF7_TWING/target.h b/src/main/target/IFLIGHTF7_TWING/target.h index ab6b1c1b63..7bfbb0bbc5 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.h +++ b/src/main/target/IFLIGHTF7_TWING/target.h @@ -44,15 +44,9 @@ #define MPU6500_0_CS_PIN PC3 #define MPU6500_0_SPI_BUS BUS_SPI1 -#define MPU6500_0_EXTI_PIN PB2 #define MPU6500_1_CS_PIN PA15 #define MPU6500_1_SPI_BUS BUS_SPI1 -#define MPU6500_1_EXTI_PIN PA8 - - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL // *************** I2C/Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/IFLIGHT_BLITZ_F722/target.h b/src/main/target/IFLIGHT_BLITZ_F722/target.h index f0078cb44e..370cea2267 100644 --- a/src/main/target/IFLIGHT_BLITZ_F722/target.h +++ b/src/main/target/IFLIGHT_BLITZ_F722/target.h @@ -32,10 +32,6 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PC4 - #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW0_DEG #define BMI270_CS_PIN PA4 diff --git a/src/main/target/IFLIGHT_BLITZ_F7_PRO/CMakeLists.txt b/src/main/target/IFLIGHT_BLITZ_F7_PRO/CMakeLists.txt new file mode 100644 index 0000000000..d1eff7c418 --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F7_PRO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(IFLIGHT_BLITZ_F7_PRO) diff --git a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c new file mode 100644 index 0000000000..592fd20b4c --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.c @@ -0,0 +1,47 @@ +/* +* This file is part of INAV Project. +* +* INAV Project 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 Project 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 Project. 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" + +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); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 + DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + + DEF_TIM(TIM2, CH2, PA1, TIM_USE_LED, 0, 0), // LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h new file mode 100644 index 0000000000..03e7d0e2f4 --- /dev/null +++ b/src/main/target/IFLIGHT_BLITZ_F7_PRO/target.h @@ -0,0 +1,150 @@ +/* + * This file is part of INAV Project. + * + * INAV Project 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 Project 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 Project. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "IFBLITZF7PRO" + +#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F7_PRO" + +#define LED0 PC4 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +// *************** IMU generic *********************** +#define USE_DUAL_GYRO +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA15 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG_FLIP +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA15 + +// *************** I2C/Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 // SCL pad +#define I2C2_SDA PB11 // SDA pad + +#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_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 +#define PITOT_I2C_BUS BUS_I2C2 + +// *************** SD Card ************************** +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PB9 + +#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_SDCARD_BY_DEFAULT + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#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 PB12 + +// *************** UART ***************************** +#define USE_VCP + +#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_UART4 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 5 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_SCALE 65 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C2 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD) + +#define USE_LED_STRIP +#define WS2811_PIN PA1 // TIM2_CH2 + +#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 (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/target.h b/src/main/target/IFLIGHT_H743_AIO_V2/target.h index 96b8b73b2b..60a235e08c 100644 --- a/src/main/target/IFLIGHT_H743_AIO_V2/target.h +++ b/src/main/target/IFLIGHT_H743_AIO_V2/target.h @@ -40,17 +40,11 @@ #define IMU_MPU6000_ALIGN CW0_DEG #define MPU6000_CS_PIN SPI1_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PD0 #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW0_DEG #define BMI270_CS_PIN SPI1_NSS_PIN #define BMI270_SPI_BUS BUS_SPI1 -#define BMI270_EXTI_PIN - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW // *************** I2C1 Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/IFLIGHT_JBF7PRO/CMakeLists.txt b/src/main/target/IFLIGHT_JBF7PRO/CMakeLists.txt new file mode 100644 index 0000000000..d55220c6d2 --- /dev/null +++ b/src/main/target/IFLIGHT_JBF7PRO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(IFLIGHT_JBF7PRO) diff --git a/src/main/target/IFLIGHT_JBF7PRO/config.c b/src/main/target/IFLIGHT_JBF7PRO/config.c new file mode 100644 index 0000000000..c258dac74a --- /dev/null +++ b/src/main/target/IFLIGHT_JBF7PRO/config.c @@ -0,0 +1,29 @@ +/* + * This file is part of INAV Project. + * + * INAV Project 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 Project 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 Project. If not, see . + */ + +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} diff --git a/src/main/target/IFLIGHT_JBF7PRO/target.c b/src/main/target/IFLIGHT_JBF7PRO/target.c new file mode 100644 index 0000000000..7c8c15a741 --- /dev/null +++ b/src/main/target/IFLIGHT_JBF7PRO/target.c @@ -0,0 +1,42 @@ +/* +* This file is part of INAV Project. +* +* INAV Project 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 Project 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 Project. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S8 + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_JBF7PRO/target.h b/src/main/target/IFLIGHT_JBF7PRO/target.h new file mode 100644 index 0000000000..8c2dfd5a76 --- /dev/null +++ b/src/main/target/IFLIGHT_JBF7PRO/target.h @@ -0,0 +1,161 @@ +/* + * This file is part of INAV Project. + * + * INAV Project 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 Project 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 Project. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "IFJBF7" + +#define USBD_PRODUCT_STRING "IFLIGHT_JBF7PRO" + +#define LED0 PC15 + + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +// *************** I2C/Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 // SCL pad +#define I2C1_SDA PB9 // SDA pad + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 + +// *************** SD Card ************************** +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PA15 + +#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_SDCARD_BY_DEFAULT + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PC3 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC0 + +// *************** UART ***************************** +#define USE_VCP +#define VBUS_SENSING_PIN PB2 +#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 USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN NONE + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_LED_STRIP) + +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#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 (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_ESC_SENSOR diff --git a/src/main/target/JHEH7AIO/target.h b/src/main/target/JHEH7AIO/target.h index 42c14137f9..2290b828de 100644 --- a/src/main/target/JHEH7AIO/target.h +++ b/src/main/target/JHEH7AIO/target.h @@ -40,11 +40,6 @@ #define IMU_MPU6000_ALIGN CW0_DEG #define MPU6000_CS_PIN SPI1_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PD0 - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW // *************** I2C1 Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/KAKUTEF4/CMakeLists.txt b/src/main/target/KAKUTEF4/CMakeLists.txt index 074eb6cd35..ae1ba2a46a 100644 --- a/src/main/target/KAKUTEF4/CMakeLists.txt +++ b/src/main/target/KAKUTEF4/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32f405xg(KAKUTEF4) target_stm32f405xg(KAKUTEF4V2) +target_stm32f405xg(KAKUTEF4V23) \ No newline at end of file diff --git a/src/main/target/KAKUTEF4/target.c b/src/main/target/KAKUTEF4/target.c index 2888d3fe97..27bded1f2f 100755 --- a/src/main/target/KAKUTEF4/target.c +++ b/src/main/target/KAKUTEF4/target.c @@ -34,10 +34,17 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1_OUT - DMA1_ST7 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2_OUT - DMA1_ST2 DEF_TIM(TIM2, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S3_OUT - DMA1_ST6 +#if !defined(KAKUTEF4V23) DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S4_OUT - DMA1_ST1 -#if defined(KAKUTEF4V2) - DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 +#else + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT - DMA1_ST1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DMA1_ST0 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT - DMA1_ST3 +#endif + +#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 #else DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5_OUT - DMA1_ST2 DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S6_OUT - DMA2_ST4 diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h old mode 100755 new mode 100644 index 53f8b6b703..bf68496933 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -26,6 +26,9 @@ #if defined(KAKUTEF4V2) # define TARGET_BOARD_IDENTIFIER "KTV2" # define USBD_PRODUCT_STRING "KakuteF4-V2" +#elif defined(KAKUTEF4V23) +# define TARGET_BOARD_IDENTIFIER "KT23" +# define USBD_PRODUCT_STRING "KakuteF4-V2.3" #else # define TARGET_BOARD_IDENTIFIER "KTV1" # define USBD_PRODUCT_STRING "KakuteF4-V1" @@ -33,15 +36,14 @@ #define LED0 PB5 #define LED1 PB4 -#define LED2 PB6 + +#if !defined(KAKUTEF4V23) +# define LED2 PB6 +#endif #define BEEPER PC9 #define BEEPER_INVERTED -#define USE_EXTI -#define GYRO_INT_EXTI PC5 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN CW270_DEG #define MPU6500_CS_PIN PC4 @@ -52,7 +54,7 @@ #define MPU6000_CS_PIN PC4 #define MPU6000_SPI_BUS BUS_SPI1 -#ifdef KAKUTEF4V2 +#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) # define USE_I2C # define USE_I2C_DEVICE_1 # define I2C1_SCL PB8 // SCL pad @@ -108,7 +110,7 @@ #define UART6_RX_PIN PC7 #define UART6_TX_PIN PC6 -#ifdef KAKUTEF4V2 +#if defined(KAKUTEF4V2) || defined(KAKUTEF4V23) # define USE_UART4 # define UART4_RX_PIN PA1 # define UART4_TX_PIN PA0 diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h index 5c79231c69..064032b7f4 100644 --- a/src/main/target/KAKUTEF7/target.h +++ b/src/main/target/KAKUTEF7/target.h @@ -36,19 +36,16 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_MPU_DATA_READY_SIGNAL -#define USE_EXTI + // ICM-20689 #define USE_IMU_ICM20689 #define IMU_ICM20689_ALIGN CW270_DEG -#define GYRO_INT_EXTI PE1 #define ICM20689_CS_PIN SPI4_NSS_PIN #define ICM20689_SPI_BUS BUS_SPI4 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG -#define GYRO_INT_EXTI PE1 #define MPU6000_CS_PIN SPI4_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI4 diff --git a/src/main/target/KAKUTEF7MINIV3/target.h b/src/main/target/KAKUTEF7MINIV3/target.h index 702f1da860..c3d8983725 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.h +++ b/src/main/target/KAKUTEF7MINIV3/target.h @@ -82,17 +82,10 @@ #define SERIAL_PORT_COUNT 6 -/* - * Gyro - */ -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - // MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PA4 #define MPU6000_CS_PIN PB2 /* diff --git a/src/main/target/KAKUTEH7/CMakeLists.txt b/src/main/target/KAKUTEH7/CMakeLists.txt index f2b739773d..de2a8af3ce 100644 --- a/src/main/target/KAKUTEH7/CMakeLists.txt +++ b/src/main/target/KAKUTEH7/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32h743xi(KAKUTEH7) -target_stm32h743xi(KAKUTEH7MINI) +target_stm32h743xi(KAKUTEH7V2) +target_stm32h743xi(KAKUTEH7MINI) \ No newline at end of file diff --git a/src/main/target/KAKUTEH7/config.c b/src/main/target/KAKUTEH7/config.c index 01391c4bae..a2605ce372 100644 --- a/src/main/target/KAKUTEH7/config.c +++ b/src/main/target/KAKUTEH7/config.c @@ -30,10 +30,14 @@ void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +#ifdef KAKUTEH7V2 + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +#endif + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].msp_baudrateIndex = BAUD_115200; -#ifdef KAKUTEH7 +#if defined(KAKUTEH7) || defined(KAKUTEH7V2) //No BT on H7 Mini, do not reserve port serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].msp_baudrateIndex = BAUD_115200; diff --git a/src/main/target/KAKUTEH7/target.h b/src/main/target/KAKUTEH7/target.h index c28ffdff0b..086e621b0e 100644 --- a/src/main/target/KAKUTEH7/target.h +++ b/src/main/target/KAKUTEH7/target.h @@ -36,8 +36,7 @@ // *************** IMU generic *********************** -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL + // *************** SPI1 **************** @@ -47,17 +46,32 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#ifdef KAKUTEH7MINI +#if defined(KAKUTEH7MINI) #define USE_FLASHFS #define USE_FLASH_M25P16 #define M25P16_CS_PIN PA4 #define M25P16_SPI_BUS BUS_SPI1 +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI1 +#define W25N01G_CS_PIN PA4 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#elif defined(KAKUTEH7V2) + +#define USE_FLASHFS +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI1 +#define W25N01G_CS_PIN PA4 + #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT #else +//Regular Kakute H7 + #define USE_SDCARD #define USE_SDCARD_SPI #define SDCARD_SPI_BUS BUS_SPI1 @@ -82,13 +96,22 @@ #define SPI4_MISO_PIN PE5 #define SPI4_MOSI_PIN PE6 - +//MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_SPI_BUS BUS_SPI4 #define MPU6000_CS_PIN PE4 -#define MPU6000_EXTI_PIN PE1 +//BMI270 +#define USE_IMU_BMI270 +#define BMI270_SPI_BUS BUS_SPI4 +#define BMI270_CS_PIN PE4 + +#ifdef KAKUTEH7MINI +#define IMU_BMI270_ALIGN CW270_DEG +#else +#define IMU_BMI270_ALIGN CW0_DEG +#endif #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 @@ -174,6 +197,13 @@ #ifdef KAKUTEH7MINI #define PINIO1_PIN PB11 #define PINIO1_FLAGS PINIO_FLAGS_INVERTED + +#elif defined(KAKUTEH7V2) + +#define PINIO1_PIN PE13 +#define PINIO2_PIN PB11 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED + #else #define PINIO1_PIN PE13 #endif diff --git a/src/main/target/KROOZX/target.h b/src/main/target/KROOZX/target.h index aa90575ecb..9af00d2f72 100755 --- a/src/main/target/KROOZX/target.h +++ b/src/main/target/KROOZX/target.h @@ -31,11 +31,6 @@ #define MPU6000_CS_PIN PB2 #define MPU6000_SPI_BUS BUS_SPI1 -// MPU6000 interrupts -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PA4 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW90_DEG_FLIP diff --git a/src/main/target/MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h index 5cd798c2c0..d7ae8462fe 100644 --- a/src/main/target/MAMBAF405US/target.h +++ b/src/main/target/MAMBAF405US/target.h @@ -35,12 +35,6 @@ #define BEEPER PC13 #define BEEPER_INVERTED - -// ******* GYRO and ACC ******** -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG #define MPU6000_SPI_BUS BUS_SPI1 diff --git a/src/main/target/MAMBAF405_2022A/CMakeLists.txt b/src/main/target/MAMBAF405_2022A/CMakeLists.txt index 418424e653..96002d494e 100644 --- a/src/main/target/MAMBAF405_2022A/CMakeLists.txt +++ b/src/main/target/MAMBAF405_2022A/CMakeLists.txt @@ -1 +1,2 @@ target_stm32f405xg(MAMBAF405_2022A) +target_stm32f405xg(MAMBAF405_2022B) diff --git a/src/main/target/MAMBAF405_2022A/target.h b/src/main/target/MAMBAF405_2022A/target.h index 07e96ecac0..c4c20e127f 100644 --- a/src/main/target/MAMBAF405_2022A/target.h +++ b/src/main/target/MAMBAF405_2022A/target.h @@ -19,9 +19,14 @@ #define USE_TARGET_CONFIG -#define TARGET_BOARD_IDENTIFIER "M42A" +#ifdef MAMBAF405_2022B +#define USBD_PRODUCT_STRING "MAMBAF405_2022B" +#define TARGET_BOARD_IDENTIFIER "M42B" +#else +#define TARGET_BOARD_IDENTIFIER "M42A" #define USBD_PRODUCT_STRING "MAMBAF405_2022A" +#endif // ******** Board LEDs ********************** #define LED0 PC15 @@ -31,12 +36,6 @@ #define BEEPER PC13 #define BEEPER_INVERTED - -// ******* GYRO and ACC ******** -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - //MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG @@ -54,7 +53,15 @@ #define IMU_BMI270_ALIGN CW180_DEG #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN SPI1_NSS_PIN -#define BMI270_EXTI_PIN GYRO_INT_EXTI + +#ifdef MAMBAF405_2022B + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN + +#endif // *************** Baro ************************** #define USE_I2C @@ -147,6 +154,7 @@ #define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 #define VBAT_SCALE_DEFAULT 1100 +#define CURRENT_METER_SCALE 183 // ******* OSD ******** #define USE_MAX7456 diff --git a/src/main/target/MAMBAF722/target.h b/src/main/target/MAMBAF722/target.h index 9ee1753054..c536cc6017 100644 --- a/src/main/target/MAMBAF722/target.h +++ b/src/main/target/MAMBAF722/target.h @@ -34,12 +34,6 @@ #define BEEPER PB2 #define BEEPER_INVERTED - -// ******* GYRO and ACC ******** -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define MPU6000_CS_PIN SPI1_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI1 diff --git a/src/main/target/MAMBAF722_2022A/CMakeLists.txt b/src/main/target/MAMBAF722_2022A/CMakeLists.txt index 202a13f7cc..509cb74f5c 100644 --- a/src/main/target/MAMBAF722_2022A/CMakeLists.txt +++ b/src/main/target/MAMBAF722_2022A/CMakeLists.txt @@ -1 +1,2 @@ -target_stm32f722xe(MAMBAF722_2022A) \ No newline at end of file +target_stm32f722xe(MAMBAF722_2022A) +target_stm32f722xe(MAMBAF722_2022B) \ No newline at end of file diff --git a/src/main/target/MAMBAF722_2022A/target.h b/src/main/target/MAMBAF722_2022A/target.h index ae93f7e042..0752bb368b 100644 --- a/src/main/target/MAMBAF722_2022A/target.h +++ b/src/main/target/MAMBAF722_2022A/target.h @@ -19,9 +19,18 @@ #define USE_TARGET_CONFIG +#ifdef MAMBAF722_2022B + +#define TARGET_BOARD_IDENTIFIER "M72B" +#define USBD_PRODUCT_STRING "MAMBAF722_2022B" + +#else + #define TARGET_BOARD_IDENTIFIER "M72A" #define USBD_PRODUCT_STRING "MAMBAF722_2022A" +#endif + // ******** Board LEDs ********************** #define LED0 PC15 #define LED1 PC14 @@ -30,11 +39,6 @@ #define BEEPER PB2 #define BEEPER_INVERTED -// ******* GYRO and ACC ******** -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - //MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG @@ -52,7 +56,15 @@ #define IMU_BMI270_ALIGN CW180_DEG #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN SPI1_NSS_PIN -#define BMI270_EXTI_PIN GYRO_INT_EXTI + +#ifdef MAMBAF722_2022B + +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW270_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN + +#endif #define USE_I2C diff --git a/src/main/target/MAMBAF722_WING/CMakeLists.txt b/src/main/target/MAMBAF722_WING/CMakeLists.txt new file mode 100644 index 0000000000..c93eb08734 --- /dev/null +++ b/src/main/target/MAMBAF722_WING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(MAMBAF722_WING) \ No newline at end of file diff --git a/src/main/target/MAMBAF722_WING/config.c b/src/main/target/MAMBAF722_WING/config.c new file mode 100644 index 0000000000..4b9b627f1b --- /dev/null +++ b/src/main/target/MAMBAF722_WING/config.c @@ -0,0 +1,65 @@ +/* + * 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 + +#include + +#include "common/axis.h" + +#include "config/config_master.h" +#include "config/feature.h" + +#include "drivers/sensor.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" +#include "drivers/serial.h" + +#include "fc/rc_controls.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "telemetry/telemetry.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; + + /* + * UART1 is SerialRX + */ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + + /* + * Enable MSP at 115200 at UART4 + */ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200; +} diff --git a/src/main/target/MAMBAF722_WING/target.c b/src/main/target/MAMBAF722_WING/target.c new file mode 100644 index 0000000000..c39247afe5 --- /dev/null +++ b/src/main/target/MAMBAF722_WING/target.c @@ -0,0 +1,41 @@ +/* + * 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/io.h" +#include "drivers/timer.h" +#include "drivers/pwm_mapping.h" +#include "drivers/bus.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S1 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0 ), // S2 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S8 + + DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MAMBAF722_WING/target.h b/src/main/target/MAMBAF722_WING/target.h new file mode 100644 index 0000000000..a877a74e65 --- /dev/null +++ b/src/main/target/MAMBAF722_WING/target.h @@ -0,0 +1,171 @@ +/* + * 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 USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "M72W" +#define USBD_PRODUCT_STRING "MAMBAF722_WING" + +// ******** Board LEDs ********************** +#define LED0 PC15 +#define LED1 PC14 + +// ******* Beeper *********** +#define BEEPER PB2 +#define BEEPER_INVERTED + +// ******* GYRO and ACC ******** +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN SPI1_NSS_PIN + +#define USE_I2C + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 +#define DEFAULT_I2C_BUS BUS_I2C1 + +// *************** Baro ************************** +#define USE_BARO +#define BARO_I2C_BUS DEFAULT_I2C_BUS +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 + +//*********** Magnetometer / Compass ************* +#define USE_MAG +#define MAG_I2C_BUS DEFAULT_I2C_BUS + +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +// ******* SERIAL ******** +#define USE_VCP +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 +#define USE_UART4 +#define USE_UART5 +#define USE_UART6 + +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 7 + +// ******* SPI ******** +#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_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_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +// ******* ADC ******** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +#define VBAT_SCALE_DEFAULT 1100 + +// ******* OSD ******** +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +//******* FLASH ******** +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN SPI3_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +//************ LEDSTRIP ***************** +#define USE_LED_STRIP +#define WS2811_PIN PB3 + +// ******* FEATURES ******** +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY) + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 8 +#define TARGET_MOTOR_COUNT 8 + +// ESC-related features +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS +#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS +#define PITOT_I2C_BUS DEFAULT_I2C_BUS + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC0 +#define PINIO2_PIN PC2 \ No newline at end of file diff --git a/src/main/target/MAMBAF722_X8/target.h b/src/main/target/MAMBAF722_X8/target.h index 6a3bd4f26f..2c8c84e9d1 100644 --- a/src/main/target/MAMBAF722_X8/target.h +++ b/src/main/target/MAMBAF722_X8/target.h @@ -30,11 +30,6 @@ #define BEEPER PB2 #define BEEPER_INVERTED -// ******* GYRO and ACC ******** -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define MPU6000_CS_PIN SPI1_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI1 diff --git a/src/main/target/MAMBAH743/CMakeLists.txt b/src/main/target/MAMBAH743/CMakeLists.txt index 580075fe29..61b073da93 100644 --- a/src/main/target/MAMBAH743/CMakeLists.txt +++ b/src/main/target/MAMBAH743/CMakeLists.txt @@ -1 +1,2 @@ target_stm32h743xi(MAMBAH743) +target_stm32h743xi(MAMBAH743_2022B) \ No newline at end of file diff --git a/src/main/target/MAMBAH743/config.c b/src/main/target/MAMBAH743/config.c index bdbc7da73c..cc04e10319 100644 --- a/src/main/target/MAMBAH743/config.c +++ b/src/main/target/MAMBAH743/config.c @@ -15,16 +15,54 @@ * along with Cleanflight. If not, see . */ +#include #include -#include "platform.h" +#include -#include "fc/fc_msp_box.h" -#include "fc/config.h" +#include "common/axis.h" + +#include "config/config_master.h" +#include "config/feature.h" + +#include "drivers/sensor.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" +#include "drivers/serial.h" + +#include "fc/rc_controls.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "telemetry/telemetry.h" #include "io/piniobox.h" void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + +#ifdef MAMBAH743_2022B + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +#endif + + /* + * UART1 is SerialRX + */ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + + /* + * Enable MSP at 115200 at UART4 + */ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_115200; } diff --git a/src/main/target/MAMBAH743/target.c b/src/main/target/MAMBAH743/target.c index 909df49a07..f684670a22 100644 --- a/src/main/target/MAMBAH743/target.c +++ b/src/main/target/MAMBAH743/target.c @@ -26,8 +26,12 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +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 +BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); +#endif timerHardware_t timerHardware[] = { diff --git a/src/main/target/MAMBAH743/target.h b/src/main/target/MAMBAH743/target.h index 6686d86a03..27a65ded29 100644 --- a/src/main/target/MAMBAH743/target.h +++ b/src/main/target/MAMBAH743/target.h @@ -17,9 +17,18 @@ #pragma once +#ifdef MAMBAH743_2022B + +#define TARGET_BOARD_IDENTIFIER "M743" +#define USBD_PRODUCT_STRING "MAMBAH743_2022B" + +#else + #define TARGET_BOARD_IDENTIFIER "M743" #define USBD_PRODUCT_STRING "MAMBAH743" +#endif + #define USE_TARGET_CONFIG #define LED0 PE5 @@ -32,9 +41,6 @@ #define USE_DUAL_GYRO #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - // *************** SPI1 IMU0 MPU6000 **************** #define USE_SPI #define USE_SPI_DEVICE_1 @@ -42,23 +48,30 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PA4 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +#ifdef MAMBAH743_2022B + // SPI4 is used on the second MPU6000 gyro, we do not use it at the moment // #define USE_SPI_DEVICE_4 // #define SPI4_SCK_PIN PE12 // #define SPI4_MISO_PIN PE13 // #define SPI4_MOSI_PIN PE14 -#define USE_IMU_MPU6000 -#define IMU_MPU6000_ALIGN CW180_DEG -#define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_CS_PIN PA4 -#define MPU6000_EXTI_PIN PC4 +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI1 +#define ICM42605_CS_PIN PA4 -#define USE_IMU_BMI270 -#define IMU_BMI270_ALIGN CW180_DEG -#define BMI270_SPI_BUS BUS_SPI1 -#define BMI270_CS_PIN PA4 -#define BMI270_EXTI_PIN PC4 +#endif // *************** SPI2 OSD *********************** #define USE_SPI_DEVICE_2 @@ -164,12 +177,23 @@ #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART6 // *************** ADC ***************************** #define USE_ADC #define ADC_INSTANCE ADC3 +#ifdef MAMBAH743_2022B + +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_3 + +#else + #define ADC_CHANNEL_1_PIN PC1 #define ADC_CHANNEL_2_PIN PC3 #define ADC_CHANNEL_3_PIN PC2 @@ -180,11 +204,23 @@ #define RSSI_ADC_CHANNEL ADC_CHN_3 #define AIRSPEED_ADC_CHANNEL ADC_CHN_4 +#endif + // *************** PINIO *************************** #define USE_PINIO #define USE_PINIOBOX + +#ifdef MAMBAH743_2022B + +#define PINIO1_PIN PC2 +#define PINIO2_PIN PC5 + +#else + #define PINIO1_PIN PC5 +#endif + // *************** LEDSTRIP ************************ #define USE_LED_STRIP #define WS2811_PIN PA8 diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index e549c26b8d..fa2af63384 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -41,10 +41,6 @@ #define MPU6000_CS_PIN PC2 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC3 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN CW180_DEG @@ -183,7 +179,7 @@ #define CURRENT_METER_SCALE 179 #define USE_LED_STRIP -#define WS2811_PIN PA15 // S5 pad for iNav +#define WS2811_PIN PA15 // S5 pad for INAV #define USE_SPEKTRUM_BIND #define BIND_PIN PA3 // RX2 diff --git a/src/main/target/MATEKF405CAN/target.h b/src/main/target/MATEKF405CAN/target.h index 58291d493f..81aa91ce99 100644 --- a/src/main/target/MATEKF405CAN/target.h +++ b/src/main/target/MATEKF405CAN/target.h @@ -40,11 +40,6 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** I2C /Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_2 diff --git a/src/main/target/MATEKF405SE/CMakeLists.txt b/src/main/target/MATEKF405SE/CMakeLists.txt index 2c754ecea8..6d8f0adbac 100644 --- a/src/main/target/MATEKF405SE/CMakeLists.txt +++ b/src/main/target/MATEKF405SE/CMakeLists.txt @@ -1 +1,2 @@ target_stm32f405xg(MATEKF405SE) +target_stm32f405xg(MATEKF405SE_PINIO) diff --git a/src/main/target/MATEKF405SE/README.md b/src/main/target/MATEKF405SE/README.md index e07ed0cba9..afbec4aa5e 100644 --- a/src/main/target/MATEKF405SE/README.md +++ b/src/main/target/MATEKF405SE/README.md @@ -13,4 +13,7 @@ * 1x Softserial * 2x I2C * 2x Motors & 7x Servos -* 4x BEC + current sensor \ No newline at end of file +* 4x BEC + current sensor + +### MATEKF405SE_PINIO +Replaces UART 6 Tx with USER 1 for PINIO and UART 6 Rx with USER 2 for PINIO \ No newline at end of file diff --git a/src/main/target/MATEKF405SE/config.c b/src/main/target/MATEKF405SE/config.c index c6176712f9..55a5e67099 100644 --- a/src/main/target/MATEKF405SE/config.c +++ b/src/main/target/MATEKF405SE/config.c @@ -17,16 +17,26 @@ #include #include + #include "config/config_master.h" #include "config/feature.h" + #include "flight/mixer.h" + #include "io/serial.h" + #include "telemetry/telemetry.h" +#include "fc/fc_msp_box.h" +#include "io/piniobox.h" // alternative defaults settings for MATEKF405SE targets void targetConfiguration(void) -{ - +{ +#ifdef MATEKF405SE_PINIO + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +#endif + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600; diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 6c62cea529..724a9a2c2d 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -20,8 +20,11 @@ #define TARGET_BOARD_IDENTIFIER "MF4S" #define USBD_PRODUCT_STRING "Matek_F405SE" +// ******** Board LEDs ********************** #define LED0 PA14 //Blue #define LED1 PA13 //Green + +// ******* Beeper *********** #define BEEPER PC15 #define BEEPER_INVERTED @@ -33,16 +36,12 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 +// MPU6000 #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** I2C /Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 @@ -126,9 +125,11 @@ #define UART5_TX_PIN PC12 #define UART5_RX_PIN PD2 +#ifndef MATEKF405SE_PINIO #define USE_UART6 #define UART6_TX_PIN PC6 #define UART6_RX_PIN PC7 +#endif #define USE_SOFTSERIAL1 //Frsky SmartPort on TX2 pad #define SOFTSERIAL_1_TX_PIN PA2 @@ -158,6 +159,14 @@ #define WS2811_DMA_STREAM DMA1_Stream5 #define WS2811_DMA_CHANNEL DMA_Channel_3 +// *************** PINIO *************************** +#ifdef MATEKF405SE_PINIO +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC6 // USER 1 +#define PINIO2_PIN PC7 // USER 2 +#endif + // *************** OTHERS ************************* #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) #define CURRENT_METER_SCALE 317 @@ -167,7 +176,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR - #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/MATEKF405TE/target.h b/src/main/target/MATEKF405TE/target.h index c9e2beba9c..93ab3345de 100644 --- a/src/main/target/MATEKF405TE/target.h +++ b/src/main/target/MATEKF405TE/target.h @@ -45,16 +45,13 @@ #define IMU_ICM42605_ALIGN CW270_DEG_FLIP #define ICM42605_SPI_BUS BUS_SPI1 #define ICM42605_CS_PIN PC14 -#define ICM42605_EXTI_PIN PC15 #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW270_DEG_FLIP #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PC14 -#define BMI270_EXTI_PIN PC15 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL + #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI1 diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index 5d4c130a92..0bf0aab198 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -45,10 +45,6 @@ #define MPU6500_CS_PIN PA4 #define MPU6500_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PA1 -#define USE_MPU_DATA_READY_SIGNAL - // *************** SPI2 OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index 44362e8f9a..abb4688457 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -39,11 +39,6 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PA14 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** SPI2 OSD ***************************** #define USE_SPI_DEVICE_2 #define SPI2_SCK_PIN PB13 diff --git a/src/main/target/MATEKF411TE/target.h b/src/main/target/MATEKF411TE/target.h index a329f4862f..a410a2c135 100644 --- a/src/main/target/MATEKF411TE/target.h +++ b/src/main/target/MATEKF411TE/target.h @@ -36,10 +36,8 @@ #define USE_IMU_BMI270 #define BMI270_SPI_BUS BUS_SPI2 #define BMI270_CS_PIN PC13 -#define USE_EXTI -#define BMI270_EXTI_PIN PC14 #define IMU_BMI270_ALIGN CW270_DEG_FLIP -#define USE_MPU_DATA_READY_SIGNAL + #define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI2 diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index de38d02e16..49cc5fac09 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -40,11 +40,6 @@ #define MPU6500_CS_PIN PC2 #define MPU6500_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC3 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** I2C/Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 diff --git a/src/main/target/MATEKF722PX/CMakeLists.txt b/src/main/target/MATEKF722PX/CMakeLists.txt index 069c6db389..9583f3a466 100644 --- a/src/main/target/MATEKF722PX/CMakeLists.txt +++ b/src/main/target/MATEKF722PX/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32f722xe(MATEKF722PX) +target_stm32f722xe(MATEKF722PX_PINIO) target_stm32f722xe(MATEKF722WPX) diff --git a/src/main/target/MATEKF722PX/config.c b/src/main/target/MATEKF722PX/config.c index cd7d7d0e4a..9d1a940c91 100755 --- a/src/main/target/MATEKF722PX/config.c +++ b/src/main/target/MATEKF722PX/config.c @@ -31,6 +31,10 @@ void targetConfiguration(void) { pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; +#ifdef MATEKF722PX_PINIO + pinioBoxConfigMutable()->permanentId[2] = BOX_PERMANENT_ID_USER3; + pinioBoxConfigMutable()->permanentId[3] = BOX_PERMANENT_ID_USER4; +#endif serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_FRSKY_OSD; } diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index 89a33c2aa1..ad30f96f08 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -34,10 +34,6 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PC4 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG_FLIP #define MPU6000_CS_PIN PB2 @@ -115,9 +111,11 @@ #define UART4_TX_PIN PA0 #define UART4_RX_PIN PA1 +#ifndef MATEKF722PX_PINIO #define USE_UART5 #define UART5_TX_PIN PC12 #define UART5_RX_PIN PD2 +#endif #define USE_UART6 #define UART6_TX_PIN PC6 @@ -154,6 +152,11 @@ #define PINIO1_PIN PA15 // Power switch #define PINIO2_PIN PB3 // Camera switch +#ifdef MATEKF722PX_PINIO +#define PINIO3_PIN PC12 // UART 5 TX - USER 3 PINIO +#define PINIO4_PIN PD2 // UART 5 RX - USER 4 PINIO +#endif + // *************** LEDSTRIP ************************ #define USE_LED_STRIP #define WS2811_PIN PA8 diff --git a/src/main/target/MATEKF722SE/target.c b/src/main/target/MATEKF722SE/target.c index 6ebfb67f8b..1ea322fb82 100644 --- a/src/main/target/MATEKF722SE/target.c +++ b/src/main/target/MATEKF722SE/target.c @@ -26,8 +26,8 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +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_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index bf2e559c14..04dc0d8123 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -47,18 +47,11 @@ #define IMU_MPU6000_ALIGN CW180_DEG_FLIP #define MPU6000_CS_PIN PB2 #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PC4 #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN CW90_DEG #define MPU6500_CS_PIN PC15 #define MPU6500_SPI_BUS BUS_SPI1 -#define MPU6500_EXTI_PIN PC3 - - - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL // *************** I2C /Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/MATEKF765/target.c b/src/main/target/MATEKF765/target.c index 751eeecb3f..0a4e42ac9c 100644 --- a/src/main/target/MATEKF765/target.c +++ b/src/main/target/MATEKF765/target.c @@ -26,11 +26,11 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu0, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu1, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); #if defined(MATEKF765SE) -BUSDEV_REGISTER_SPI_TAG(busdev_imu3, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_imu3, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); #endif timerHardware_t timerHardware[] = { diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index 5ef88efadb..e40fe455be 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -55,25 +55,19 @@ #define IMU_MPU6000_ALIGN CW90_DEG_FLIP #define MPU6000_SPI_BUS BUS_SPI1 #define MPU6000_CS_PIN PC4 -#define MPU6000_EXTI_PIN PB2 #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN CW270_DEG_FLIP #define MPU6500_SPI_BUS BUS_SPI3 #define MPU6500_CS_PIN PD7 -#define MPU6500_EXTI_PIN PD4 #if defined(MATEKF765SE) #define USE_IMU_ICM42605 #define IMU_ICM42605_ALIGN CW0_DEG_FLIP #define ICM42605_SPI_BUS BUS_SPI4 #define ICM42605_CS_PIN PE11 -#define ICM42605_EXTI_PIN PC13 #endif -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - // *************** I2C /Baro/Mag ********************* #define USE_I2C #define USE_I2C_DEVICE_1 diff --git a/src/main/target/MATEKH743/target.c b/src/main/target/MATEKH743/target.c index d51872b5a9..706d578786 100644 --- a/src/main/target/MATEKH743/target.c +++ b/src/main/target/MATEKH743/target.c @@ -26,10 +26,10 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_icm20602, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, ICM42605_EXTI_PIN, 2, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); +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_icm42688, DEVHW_ICM42605, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm20602, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 2, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 886eb12b55..37742a88fc 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -34,8 +34,7 @@ #define USE_DUAL_GYRO #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL + // *************** SPI1 IMU0 MPU6000 **************** #define USE_SPI @@ -49,7 +48,6 @@ #define IMU_MPU6000_ALIGN CW0_DEG_FLIP #define MPU6000_SPI_BUS BUS_SPI1 #define MPU6000_CS_PIN PC15 -#define MPU6000_EXTI_PIN PB2 // *************** SPI4 IMU1 ICM20602 ************** #define USE_SPI_DEVICE_4 @@ -62,7 +60,6 @@ #define IMU_MPU6500_ALIGN CW0_DEG_FLIP #define MPU6500_SPI_BUS BUS_SPI4 #define MPU6500_CS_PIN PE11 -#define MPU6500_EXTI_PIN PE15 // *************** SPI4 IMU2 ICM42605 ************** #define USE_IMU_ICM42605 @@ -70,8 +67,6 @@ #define IMU_ICM42605_ALIGN CW90_DEG_FLIP #define ICM42605_SPI_BUS BUS_SPI4 #define ICM42605_CS_PIN PC13 -#define ICM42605_EXTI_PIN PC14 - // *************** SPI2 OSD *********************** #define USE_SPI_DEVICE_2 diff --git a/src/main/target/NEUTRONRCH7BT/target.h b/src/main/target/NEUTRONRCH7BT/target.h index a8ca94f3fa..78a1949e04 100644 --- a/src/main/target/NEUTRONRCH7BT/target.h +++ b/src/main/target/NEUTRONRCH7BT/target.h @@ -33,9 +33,6 @@ // #define USE_DUAL_GYRO // #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL - // *************** SPI1 IMU0 BMI270 ***************** #define USE_SPI #define USE_SPI_DEVICE_1 @@ -48,7 +45,6 @@ #define IMU_BMI270_ALIGN CW270_DEG #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PC15 -#define BMI270_EXTI_PIN PB2 // *************** SPI4 IMU1 BMI270 ***************** #define USE_SPI_DEVICE_4 @@ -61,7 +57,6 @@ // #define IMU_BMI270_ALIGN CW0_DEG_FLIP // #define BMI270_SPI_BUS BUS_SPI4 // #define BMI270_CS_PIN PE11 -// #define BMI270_EXTI_PIN PE15 // *************** SPI2 OSD *********************** #define USE_SPI_DEVICE_2 diff --git a/src/main/target/NOX/target.h b/src/main/target/NOX/target.h index 764e889bb4..0c32bcb6e3 100755 --- a/src/main/target/NOX/target.h +++ b/src/main/target/NOX/target.h @@ -48,11 +48,6 @@ #define MPU6000_CS_PIN PB12 #define MPU6000_SPI_BUS BUS_SPI2 -#define USE_EXTI -#define GYRO_INT_EXTI PA8 -#define USE_MPU_DATA_READY_SIGNAL - - // *************** SPI BARO ***************************** #define USE_BARO #define USE_BARO_BMP280 diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index f150539a2c..2c0bd22801 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -64,11 +64,6 @@ #define UG2864_I2C_BUS I2C_EXT_BUS -// MPU6000 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 @@ -86,6 +81,12 @@ #define MPU6500_SPI_BUS MPU6000_SPI_BUS #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN IMU_MPU6000_ALIGN + + //BMI270 + #define USE_IMU_BMI270 + #define IMU_BMI270_ALIGN IMU_MPU6000_ALIGN + #define BMI270_SPI_BUS MPU6000_SPI_BUS + #define BMI270_CS_PIN MPU6000_CS_PIN #endif #define USE_MAG diff --git a/src/main/target/OMNIBUSF7/target.c b/src/main/target/OMNIBUSF7/target.c index 25c97bb9b6..c11e1629bf 100644 --- a/src/main/target/OMNIBUSF7/target.c +++ b/src/main/target/OMNIBUSF7/target.c @@ -23,8 +23,8 @@ #include "drivers/sensor.h" /* GYRO */ -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +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_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); BUSDEV_REGISTER_SPI( busdev_bmp280, DEVHW_BMP280, BMP280_SPI_BUS, BMP280_CS_PIN, NONE, DEVFLAGS_NONE, 0); diff --git a/src/main/target/OMNIBUSF7/target.h b/src/main/target/OMNIBUSF7/target.h index 14731f566a..6a5a9d6ea9 100644 --- a/src/main/target/OMNIBUSF7/target.h +++ b/src/main/target/OMNIBUSF7/target.h @@ -38,33 +38,27 @@ // MPU6000 #ifdef OMNIBUSF7V2 -# define USE_IMU_MPU6000 -# define IMU_MPU6000_ALIGN CW0_DEG -# define MPU6000_CS_PIN SPI1_NSS_PIN -# define MPU6000_SPI_BUS BUS_SPI1 -# define MPU6000_EXTI_PIN PE8 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI1 -# define USE_IMU_MPU6500 -# define IMU_MPU6500_ALIGN CW90_DEG -# define MPU6500_CS_PIN SPI3_NSS_PIN -# define MPU6500_SPI_BUS BUS_SPI3 -# define MPU6500_EXTI_PIN PD0 +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW90_DEG +#define MPU6500_CS_PIN SPI3_NSS_PIN +#define MPU6500_SPI_BUS BUS_SPI3 #else -# define USE_IMU_MPU6000 -# define IMU_MPU6000_ALIGN CW0_DEG -# define MPU6000_CS_PIN SPI3_NSS_PIN -# define MPU6000_SPI_BUS BUS_SPI3 -# define MPU6000_EXTI_PIN PD0 +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_CS_PIN SPI3_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI3 -# define USE_IMU_MPU6500 -# define IMU_MPU6500_ALIGN CW0_DEG -# define MPU6500_CS_PIN SPI1_NSS_PIN -# define MPU6500_SPI_BUS BUS_SPI1 -# define MPU6500_EXTI_PIN PE8 +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW0_DEG +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_BUS BUS_SPI1 #endif -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL #define USE_VCP #define VBUS_SENSING_PIN PC4 diff --git a/src/main/target/PIXRACER/README.md b/src/main/target/PIXRACER/README.md old mode 100755 new mode 100644 index 3e79da8e70..e513f3993c --- a/src/main/target/PIXRACER/README.md +++ b/src/main/target/PIXRACER/README.md @@ -1,21 +1,29 @@ -# Pixracer +# PixRacer * Target owner: @DigitalEntity -* The Pixracer is the first autopilot of the new FMUv4 Pixhawk generation. It has Wifi built-in, comes with upgraded sensors and more flash. -* Website: https://pixhawk.org/modules/pixracer -* Purchase from: http://www.auav.co/product-p/xr-v1.htm +* The PixRacer is the first autopilot of the new FMUv4 Pixhawk generation. It has Wifi built-in, comes with upgraded sensors and more flash. +* Website: https://store.mrobotics.io/mRo-PixRacer-R14-Official-p/auav-pxrcr-r14-mr.htm ## HW info * STM32F427VIT6 -* ICM-20608 SPI * MPU9250 SPI -* HMC5983 compass * MS5611 baro * 6 pwm outputs + PPM/SBus input +## R14 + +* ICM-20608 SPI +* HMC5983 compass + +## R15 + +* ICM-20608 or ICM-20602 SPI +* LIS3MDL compass + ## Warnings -* PicRacers native Flight controller (PX4 & ArduPilot) motor layout is different to iNAV - * Either Swap your ESC PWM cables to match iNav - * Or make a custom mix + +* PixRacers native Flight controller (PX4 & ArduPilot) motor layout is different to INAV +* Either Swap your ESC PWM cables to match INAV +* Or make a custom mix diff --git a/src/main/target/PIXRACER/target.c b/src/main/target/PIXRACER/target.c index 5a86a0f329..294c962f24 100755 --- a/src/main/target/PIXRACER/target.c +++ b/src/main/target/PIXRACER/target.c @@ -24,8 +24,8 @@ #include "drivers/sensor.h" #include "drivers/bus.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, MPU9250_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU9250_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_icm20608, DEVHW_MPU6500, ICM20608_SPI_BUS, ICM20608_CS_PIN, ICM20608_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU9250_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_icm20608, DEVHW_MPU6500, ICM20608_SPI_BUS, ICM20608_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); BUSDEV_REGISTER_SPI_TAG(busdev_ms5611, DEVHW_MS5611, MS5611_SPI_BUS, MS5611_CS_PIN, NONE, 0, DEVFLAGS_USE_RAW_REGISTERS, 0); diff --git a/src/main/target/PIXRACER/target.h b/src/main/target/PIXRACER/target.h index e700d09aa6..738fc1ad91 100755 --- a/src/main/target/PIXRACER/target.h +++ b/src/main/target/PIXRACER/target.h @@ -28,7 +28,6 @@ // PixRacer target requires some hardware to be set up before booting and detecting sensors #define USE_HARDWARE_PREBOOT_SETUP -#define USE_EXTI #define LED0 PB11 //red #define LED1 PB3 //blue @@ -49,12 +48,10 @@ // ICM20608 #define ICM20608_CS_PIN PC15 -#define ICM20608_EXTI_PIN PC14 #define ICM20608_SPI_BUS BUS_SPI1 // MPU9250 gyro/acc/mag #define MPU9250_CS_PIN PC2 -#define MPU9250_EXTI_PIN PD15 #define MPU9250_SPI_BUS BUS_SPI1 #define USE_MAG @@ -80,11 +77,6 @@ #define SDCARD_SDIO_4BIT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -// MPU9250 interrupt -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW -#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready - #define USE_VCP #define VBUS_SENSING_PIN PA9 #define VBUS_SENSING_ENABLED diff --git a/src/main/target/RADIX/target.h b/src/main/target/RADIX/target.h index dd29db84e6..95b3957698 100644 --- a/src/main/target/RADIX/target.h +++ b/src/main/target/RADIX/target.h @@ -26,10 +26,8 @@ #define BEEPER NONE -#define USE_EXTI #define BMI160_SPI_BUS BUS_SPI3 #define BMI160_CS_PIN PB4 -#define GYRO_EXTI_PIN PC13 #define USE_IMU_BMI160 #define IMU_BMI160_ALIGN CW0_DEG diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index fd7f79213f..29619624df 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -32,11 +32,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -// MPU6000 interrupts -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_CS_PIN PA4 diff --git a/src/main/target/RUSH_BLADE_F7/target.h b/src/main/target/RUSH_BLADE_F7/target.h index 9ad6e1ccd0..89ac040e2b 100644 --- a/src/main/target/RUSH_BLADE_F7/target.h +++ b/src/main/target/RUSH_BLADE_F7/target.h @@ -34,10 +34,6 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PA4 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #define MPU6000_CS_PIN PC4 diff --git a/src/main/target/SKYSTARSF405HD/config.c b/src/main/target/SKYSTARSF405HD/config.c index 6dd129e144..a327f7a460 100644 --- a/src/main/target/SKYSTARSF405HD/config.c +++ b/src/main/target/SKYSTARSF405HD/config.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/target/SKYSTARSF405HD/target.c b/src/main/target/SKYSTARSF405HD/target.c index 9ea328de80..e6bec48b4c 100644 --- a/src/main/target/SKYSTARSF405HD/target.c +++ b/src/main/target/SKYSTARSF405HD/target.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h index 03447e3fed..ac88a72084 100644 --- a/src/main/target/SKYSTARSF405HD/target.h +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #pragma once @@ -35,21 +35,15 @@ #define SPI1_MISO_PIN PA6 #define SPI1_MOSI_PIN PA7 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW180_DEG_FLIP #define MPU6000_SPI_BUS BUS_SPI1 #define MPU6000_CS_PIN PA4 -//#define MPU6000_EXTI_PIN GYRO_INT_EXTI #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW180_DEG_FLIP #define BMI270_SPI_BUS BUS_SPI1 #define BMI270_CS_PIN PA4 -#define BMI270_EXTI_PIN GYRO_INT_EXTI // *************** M25P256 flash ******************** #define USE_FLASHFS diff --git a/src/main/target/SKYSTARSF722HD/config.c b/src/main/target/SKYSTARSF722HD/config.c index 6dd129e144..a327f7a460 100644 --- a/src/main/target/SKYSTARSF722HD/config.c +++ b/src/main/target/SKYSTARSF722HD/config.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/target/SKYSTARSF722HD/target.c b/src/main/target/SKYSTARSF722HD/target.c index 28d9e8b757..cf5906d915 100644 --- a/src/main/target/SKYSTARSF722HD/target.c +++ b/src/main/target/SKYSTARSF722HD/target.c @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #include diff --git a/src/main/target/SKYSTARSF722HD/target.h b/src/main/target/SKYSTARSF722HD/target.h index d1d75c8ad4..1435b94f50 100644 --- a/src/main/target/SKYSTARSF722HD/target.h +++ b/src/main/target/SKYSTARSF722HD/target.h @@ -1,18 +1,18 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav 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. * - * iNav 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 iNav. If not, see . + * along with INAV. If not, see . */ #pragma once @@ -38,10 +38,6 @@ #define BMI270_CS_PIN PA4 #define BMI270_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_IMU_BMI270 #define IMU_BMI270_ALIGN CW90_DEG_FLIP diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h index 830ec23c33..76d6e93099 100644 --- a/src/main/target/SPARKY2/target.h +++ b/src/main/target/SPARKY2/target.h @@ -29,16 +29,11 @@ #define BEEPER PC9 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define USE_IMU_MPU9250 #define IMU_MPU9250_ALIGN CW270_DEG #define MPU9250_SPI_BUS BUS_SPI1 #define MPU9250_CS_PIN PC4 -#define GYRO_INT_EXTI PC5 #define USE_MAG #define USE_MAG_MPU9250 diff --git a/src/main/target/SPEEDYBEEF4/target.h b/src/main/target/SPEEDYBEEF4/target.h index 13d72d8071..ff7fc7189a 100644 --- a/src/main/target/SPEEDYBEEF4/target.h +++ b/src/main/target/SPEEDYBEEF4/target.h @@ -23,15 +23,9 @@ /*** Indicators ***/ #define LED0 PB9 #define BEEPER PC13 -#define BEEPER_INVERTED +#define BEEPER_INVERTED -/*** IMU sensors ***/ -#define USE_EXTI - -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - -#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO) +#define SENSORS_SET (SENSOR_ACC | SENSOR_MAG | SENSOR_BARO) /*** MPU6000 ***/ #define USE_IMU_MPU6000 diff --git a/src/main/target/SPEEDYBEEF405V3/CMakeLists.txt b/src/main/target/SPEEDYBEEF405V3/CMakeLists.txt new file mode 100644 index 0000000000..f54e24c5a1 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(SPEEDYBEEF405V3) diff --git a/src/main/drivers/accgyro/accgyro_bno055.h b/src/main/target/SPEEDYBEEF405V3/config.c similarity index 61% rename from src/main/drivers/accgyro/accgyro_bno055.h rename to src/main/target/SPEEDYBEEF405V3/config.c index 7e5e7b7f6c..c33c883957 100644 --- a/src/main/drivers/accgyro/accgyro_bno055.h +++ b/src/main/target/SPEEDYBEEF405V3/config.c @@ -1,5 +1,5 @@ /* - * This file is part of INAV. + * This file is part of INAV Project. * * This Source Code Form is subject to the terms of the Mozilla Public * License, v. 2.0. If a copy of the MPL was not distributed with this file, @@ -21,13 +21,21 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see http://www.gnu.org/licenses/. */ -#pragma once -#include "common/vector.h" +#include +#include +#include "platform.h" -bool bno055Init(bno055CalibrationData_t calibrationData, bool setCalibration); -fpVector3_t bno055GetEurlerAngles(void); -void bno055FetchEulerAngles(int16_t * buffer); -bno055CalibStat_t bno055GetCalibStat(void); -bno055CalibrationData_t bno055GetCalibrationData(void); \ No newline at end of file +#include "fc/fc_msp_box.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_RX_SERIAL; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP; + // serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_ESCSERIAL; +} diff --git a/src/main/target/SPEEDYBEEF405V3/target.c b/src/main/target/SPEEDYBEEF405V3/target.c new file mode 100644 index 0000000000..fffac26520 --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V3/target.c @@ -0,0 +1,51 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#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" + +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S3 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + + DEF_TIM(TIM8, CH4, PC9, TIM_USE_LED, 0, 0), // LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF405V3/target.h b/src/main/target/SPEEDYBEEF405V3/target.h new file mode 100644 index 0000000000..d7bb949b2e --- /dev/null +++ b/src/main/target/SPEEDYBEEF405V3/target.h @@ -0,0 +1,169 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute 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. + * + * This file 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 this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SB43" +#define USBD_PRODUCT_STRING "SpeedyBeeF405V3" + +/*** Indicators ***/ +#define LED0 PC8 +#define BEEPER PC5 +#define BEEPER_INVERTED + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC3 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED + +// *************** UART ***************************** +#define USB_IO +#define USE_VCP + +#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 USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 7 + +// *************** Gyro & ACC ********************** +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PA4 + +// *************** I2C(Baro & I2C) ************************** +#define USE_I2C +#define DEFAULT_I2C_BUS BUS_I2C2 + +#define USE_I2C_DEVICE_2 +#define I2C1_SCL PB10 +#define I2C1_SDA PB11 + +// Baro +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 +#define BARO_I2C_BUS BUS_I2C2 + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +// *************** Internal SD card ************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI2 +#define SDCARD_CS_PIN PA15 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** OSD ***************************** +#define USE_OSD + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** LED ***************************** +#define USE_LED_STRIP +#define WS2811_PIN PC9 + +// ********** Optiical Flow adn Lidar ************** +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +#define TEMPERATURE_I2C_BUS BUS_I2C2 +#define PITOT_I2C_BUS BUS_I2C2 +#define RANGEFINDER_I2C_BUS BUS_I2C2 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) +// #define USE_DSHOT +// #define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define CURRENT_METER_SCALE 386 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) diff --git a/src/main/target/SPEEDYBEEF7/target.h b/src/main/target/SPEEDYBEEF7/target.h index a7aa1b8266..7f5ed75141 100644 --- a/src/main/target/SPEEDYBEEF7/target.h +++ b/src/main/target/SPEEDYBEEF7/target.h @@ -57,13 +57,11 @@ #define USE_SPI #define USE_SPI_DEVICE_1 -#define USE_MPU_DATA_READY_SIGNAL -#define USE_EXTI + #define USE_IMU_ICM20689 #define IMU_ICM20689_ALIGN CW0_DEG -#define GYRO_INT_EXTI PC4 #define ICM20689_CS_PIN PA4 #define ICM20689_SPI_BUS BUS_SPI1 diff --git a/src/main/target/SPEEDYBEEF745AIO/CMakeLists.txt b/src/main/target/SPEEDYBEEF745AIO/CMakeLists.txt new file mode 100644 index 0000000000..c2e70490d9 --- /dev/null +++ b/src/main/target/SPEEDYBEEF745AIO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f745xg(SPEEDYBEEF745AIO) \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF745AIO/config.c b/src/main/target/SPEEDYBEEF745AIO/config.c new file mode 100644 index 0000000000..a760b1b2f9 --- /dev/null +++ b/src/main/target/SPEEDYBEEF745AIO/config.c @@ -0,0 +1,35 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + + +#include +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_RX_SERIAL; + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} diff --git a/src/main/target/SPEEDYBEEF745AIO/target.c b/src/main/target/SPEEDYBEEF745AIO/target.c new file mode 100644 index 0000000000..8a97ac96bc --- /dev/null +++ b/src/main/target/SPEEDYBEEF745AIO/target.c @@ -0,0 +1,42 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * 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_MC_MOTOR, 0, 0), // S1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 0, 0), // S2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR, 0, 2), // S3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR, 0, 1), // S4 + + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED + DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // Camera Control +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF745AIO/target.h b/src/main/target/SPEEDYBEEF745AIO/target.h new file mode 100644 index 0000000000..1cb7b7dbc1 --- /dev/null +++ b/src/main/target/SPEEDYBEEF745AIO/target.h @@ -0,0 +1,167 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SB73" +#define USBD_PRODUCT_STRING "SpeedyBee F745 AIO" + +#define LED0 PA2 + +#define USE_BEEPER +#define BEEPER PD15 +#define BEEPER_INVERTED + +// *************** UART ***************************** +#define USB_IO +#define USE_VCP +// #define VBUS_SENSING_PIN PC15 +// #define VBUS_SENSING_ENABLED + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC4 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED + +// Serial ports +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PD6 +#define UART2_TX_PIN PD5 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 6 + +// *************** Gyro & ACC ********************** + +#define USE_SPI +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW90_DEG +#define MPU6000_CS_PIN PE4 +#define MPU6000_SPI_BUS BUS_SPI4 + +//BMI270 +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW90_DEG +#define BMI270_SPI_BUS BUS_SPI4 +#define BMI270_CS_PIN PE4 + +// *************** I2C(Baro & I2C) ************************** +#define USE_I2C + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +// Baro +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 +#define BARO_I2C_BUS BUS_I2C1 + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +// *************** SPI3 SD BLACKBOX******************* +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI1 +#define M25P16_CS_PIN PA4 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** OSD ***************************** +#define USE_OSD +#define USE_SPI_DEVICE_2 +#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 PB12 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC3 +#define ADC_CHANNEL_2_PIN PC2 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +// *************** LED ***************************** +#define USE_LED_STRIP +#define WS2811_PIN PD12 + +// ********** Optiical Flow adn Lidar ************** +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define MAX_PWM_OUTPUT_PORTS 4 + +#define CURRENT_METER_SCALE 256 + +#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 diff --git a/src/main/target/SPEEDYBEEF7MINI/target.c b/src/main/target/SPEEDYBEEF7MINI/target.c index 46d1c18796..468ac3c2f6 100644 --- a/src/main/target/SPEEDYBEEF7MINI/target.c +++ b/src/main/target/SPEEDYBEEF7MINI/target.c @@ -26,7 +26,7 @@ #include "drivers/pinio.h" #include "drivers/sensor.h" -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) diff --git a/src/main/target/SPEEDYBEEF7MINI/target.h b/src/main/target/SPEEDYBEEF7MINI/target.h index b355f152e3..f6db8e86fa 100644 --- a/src/main/target/SPEEDYBEEF7MINI/target.h +++ b/src/main/target/SPEEDYBEEF7MINI/target.h @@ -39,10 +39,6 @@ #define IMU_MPU6000_ALIGN CW0_DEG #define MPU6000_CS_PIN PB2 #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PC4 - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL // *************** I2C /Baro/Mag ********************* #define USE_I2C diff --git a/src/main/target/SPEEDYBEEF7V2/target.h b/src/main/target/SPEEDYBEEF7V2/target.h index dbd4263db0..8b53b53b96 100644 --- a/src/main/target/SPEEDYBEEF7V2/target.h +++ b/src/main/target/SPEEDYBEEF7V2/target.h @@ -72,10 +72,6 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_BEEPER #define BEEPER PB2 #define BEEPER_INVERTED diff --git a/src/main/target/SPEEDYBEEF7V3/CMakeLists.txt b/src/main/target/SPEEDYBEEF7V3/CMakeLists.txt new file mode 100644 index 0000000000..3a038643bd --- /dev/null +++ b/src/main/target/SPEEDYBEEF7V3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(SPEEDYBEEF7V3) \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF7V3/config.c b/src/main/target/SPEEDYBEEF7V3/config.c new file mode 100644 index 0000000000..b064cd99f9 --- /dev/null +++ b/src/main/target/SPEEDYBEEF7V3/config.c @@ -0,0 +1,34 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + + +#include +#include + +#include "platform.h" + +#include "fc/fc_msp_box.h" +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_ESCSERIAL; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; +} diff --git a/src/main/target/SPEEDYBEEF7V3/target.c b/src/main/target/SPEEDYBEEF7V3/target.c new file mode 100644 index 0000000000..ad2eaf1353 --- /dev/null +++ b/src/main/target/SPEEDYBEEF7V3/target.c @@ -0,0 +1,49 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * 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" + +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_BMI270_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + +timerHardware_t timerHardware[] = { + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 Clash with S2, DSHOT does not work + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 + + DEF_TIM(TIM8, CH3, PC8, TIM_USE_LED, 0, 0), // LED + DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // Camera Control +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF7V3/target.h b/src/main/target/SPEEDYBEEF7V3/target.h new file mode 100644 index 0000000000..f8705f97da --- /dev/null +++ b/src/main/target/SPEEDYBEEF7V3/target.h @@ -0,0 +1,171 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SB73" +#define USBD_PRODUCT_STRING "SpeedyBeeF7V3" + +#define LED0 PA14 +#define LED1 PA13 + +#define USE_BEEPER +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** UART ***************************** +#define USB_IO +#define USE_VCP +// #define VBUS_SENSING_PIN PC15 +// #define VBUS_SENSING_ENABLED + +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC9 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED + +#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 PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN NONE + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 6 + +// *************** Gyro & ACC ********************** +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG_FLIP +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_CS_PIN PB2 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW0_DEG_FLIP +#define BMI270_SPI_BUS BUS_SPI1 +#define BMI270_CS_PIN PC15 + +// *************** I2C(Baro & I2C) ************************** +#define USE_I2C + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// Baro +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 +#define USE_BARO_SPL06 +#define BARO_I2C_BUS BUS_I2C1 + +// Mag +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +// *************** Internal SD card ************************** + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI3 +#define SDCARD_CS_PIN PD2 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** OSD ***************************** +#define USE_OSD +#define USE_SPI_DEVICE_2 +#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 PB12 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC0 +#define ADC_CHANNEL_3_PIN PC1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3 +#define RSSI_ADC_CHANNEL ADC_CHN_2 + +// *************** LED ***************************** +#define USE_LED_STRIP +#define WS2811_PIN PC8 + +// ********** Optiical Flow adn Lidar ************** +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define SERIALRX_UART SERIAL_PORT_USART2 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define MAX_PWM_OUTPUT_PORTS 8 + +#define CURRENT_METER_SCALE 490 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h index 9bdacd3e7f..6eb48977d1 100755 --- a/src/main/target/SPRACINGF4EVO/target.h +++ b/src/main/target/SPRACINGF4EVO/target.h @@ -30,10 +30,6 @@ #define BEEPER PC15 #define BEEPER_INVERTED -#define USE_EXTI -#define GYRO_INT_EXTI PC13 -#define USE_MPU_DATA_READY_SIGNAL - #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH diff --git a/src/main/target/SPRACINGF7DUAL/target.c b/src/main/target/SPRACINGF7DUAL/target.c index 87bb38c355..533cc17c58 100644 --- a/src/main/target/SPRACINGF7DUAL/target.c +++ b/src/main/target/SPRACINGF7DUAL/target.c @@ -30,8 +30,8 @@ #include "drivers/sensor.h" // Register both MPU6500 -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, GYRO_1_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_1_ALIGN); -BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, MPU6500_2_SPI_BUS, MPU6500_2_CS_PIN, GYRO_2_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_2_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_1, DEVHW_MPU6500, MPU6500_1_SPI_BUS, MPU6500_1_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, MPU6500_2_SPI_BUS, MPU6500_2_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_2_ALIGN); timerHardware_t timerHardware[] = { diff --git a/src/main/target/SPRACINGF7DUAL/target.h b/src/main/target/SPRACINGF7DUAL/target.h index b158647d11..20e1104720 100644 --- a/src/main/target/SPRACINGF7DUAL/target.h +++ b/src/main/target/SPRACINGF7DUAL/target.h @@ -36,13 +36,6 @@ #define BEEPER PC15 #define BEEPER_INVERTED -#define USE_EXTI -#define GYRO_1_EXTI_PIN PC13 -#define GYRO_2_EXTI_PIN PC14 - -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS #define USE_IMU_MPU6500 diff --git a/src/main/target/TMOTORF7/target.c b/src/main/target/TMOTORF7/target.c index d455e90c52..966bc54d3a 100644 --- a/src/main/target/TMOTORF7/target.c +++ b/src/main/target/TMOTORF7/target.c @@ -25,8 +25,8 @@ #include "drivers/timer.h" #include "drivers/sensor.h" -// BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); -// BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +// 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_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); timerHardware_t timerHardware[] = { DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), diff --git a/src/main/target/TMOTORF7/target.h b/src/main/target/TMOTORF7/target.h index 0c7c93a43f..890e95b353 100644 --- a/src/main/target/TMOTORF7/target.h +++ b/src/main/target/TMOTORF7/target.h @@ -43,10 +43,6 @@ #define IMU_MPU6000_ALIGN CW0_DEG #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define MPU6000_EXTI_PIN PC4 - -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL // *************** I2C Mag ********************* #define USE_I2C diff --git a/src/main/target/TMOTORF7V2/target.h b/src/main/target/TMOTORF7V2/target.h index 1df62a18f2..5aaab2e390 100644 --- a/src/main/target/TMOTORF7V2/target.h +++ b/src/main/target/TMOTORF7V2/target.h @@ -64,10 +64,6 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define GYRO_INT_EXTI PC4 - #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW0_DEG diff --git a/src/main/target/YUPIF4/target.h b/src/main/target/YUPIF4/target.h index e699fad7d1..ab9f07cd2c 100644 --- a/src/main/target/YUPIF4/target.h +++ b/src/main/target/YUPIF4/target.h @@ -44,11 +44,6 @@ #define BEEPER_PWM_FREQUENCY 3150 #endif -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - #define MPU6500_CS_PIN SPI1_NSS_PIN #define MPU6500_SPI_BUS BUS_SPI1 diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index ab381a3fb8..f494222f0f 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -28,12 +28,6 @@ #define BEEPER_INVERTED #define BEEPER_PWM_FREQUENCY 3150 -// Gyro interrupt -#define USE_EXTI -#define GYRO_INT_EXTI PC4 -#define USE_MPU_DATA_READY_SIGNAL -#define ENSURE_MPU_DATA_READY_IS_LOW - // ICM 20689 #define USE_IMU_ICM20689 #define IMU_ICM20689_ALIGN CW90_DEG diff --git a/src/main/target/ZEEZF7/CMakeLists.txt b/src/main/target/ZEEZF7/CMakeLists.txt index eb14cb8802..783143ed71 100644 --- a/src/main/target/ZEEZF7/CMakeLists.txt +++ b/src/main/target/ZEEZF7/CMakeLists.txt @@ -1,2 +1,3 @@ target_stm32f722xe(ZEEZF7) target_stm32f722xe(ZEEZF7V2) +target_stm32f722xe(ZEEZF7V3) diff --git a/src/main/target/ZEEZF7/config.c b/src/main/target/ZEEZF7/config.c index bde6f06f21..70769a1b74 100644 --- a/src/main/target/ZEEZF7/config.c +++ b/src/main/target/ZEEZF7/config.c @@ -25,7 +25,7 @@ void targetConfiguration(void) { -#ifndef ZEEZF7V2 +#ifdef ZEEZF7 pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; // VTX power switcher //pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; #endif diff --git a/src/main/target/ZEEZF7/target.c b/src/main/target/ZEEZF7/target.c index cc3b3223fe..9901d7f83b 100755 --- a/src/main/target/ZEEZF7/target.c +++ b/src/main/target/ZEEZF7/target.c @@ -14,7 +14,6 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ - #include #include "platform.h" @@ -23,8 +22,21 @@ #include "drivers/io.h" #include "drivers/pwm_mapping.h" #include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" timerHardware_t timerHardware[] = { +#ifdef ZEEZF7V3 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 1), // S5 + DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S6 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // S8 +#endif + #ifdef ZEEZF7V2 DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 @@ -34,7 +46,9 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S7 DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S8 -#else +#endif + +#ifdef ZEEZF7 DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR, 0, 0), // S1 DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), // S2 DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), // S3 @@ -45,3 +59,4 @@ timerHardware_t timerHardware[] = { }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + diff --git a/src/main/target/ZEEZF7/target.h b/src/main/target/ZEEZF7/target.h index b13c7f3534..07e22f1d93 100755 --- a/src/main/target/ZEEZF7/target.h +++ b/src/main/target/ZEEZF7/target.h @@ -17,60 +17,107 @@ #pragma once +#ifdef ZEEZF7V3 +#define TARGET_BOARD_IDENTIFIER "ZEF7V3" +#define USBD_PRODUCT_STRING "ZEEZF7V3" +#endif #ifdef ZEEZF7V2 #define TARGET_BOARD_IDENTIFIER "ZEF7V2" #define USBD_PRODUCT_STRING "ZEEZF7V2" -#else +#endif +#ifdef ZEEZF7 #define TARGET_BOARD_IDENTIFIER "ZEF7" #define USBD_PRODUCT_STRING "ZEEZF7" #endif +#define USE_TARGET_CONFIG + #define LED0 PC14 #define LED1 PC15 +#ifdef ZEEZF7V3 +#define BEEPER PC4 +#define BEEPER_INVERTED +#else #define BEEPER PB2 #define BEEPER_INVERTED +#endif // *************** Gyro & ACC ********************** #define USE_SPI -#ifdef ZEEZF7V2 +#ifdef ZEEZF7V3 +#define USE_SPI_DEVICE_3 + +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +// *************** SPI3 IMU0 ICM42688P ************** +#define USE_IMU_ICM42605 + +#define IMU_ICM42605_ALIGN CW0_DEG +#define ICM42605_SPI_BUS BUS_SPI3 +#define ICM42605_CS_PIN SPI3_NSS_PIN + +// *************** SPI3 IMU0 BMI270 ************** +#define USE_IMU_BMI270 + +#define IMU_BMI270_ALIGN CW270_DEG +#define BMI270_SPI_BUS BUS_SPI3 +#define BMI270_CS_PIN SPI3_NSS_PIN +#endif + +#ifdef ZEEZF7V2 #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 MPU6000_CS_PIN PA4 +#define MPU6000_CS_PIN SPI1_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI1 -#define GYRO_INT_EXTI PC4 #define IMU_MPU6000_ALIGN CW0_DEG +#define USE_IMU_MPU6000 +#endif -#else +#ifdef ZEEZF7 #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 MPU6000_CS_PIN PB12 +#define MPU6000_CS_PIN SPI2_NSS_PIN #define MPU6000_SPI_BUS BUS_SPI2 -#define GYRO_INT_EXTI PC9 - -#define IMU_MPU6000_ALIGN CW180_DEG +#define IMU_MPU6000_ALIGN CW0_DEG_FLIP +#define USE_IMU_MPU6000 #endif -#define USE_EXTI -#define USE_MPU_DATA_READY_SIGNAL -#define USE_IMU_MPU6000 - // *************** I2C/Baro/Mag ********************* -#ifdef ZEEZF7V2 +#ifdef ZEEZF7 +// Target has no I2C but can use MSP devices, such as those provided on Mateksys MQ8-CAN/MSP +// Which contains: GPS SAM-M8Q, Compass QMC5883L, Barometer DPS310 +// See: http://www.mateksys.com/?portfolio=m8q-can +#define USE_BARO +#define USE_BARO_DPS310 + +#define USE_MAG +#define USE_MAG_QMC5883 +#endif + +#if defined ZEEZF7V2 || defined ZEEZF7V3 #define USE_I2C #define USE_BARO #define USE_BARO_BMP280 +#define USE_BARO_BMP388 +#define USE_BARO_DPS310 + #define BARO_I2C_BUS BUS_I2C1 #define USE_I2C_DEVICE_1 @@ -91,47 +138,44 @@ #define USE_MAG_MAG3110 #define USE_MAG_LIS3MDL #define USE_MAG_AK8975 - -#else -// Target has no I2C but can use MSP devices, such as those provided on Mateksys MQ8-CAN/MSP -// Which contains: GPS SAM-M8Q, Compass QMC5883L, Barometer DPS310 -// See: http://www.mateksys.com/?portfolio=m8q-can - -#define USE_BARO -#define USE_BARO_DPS310 - -#define USE_MAG -#define USE_MAG_QMC5883 - #endif // *************** Flash **************************** -#ifdef ZEEZF7V2 - +#if defined ZEEZF7V2 || defined ZEEZF7V3 #define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 #define SPI2_MISO_PIN PC2 #define SPI2_MOSI_PIN PC3 #define M25P16_SPI_BUS BUS_SPI2 -#define M25P16_CS_PIN PB12 +#define M25P16_CS_PIN SPI2_NSS_PIN #define W25N01G_SPI_BUS BUS_SPI2 -#define W25N01G_CS_PIN PB12 +#define W25N01G_CS_PIN SPI2_NSS_PIN +#ifdef ZEEZF7V3 +#define SDCARD_SPI_BUS BUS_SPI2 +#define SDCARD_CS_PIN SPI2_NSS_PIN -#else +#define USE_SDCARD +#define USE_SDCARD_SPI +#endif +#endif + +#ifdef ZEEZF7 #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 M25P16_SPI_BUS BUS_SPI1 -#define M25P16_CS_PIN PA4 +#define M25P16_CS_PIN SPI1_NSS_PIN #define W25N01G_SPI_BUS BUS_SPI1 -#define W25N01G_CS_PIN PA4 +#define W25N01G_CS_PIN SPI1_NSS_PIN #endif @@ -141,26 +185,38 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT // *************** OSD ***************************** +#define USE_MAX7456 +#if defined ZEEZF7 || defined ZEEZF7V2 #define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 #define SPI3_SCK_PIN PC10 #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PB5 -#define USE_MAX7456 #define MAX7456_SPI_BUS BUS_SPI3 -#define MAX7456_CS_PIN PA15 +#define MAX7456_CS_PIN SPI3_NSS_PIN +#else +#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 MAX7456_SPI_BUS BUS_SPI1 +#define MAX7456_CS_PIN SPI1_NSS_PIN +#endif // *************** PINIO *************************** -#ifdef ZEEZF7 +#ifdef ZEEZF7 #define USE_PINIO #define USE_PINIOBOX #define PINIO1_PIN PB11 // VTX power switcher - #endif // *************** UART ***************************** + #define USE_VCP #define USE_UART1 @@ -183,18 +239,13 @@ #define UART5_RX_PIN PD2 #define UART5_TX_PIN PC12 -#ifdef ZEEZF7V2 - +#if defined ZEEZF7V2 || defined ZEEZF7V3 #define SERIAL_PORT_COUNT 6 - #else - #define USE_UART6 #define UART6_RX_PIN PC7 #define UART6_TX_PIN PC6 - #define SERIAL_PORT_COUNT 7 - #endif #define DEFAULT_RX_TYPE RX_TYPE_SERIAL @@ -205,22 +256,33 @@ #define USE_ADC #define ADC_INSTANCE ADC1 #define ADC1_DMA_STREAM DMA2_Stream0 -#ifdef ZEEZF7V2 + +#if defined ZEEZF7V2 || defined ZEEZF7V3 #define ADC_CHANNEL_1_PIN PC0 #define ADC_CHANNEL_2_PIN PC1 #else #define ADC_CHANNEL_1_PIN PC2 #define ADC_CHANNEL_2_PIN PC3 #endif + #define VBAT_ADC_CHANNEL ADC_CHN_1 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_LED_STRIP) -#ifdef ZEEZF7V2 +#if defined ZEEZF7V2 || defined ZEEZF7V3 #define CURRENT_METER_SCALE 250 #endif +// ********** Optical Flow and Lidar ************** + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_OPFLOW +#define USE_OPFLOW_MSP + +// *************** LED ***************************** + #define USE_LED_STRIP #define WS2811_PIN PB0 @@ -231,10 +293,11 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#ifdef ZEEZF7V2 +#if defined ZEEZF7V2 || defined ZEEZF7V3 #define MAX_PWM_OUTPUT_PORTS 8 #else #define MAX_PWM_OUTPUT_PORTS 4 #endif + #define USE_DSHOT #define USE_ESC_SENSOR diff --git a/src/main/target/common.h b/src/main/target/common.h index d73f4a4ea2..2365be9671 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -114,7 +114,7 @@ #define USE_OSD #define USE_FRSKYOSD #define USE_DJI_HD_OSD -#define USE_HDZERO_OSD +#define USE_MSP_OSD #define USE_SMARTPORT_MASTER #define NAV_NON_VOLATILE_WAYPOINT_CLI @@ -145,9 +145,6 @@ #define USE_SERIALRX_GHST #define USE_TELEMETRY_GHST -#define USE_SECONDARY_IMU -#define USE_IMU_BNO055 - #define USE_POWER_LIMITS #define NAV_FIXED_WING_LANDING @@ -185,12 +182,11 @@ #define USE_WIND_ESTIMATOR #define USE_SIMULATOR +#define USE_PITOT_VIRTUAL //Designed to free space of F722 and F411 MCUs #if (MCU_FLASH_SIZE > 512) - #define USE_VTX_FFPV -#define USE_PITOT_VIRTUAL #define USE_SERIALRX_SUMD #define USE_TELEMETRY_HOTT #define USE_HOTT_TEXTMODE diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 793d075ac3..a8bf517223 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -24,61 +24,58 @@ /** IMU **/ #if !defined(USE_TARGET_IMU_HARDWARE_DESCRIPTORS) - #if !defined(GYRO_INT_EXTI) - #define GYRO_INT_EXTI NONE - #endif #if !defined(MPU_ADDRESS) #define MPU_ADDRESS 0x68 #endif #if defined(USE_IMU_MPU6000) - BUSDEV_REGISTER_SPI(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + BUSDEV_REGISTER_SPI(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); #endif #if defined(USE_IMU_MPU6500) #if defined(MPU6500_SPI_BUS) - BUSDEV_REGISTER_SPI(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); + BUSDEV_REGISTER_SPI(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); #elif defined(MPU6500_I2C_BUS) - BUSDEV_REGISTER_I2C(busdev_mpu6500, DEVHW_MPU6500, MPU6500_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); + BUSDEV_REGISTER_I2C(busdev_mpu6500, DEVHW_MPU6500, MPU6500_I2C_BUS, MPU_ADDRESS, NONE, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); #endif #endif #if defined(USE_IMU_MPU9250) #if defined(MPU9250_SPI_BUS) - BUSDEV_REGISTER_SPI(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_MPU9250_ALIGN); + BUSDEV_REGISTER_SPI(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, NONE, DEVFLAGS_NONE, IMU_MPU9250_ALIGN); #elif defined(MPU9250_I2C_BUS) - BUSDEV_REGISTER_I2C(busdev_mpu9250, DEVHW_MPU9250, MPU9250_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_MPU9250_ALIGN); + BUSDEV_REGISTER_I2C(busdev_mpu9250, DEVHW_MPU9250, MPU9250_I2C_BUS, MPU_ADDRESS, NONE, DEVFLAGS_NONE, IMU_MPU9250_ALIGN); #endif #endif #if defined(USE_IMU_ICM20689) - BUSDEV_REGISTER_SPI(busdev_icm20689, DEVHW_ICM20689, ICM20689_SPI_BUS, ICM20689_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_ICM20689_ALIGN); + BUSDEV_REGISTER_SPI(busdev_icm20689, DEVHW_ICM20689, ICM20689_SPI_BUS, ICM20689_CS_PIN, NONE, DEVFLAGS_NONE, IMU_ICM20689_ALIGN); #endif #if defined(USE_IMU_ICM42605) - BUSDEV_REGISTER_SPI(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); + BUSDEV_REGISTER_SPI(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, DEVFLAGS_NONE, IMU_ICM42605_ALIGN); #endif #if defined(USE_IMU_BMI160) #if defined(BMI160_SPI_BUS) - BUSDEV_REGISTER_SPI(busdev_bmi160, DEVHW_BMI160, BMI160_SPI_BUS, BMI160_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_BMI160_ALIGN); + BUSDEV_REGISTER_SPI(busdev_bmi160, DEVHW_BMI160, BMI160_SPI_BUS, BMI160_CS_PIN, NONE, DEVFLAGS_NONE, IMU_BMI160_ALIGN); #elif defined(BMI160_I2C_BUS) - BUSDEV_REGISTER_I2C(busdev_bmi160, DEVHW_BMI160, BMI160_I2C_BUS, 0x68, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_BMI160_ALIGN); + BUSDEV_REGISTER_I2C(busdev_bmi160, DEVHW_BMI160, BMI160_I2C_BUS, 0x68, NONE, DEVFLAGS_NONE, IMU_BMI160_ALIGN); #endif #endif #if defined(USE_IMU_BMI088) #if defined(BMI088_SPI_BUS) - BUSDEV_REGISTER_SPI(busdev_bmi088_gyro, DEVHW_BMI088_GYRO, BMI088_SPI_BUS, BMI088_GYRO_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_BMI088_ALIGN); - BUSDEV_REGISTER_SPI(busdev_bmi088_acc, DEVHW_BMI088_ACC, BMI088_SPI_BUS, BMI088_ACC_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_BMI088_ALIGN); + BUSDEV_REGISTER_SPI(busdev_bmi088_gyro, DEVHW_BMI088_GYRO, BMI088_SPI_BUS, BMI088_GYRO_CS_PIN, NONE, DEVFLAGS_NONE, IMU_BMI088_ALIGN); + BUSDEV_REGISTER_SPI(busdev_bmi088_acc, DEVHW_BMI088_ACC, BMI088_SPI_BUS, BMI088_ACC_CS_PIN, NONE, DEVFLAGS_NONE, IMU_BMI088_ALIGN); #elif defined(BMI088_I2C_BUS) - BUSDEV_REGISTER_I2C(busdev_bmi088, DEVHW_BMI088, BMI088_I2C_BUS, 0x68, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_BMI088_ALIGN); + BUSDEV_REGISTER_I2C(busdev_bmi088, DEVHW_BMI088, BMI088_I2C_BUS, 0x68, NONE, DEVFLAGS_NONE, IMU_BMI088_ALIGN); #endif #endif #if defined(USE_IMU_BMI270) - BUSDEV_REGISTER_SPI(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE, IMU_BMI270_ALIGN); + BUSDEV_REGISTER_SPI(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, NONE, DEVFLAGS_NONE, IMU_BMI270_ALIGN); #endif #endif diff --git a/src/main/target/system.h b/src/main/target/system.h index 916654eaa5..15b31b9582 100644 --- a/src/main/target/system.h +++ b/src/main/target/system.h @@ -1,13 +1,13 @@ /* - * This file is part of iNav. + * This file is part of INAV. * - * iNav is free software. You can redistribute this software + * INAV is free software. You can redistribute this software * and/or modify this software 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 they will be + * INAV is distributed in the hope that they 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. diff --git a/src/main/telemetry/frsky_d.c b/src/main/telemetry/frsky_d.c index 6d44ea7cf5..f6f6bbf95f 100644 --- a/src/main/telemetry/frsky_d.c +++ b/src/main/telemetry/frsky_d.c @@ -195,10 +195,10 @@ static void sendThrottleOrBatterySizeAsRpm(void) { sendDataHead(ID_RPM); if (ARMING_FLAG(ARMED)) { - const throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER; - if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) - throttleForRPM = 0; + if (throttleStickIsLow() && feature(FEATURE_MOTOR_STOP)) { + throttleForRPM = 0; + } serialize16(throttleForRPM); } else { serialize16((currentBatteryProfile->capacity.value / BLADE_NUMBER_DIVIDER)); diff --git a/src/main/telemetry/ltm.h b/src/main/telemetry/ltm.h index af34a7cc44..68fdeec002 100644 --- a/src/main/telemetry/ltm.h +++ b/src/main/telemetry/ltm.h @@ -65,7 +65,7 @@ typedef enum { LTM_MODE_FLYBYWIRE2, LTM_MODE_CRUISE, LTM_MODE_UNKNOWN, - // iNav specific extensions + // INAV specific extensions LTM_MODE_LAUNCH, LTM_MODE_AUTOTUNE } ltm_modes_e; diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 421ff59dd2..07df75bcc0 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -1105,7 +1105,13 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs) if ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) { // Only process scheduled data if we didn't serve any incoming request this cycle - if (!incomingRequestServed) { + if (!incomingRequestServed || + ( + (rxConfig()->receiverType == RX_TYPE_SERIAL) && + (rxConfig()->serialrx_provider == SERIALRX_MAVLINK) && + !tristateWithDefaultOnIsActive(rxConfig()->halfDuplex) + ) + ) { processMAVLinkTelemetry(currentTimeUs); } lastMavlinkMessage = currentTimeUs; diff --git a/src/main/telemetry/sim.c b/src/main/telemetry/sim.c index a7c3776e4e..85f1e740d6 100644 --- a/src/main/telemetry/sim.c +++ b/src/main/telemetry/sim.c @@ -346,7 +346,7 @@ static void sendSMS(void) uint16_t avgSpeed = lrintf(10 * calculateAverageSpeed()); uint32_t now = millis(); - memset(pluscode_url, 0, sizeof(pluscode_url)); + ZERO_FARRAY(pluscode_url); if (sensors(SENSOR_GPS) && (STATE(GPS_FIX) || STATE(GPS_ESTIMATED_FIX))) { groundSpeed = gpsSol.groundSpeed / 100; diff --git a/src/test/unit/bitarray_unittest.cc b/src/test/unit/bitarray_unittest.cc index d80f380d82..23e1dd3a93 100644 --- a/src/test/unit/bitarray_unittest.cc +++ b/src/test/unit/bitarray_unittest.cc @@ -3,6 +3,7 @@ extern "C" { #include "common/bitarray.h" +#include "common/utils.h" } #include "gtest/gtest.h" @@ -10,7 +11,7 @@ extern "C" { TEST(BitArrayTest, TestGetSet) { BITARRAY_DECLARE(p, 32); - memset(p, 0, sizeof(p)); + ZERO_FARRAY(p); bitArraySet(p, 14); EXPECT_EQ(bitArrayGet(p, 14), true); @@ -25,7 +26,7 @@ TEST(BitArrayTest, TestGetSet) TEST(BitArrayTest, TestClr) { BITARRAY_DECLARE(p, 32); - memset(p, 0, sizeof(p)); + ZERO_FARRAY(p); bitArraySet(p, 31); EXPECT_EQ(bitArrayGet(p, 31), true); @@ -37,8 +38,8 @@ TEST(BitArrayTest, TestClr) TEST(BitArrayTest, TestFind) { - BITARRAY_DECLARE(p, 32*4); - memset(p, 0, sizeof(p)); + BITARRAY_DECLARE(p, 32 * 4); + ZERO_FARRAY(p); EXPECT_EQ(bitArrayFindFirstSet(p, 0, sizeof(p)), -1); diff --git a/src/test/unit/flight_imu_unittest.cc b/src/test/unit/flight_imu_unittest.cc index 25e2c438c3..37b7429c51 100644 --- a/src/test/unit/flight_imu_unittest.cc +++ b/src/test/unit/flight_imu_unittest.cc @@ -28,7 +28,7 @@ extern "C" { #include "fc/runtime_config.h" #include "io/gps.h" - + #include "flight/pid.h" #include "flight/imu.h" } @@ -100,6 +100,8 @@ gpsSolutionData_t gpsSol; compassConfig_t compassConfig_System; +pidProfile_t* pidProfile_ProfileCurrent; + uint8_t detectedSensors[] = { GYRO_NONE, ACC_NONE }; bool sensors(uint32_t mask) diff --git a/src/utils/combine_tool b/src/utils/combine_tool index c32110f3d5..1557388567 100755 --- a/src/utils/combine_tool +++ b/src/utils/combine_tool @@ -1,15 +1,15 @@ #!/usr/bin/env ruby ## -## This file is part of iNav. +## This file is part of INAV. ## -## iNav is free software. You can redistribute this software +## INAV is free software. You can redistribute this software ## and/or modify this software 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 they will be +## INAV is distributed in the hope that they 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. diff --git a/src/utils/intelhex.rb b/src/utils/intelhex.rb index 58dca4024d..29b7d05808 100644 --- a/src/utils/intelhex.rb +++ b/src/utils/intelhex.rb @@ -1,13 +1,13 @@ ## -## This file is part of iNav. +## This file is part of INAV. ## -## iNav is free software. You can redistribute this software +## INAV is free software. You can redistribute this software ## and/or modify this software 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 they will be +## INAV is distributed in the hope that they 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.