mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Merge branch 'development' into dzikuvx-mr-cruise-experiments
This commit is contained in:
commit
9212209d96
236 changed files with 2570 additions and 1290 deletions
15
README.md
15
README.md
|
@ -12,12 +12,8 @@
|
|||
* Rangefinder support (sonar and laser)
|
||||
* Oneshot and Multishot ESC support.
|
||||
* Blackbox flight recorder logging (to onboard flash or external SD card).
|
||||
* Support for more than 8 RC channels - (e.g. 16 Channels via FrSky X4RSB SBus).
|
||||
* Support for N-Position switches via flexible channel ranges - not just 3 like baseflight or 3/6 in MultiWii
|
||||
* Lux's new PID (uses float values internally, resistant to looptime variation).
|
||||
* Simultaneous Bluetooth configuration and OSD.
|
||||
* Better PWM and PPM input and failsafe detection than baseflight.
|
||||
* Better FrSky Telemetry than baseflight.
|
||||
* LTM Telemetry.
|
||||
* Smartport Telemetry.
|
||||
* RSSI via ADC - Uses ADC to read PWM RSSI signals, tested with FrSky D4R-II and X8R.
|
||||
|
@ -28,7 +24,7 @@
|
|||
* Configurable serial ports for Serial RX, Telemetry, MSP, GPS - Use most devices on any port, softserial too.
|
||||
* Multi-color RGB LED Strip support (each LED can be a different color using variable length WS2811 Addressable RGB strips - use for Orientation Indicators, Low Battery Warning, Flight Mode Status, etc)
|
||||
* PIDs from CF/BF can be used in INAV, no need to retune for INAV
|
||||
* And many more minor bug fixes.
|
||||
* And many more!
|
||||
|
||||
For a list of features, changes and some discussion please review the thread on RCGroups forums and consult the documentation.
|
||||
|
||||
|
@ -54,7 +50,10 @@ See: https://github.com/iNavFlight/inav/blob/master/docs/Installation.md
|
|||
|
||||
* [Official documentation](https://github.com/iNavFlight/inav/tree/master/docs)
|
||||
* [Official Wiki](https://github.com/iNavFlight/inav/wiki)
|
||||
* [Slack channel](https://inavflight.signup.team/)
|
||||
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
||||
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
|
||||
* [INAV Official on Slack](https://publicslack.com/slacks/inavflight/invites/new)
|
||||
* [INAV IRC channel] (irc://irc.freenode.net/#inavflight)
|
||||
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
|
||||
* [Video series by Painless360](https://www.youtube.com/playlist?list=PLYsWjANuAm4qdXEGFSeUhOZ10-H8YTSnH)
|
||||
* [Video series by Paweł Spychalski](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLloACrA6f1_daCjhqY2x0fB)
|
||||
|
@ -69,7 +68,9 @@ Contributions are welcome and encouraged. You can contribute in many ways:
|
|||
* New features.
|
||||
* Telling us your ideas and suggestions.
|
||||
|
||||
The best place to start is the IRC channel on freenode (see above), drop in, say hi. Next place is the github issue tracker:
|
||||
A good place to start is Telegram channel, Slack, Facebook goop or IRC channel on freenode (#inavflight), drop in, say hi.
|
||||
|
||||
Github issue tracker is a good place to search for existing issues or report a new bug/feature request:
|
||||
|
||||
https://github.com/iNavFlight/inav/issues
|
||||
|
||||
|
|
|
@ -311,4 +311,14 @@ If `---` is displayed during flight instead of the remaining flight time/distanc
|
|||
|
||||
## Automatic throttle compensation based on battery voltage
|
||||
|
||||
Automatic throttle compensation based on battery voltage can be used by enabling the `THR_VBAT_COMP` feature. It is working like this: used_throttle = requested_throttle * battery_max_voltage / sag_compensated_voltage.
|
||||
This features aims to compensate the throttle to get constant thrust with the same throttle request despite the battery voltage going down during flight. It can be used by enabling the `THR_VBAT_COMP` feature. This feature needs the sag compensated voltage which needs a current sensor (real or virtual) to be calculated.
|
||||
|
||||
It is working like this: `used_throttle = requested_throttle * (1 + (battery_full_voltage / sag_compensated_voltage - 1) * thr_comp_weight)`.
|
||||
|
||||
The default `thr_comp_weight` of 1 should be close to idal but if you want to tune this feature you need to find the difference in throttle value to achieve the same thrust (same power) when your battery is full and when your battery is almost empty then set `thr_comp_weight` to `(empty_battery_throttle / full_battery_throttle - 1) / (battery_full_voltage / battery_empty_sag_compensated_voltage - 1)`
|
||||
|
||||
Example:
|
||||
If the drawn power is 100W when the battery is full (12.6V) with 53% throttle and the drawn power is 100W with 58% throttle when the battery is almost empty with the sag compensated voltage being 11.0V `thr_comp_weight` needs to be set to this value to compensate the throttle automatically:
|
||||
`(58 / 53 - 1) / (12.6 / 11.0 - 1) = 0.649`
|
||||
|
||||
Known limitation: it doesn't work in 3D mode (3D feature)
|
||||
|
|
|
@ -79,10 +79,10 @@ I2C requires that the WS2812 led strip is moved to S5, thus WS2812 is not usable
|
|||
|
||||
### Soft Serial
|
||||
|
||||
Soft serial is available as an alternative to a hardware UART on RX4/TX4. By default this is NOT inverted. In order to use this feature:
|
||||
Soft serial is available as an alternative to a hardware UART on RX4/TX4 and TX2. By default this is NOT inverted. In order to use this feature:
|
||||
|
||||
* Enable soft serial
|
||||
* Do not assign any function to hardware UART 4
|
||||
* Do not assign any function to hardware UART4 or UART2-TX
|
||||
* Assign the desired function to the soft-serial port
|
||||
|
||||
### USB
|
||||
|
|
|
@ -132,6 +132,8 @@ For Omnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_
|
|||
|
||||
## SoftwareSerial
|
||||
|
||||
### Omnibus F4 v1/v2 SoftwareSerial Connections
|
||||
|
||||
This board allows for single **SoftwareSerial** port on small soldering pads located on the bottom side of the board.
|
||||
Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount pads CH5/CH6.
|
||||
|
||||
|
@ -148,7 +150,7 @@ Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount
|
|||
### Omnibus F4 v3/v4/v5 SoftwareSerial Connections
|
||||
|
||||
The SOFTSERIAL1 is an uni-directional port mapped to UART6-TX pin.
|
||||
When enabled, the UART6 is still available as hardware port but it's then RX-only port (good for e.g. receiving S.BUS input). TX instead is controlled in software (can be used for e.g. transmitting one-way telemetry).
|
||||
When enabled, the UART6 is still available as hardware port but it's then RX-only port (good for e.g. receiving S.BUS input). TX instead is controlled in software and can be used for transmitting one-way telemetry (e.g. LTM). Please note that UART6-TX line passes programmable inverter on those boards, so it is a pure output-only port. SmartPort/FPort telemetry requires bi-directional communication, so it is not possible on this port without hardware modification (bypassing the inverter).
|
||||
|
||||
|
||||
# Wiring diagrams for Omnibus F4 Pro
|
||||
|
|
34
docs/Cli.md
34
docs/Cli.md
|
@ -16,7 +16,7 @@ To exit the CLI without saving power off the flight controller or type in 'exit'
|
|||
|
||||
To see a list of other commands type in 'help' and press return.
|
||||
|
||||
To dump your configuration (including the current profile), use the 'dump' command.
|
||||
To dump your configuration (including the current profile), use the 'dump' or 'diff' command.
|
||||
|
||||
See the other documentation sections for details of the cli commands and settings that are available.
|
||||
|
||||
|
@ -42,23 +42,21 @@ dump profile
|
|||
|
||||
copy screen output to a file and save it.
|
||||
|
||||
Alternatively, use the `diff` command to dump only those settings that differ from their default values (those that have been changed).
|
||||
|
||||
|
||||
## Restore via CLI.
|
||||
|
||||
Use the cli `defaults` command first.
|
||||
|
||||
When restoring from a backup it is a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created you will be able to see the cli changes between firmware versions. For instance, in December 2014 the default GPS navigation PIDs changed. If you blindly restore your backup you would not benefit from these new defaults.
|
||||
When restoring from backup it's a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created you will be able to see the cli changes between firmware versions. If you blindly restore your backup you would not benefit from these new defaults or may even end up with completely wrong settings in case some parameters changed semantics and/or value ranges.
|
||||
|
||||
Use the CLI and send all the output from the saved backup commands.
|
||||
It may be good idea to restore settings using the `diff` output rather than complete `dump`. This way you can have more control on what is restored and the risk of mistakenly restoring bad values if the semantics changes is minimised.
|
||||
|
||||
Do not send the file too fast, if you do the FC might not be able to keep up when using USART adapters (including built in ones) since there is no hardware serial flow control.
|
||||
To perform the restore simply paste the saved commands in the Configurator CLI tab and then type `save`.
|
||||
|
||||
You may find you have to copy/paste a few lines at a time.
|
||||
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.
|
||||
|
||||
Repeat the backup process again!
|
||||
|
||||
Compare the two backups to make sure you are happy with your restored settings.
|
||||
|
||||
Re-apply any new defaults as desired.
|
||||
|
||||
## CLI Command Reference
|
||||
|
||||
|
@ -72,6 +70,7 @@ Re-apply any new defaults as desired.
|
|||
| `color` | configure colors |
|
||||
| `defaults` | reset to defaults and reboot |
|
||||
| `dump` | print configurable settings in a pastable form |
|
||||
| `diff` | print only settings that have been modified |
|
||||
| `exit` | |
|
||||
| `feature` | list or -val or val |
|
||||
| `get` | get variable value |
|
||||
|
@ -96,16 +95,15 @@ Re-apply any new defaults as desired.
|
|||
| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
|
||||
| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) |
|
||||
| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz |
|
||||
| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Use gyro_lpf and gyro_sync_denom determine the gyro refresh rate. Note that different targets have different limits. Setting too high refresh rate can mean that FC cannot keep up with the gyro and higher gyro_sync_denom is needed, |
|
||||
| gyro_sync_denom | 2 | This option determines the sampling ratio. Denominator of 1 means full gyro sampling rate. Denominator 2 would mean 1/2 samples will be collected. Denominator and gyro_lpf will together determine the control loop speed. |
|
||||
| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf |
|
||||
| acc_task_frequency | 500 | Determines accelerometer task frequency in async_mode = ALL. Depending on UAV type this frequency can be lowered to conserve CPU resources as long as vibrations are not a problem. |
|
||||
| attitude_task_frequency | 250 | Determines attitude task frequency when async_mode = ALL |
|
||||
| async_mode | NONE | Enables asynchronous mode processing for gyro/accelerometer and attitude computations. Allowed modes: NONE -> default behavior, all calculations are executed in main PID loop. GYRO -> gyro sampling and filtering is detached from main PID loop. PID loop runs based on looptime while gyro sampling uses gyro_sync_denom and gyro_lpf combination to determine its frequency. ALL -> in this mode, gyro, accelerometer and attitude are running as separate tasks. Accelerometer task frequency is determined by acc_task_frequency, attitude task frequency by attitude_task_frequency. In this mode ANGLE and HORIZON, as well GPS assisted flight modes (including PosHold) performance might be lowered. |
|
||||
| async_mode | NONE | Enables asynchronous mode processing for gyro/accelerometer and attitude computations. Allowed modes: NONE -> default behavior, all calculations are executed in main PID loop. GYRO -> gyro sampling and filtering is detached from main PID loop. PID loop runs based on looptime while gyro sampling rate is determined by the gyro driver using also the gyro_hardware_lpf setting. ALL -> in this mode, gyro, accelerometer and attitude are running as separate tasks. Accelerometer task frequency is determined by acc_task_frequency, attitude task frequency by attitude_task_frequency. In this mode ANGLE and HORIZON, as well GPS assisted flight modes (including PosHold) performance might be lowered if improper settings are used. |
|
||||
| min_check | 1100 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
|
||||
| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
|
||||
| rssi_channel | 0 | RX channel containing the RSSI signal |
|
||||
| rssi_scale | 100 | By default RSSI expects to use full span of the input (0-3.3V for ADC, 1000-2000 for AUX channel). This scale (percentage) allows you to adjust the scaling to get 100% RSSI shown correctly |
|
||||
| rssi_invert | OFF | |
|
||||
| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). |
|
||||
| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. |
|
||||
| rc_smoothing | ON | Interpolation of Rc data during looptimes when there are no new updates. This gives smoother RC input to PID controller and cleaner PIDsum |
|
||||
| input_filtering_mode | OFF | Filter out noise from OpenLRS Telemetry RX |
|
||||
| min_throttle | 1150 | These are min/max values (in us) that are sent to esc when armed. Defaults of 1150/1850 are OK for everyone, for use with AfroESC, they could be set to 1064/1864. |
|
||||
|
@ -164,6 +162,7 @@ Re-apply any new defaults as desired.
|
|||
| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] |
|
||||
| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] |
|
||||
| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. |
|
||||
| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. |
|
||||
| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
|
||||
| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
|
||||
| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. |
|
||||
|
@ -211,10 +210,11 @@ Re-apply any new defaults as desired.
|
|||
| frsky_coordinates_format | 0 | FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
|
||||
| frsky_unit | METRIC | METRIC , IMPERIAL |
|
||||
| frsky_vfas_precision | 0 | Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
|
||||
| frsky_pitch_roll | OFF | Send pitch and roll degrees*10 instead of raw accelerometer telemetry for S.Port and FrSky D-Series telemetry |
|
||||
| report_cell_voltage | OFF | |
|
||||
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
|
||||
| smartport_uart_unidir | OFF | Turn UART into UNIDIR for smartport telemetry for usage on F1 and F4 target. See Telemetry.md for details |
|
||||
| smartport_fuel_unit | MAH | Unit of the value sent with the `FUEL` ID through the S.Port telemetry. Replaces the `smartport_fuel_percent` setting in versions < 1.9 [PERCENT/MAH/MWH] |
|
||||
| smartport_fuel_unit | MAH | Unit of the value sent with the `FUEL` ID through the S.Port and FrSky D-Series telemetry. [PERCENT/MAH/MWH] |
|
||||
| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. |
|
||||
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
|
||||
| battery_capacity | 0 | Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. |
|
||||
|
@ -300,7 +300,6 @@ Re-apply any new defaults as desired.
|
|||
| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
|
||||
| osd_attitude_angle_decimals | 0 | Chose the numbers of decimals displayed by OSD attitude angle elements [0-1] |
|
||||
| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
|
@ -420,6 +419,7 @@ Re-apply any new defaults as desired.
|
|||
| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. |
|
||||
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
|
||||
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
|
||||
| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) |
|
||||
|
||||
This Markdown table is made by MarkdwonTableMaker addon for google spreadsheet.
|
||||
Original Spreadsheet used to make this table can be found here https://docs.google.com/spreadsheets/d/1ubjYdMGmZ2aAMUNYkdfe3hhIF7wRfIjcuPOi_ysmp00/edit?usp=sharing
|
||||
|
|
|
@ -2,13 +2,13 @@
|
|||
|
||||
iNav requires a reasonably modern `gcc-arm-none-eabi` compiler. As a consequence of the long term support options in Ubuntu, it is possible that the distribution compiler will be too old to build iNav firmware. For example, Ubuntu 16.04 LTS ships with version 4.9.3 which cannot compile contemporary iNav.
|
||||
|
||||
As of March 2018, the recommendation for Ubuntu releases is:
|
||||
As of August 2018, the recommendation for Ubuntu releases is:
|
||||
|
||||
| Release | Compiler Source |
|
||||
| ------- | --------------- |
|
||||
| 16.04 or earlier | Use the 'official' PPA |
|
||||
| 17.10 | Use the 'official' PPA as the distro compiler (5.4) *may* be too old |
|
||||
| 18.04 | Use the distro compiler (6.3+) |
|
||||
| 18.04 | Use the 'official' PPA, as the distro compiler (6.3) was broken when last tested |
|
||||
|
||||
For Ubuntu derivatives (ElementaryOS, Mint etc.), please check the distro provided version, and if it's lower than 6, use the PPA.
|
||||
|
||||
|
@ -47,14 +47,15 @@ sudo apt-get install ruby2.4 ruby2.4-dev
|
|||
|
||||
# Using the Distro compiler
|
||||
|
||||
For Releases after 17.10 is is recommended to use the distro provided compiler, at least until it proves to be too old.
|
||||
In case Ubuntu ever provides a modern compiler (as of August 2018, not recommended):
|
||||
|
||||
```
|
||||
sudo apt install gcc-arm-none-eabi
|
||||
```
|
||||
|
||||
# Using the PPA compiler
|
||||
|
||||
For releases prior to (and perhaps including) 17.10, the PPA compiler is used. This can be used on releases post 17.10 if you really wish to have a newer compiler than the distro default.
|
||||
The PPA compiler is recommended for all cases:
|
||||
|
||||
```
|
||||
sudo apt-get remove binutils-arm-none-eabi gcc-arm-none-eabi
|
||||
|
@ -84,9 +85,9 @@ cd inav
|
|||
make
|
||||
```
|
||||
|
||||
If you have a github account with registered ssh key you can replace the `git clone` command with `git clone https://github.com/iNavFlight/inav.git` instead of the https link.
|
||||
If you have a github account with registered ssh key you can replace the `git clone` command with `git clone git@github.com:iNavFlight/inav.git` instead of the https link.
|
||||
|
||||
By default, this builds the SPRACINGF3 target, to build another target, specify the target name to the make command, for example:
|
||||
By default, this builds the REVO target, to build another target, specify the target name to the make command, for example:
|
||||
```
|
||||
make TARGET=MATEKF405
|
||||
```
|
||||
|
@ -94,7 +95,7 @@ The resultant hex file are in the `obj/` directory.
|
|||
|
||||
You can use the INAV Configurator to flash the local ```obj/inav_TARGET.hex``` file, or use `stm32flash` or `dfu-util` directly from the command line.
|
||||
|
||||
https://github.com/fiam/msp-tool and https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh provide / describe helper tools for command line flashing.
|
||||
[msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing.
|
||||
|
||||
# Updating and rebuilding
|
||||
|
||||
|
|
|
@ -180,7 +180,7 @@ USB_OTG_STS USB_OTG_WritePacket(USB_OTG_CORE_HANDLE *pdev,
|
|||
fifo = pdev->regs.DFIFO[ch_ep_num];
|
||||
for (i = 0; i < count32b; i++)
|
||||
{
|
||||
USB_OTG_WRITE_REG32( fifo, *((__packed uint32_t *)src) );
|
||||
USB_OTG_WRITE_REG32( fifo, *((uint32_t *)src) );
|
||||
src+=4;
|
||||
}
|
||||
}
|
||||
|
@ -206,7 +206,7 @@ void *USB_OTG_ReadPacket(USB_OTG_CORE_HANDLE *pdev,
|
|||
|
||||
for( i = 0; i < count32b; i++)
|
||||
{
|
||||
*(__packed uint32_t *)dest = USB_OTG_READ_REG32(fifo);
|
||||
*(uint32_t *)dest = USB_OTG_READ_REG32(fifo);
|
||||
dest += 4 ;
|
||||
}
|
||||
return ((void *)dest);
|
||||
|
|
|
@ -156,13 +156,13 @@ MCU_COMMON_SRC = \
|
|||
drivers/adc_stm32f4xx.c \
|
||||
drivers/adc_stm32f4xx.c \
|
||||
drivers/bus_i2c_stm32f40x.c \
|
||||
drivers/inverter.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart_stm32f4xx.c \
|
||||
drivers/system_stm32f4xx.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_impl_stdperiph.c \
|
||||
drivers/timer_stm32f4xx.c \
|
||||
drivers/uart_inverter.c \
|
||||
drivers/dma_stm32f4xx.c
|
||||
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
|
|
|
@ -146,11 +146,11 @@ MCU_COMMON_SRC = \
|
|||
drivers/adc_stm32f7xx.c \
|
||||
drivers/bus_i2c_hal.c \
|
||||
drivers/dma_stm32f7xx.c \
|
||||
drivers/inverter.c \
|
||||
drivers/bus_spi_hal.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_impl_hal.c \
|
||||
drivers/timer_stm32f7xx.c \
|
||||
drivers/uart_inverter.c \
|
||||
drivers/system_stm32f7xx.c \
|
||||
drivers/serial_uart_stm32f7xx.c \
|
||||
drivers/serial_softserial.c \
|
||||
|
|
|
@ -14,4 +14,4 @@ RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 FIREWORKSV2
|
|||
RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4V3 OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO
|
||||
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7
|
||||
|
||||
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF405SE
|
||||
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF405SE MATEKF411
|
||||
|
|
|
@ -75,6 +75,7 @@
|
|||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "flight/wind_estimator.h"
|
||||
|
||||
|
||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||
|
@ -193,6 +194,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"axisD", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_0)},
|
||||
{"axisD", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_1)},
|
||||
{"axisD", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_2)},
|
||||
|
||||
{"fwAltP", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwAltI", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwAltD", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
|
@ -201,6 +203,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"fwPosI", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwPosD", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwPosOut", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
|
||||
{"mcPosAxisP", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(MC_NAV)},
|
||||
{"mcPosAxisP", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(MC_NAV)},
|
||||
{"mcPosAxisP", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(MC_NAV)},
|
||||
|
@ -233,8 +236,8 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
/* Throttle is always in the range [minthrottle..maxthrottle]: */
|
||||
{"rcCommand", 3, UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
|
||||
|
||||
{"vbatLatest", -1, UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT},
|
||||
{"amperageLatest",-1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC},
|
||||
{"vbat", -1, UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT},
|
||||
{"amperage", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE},
|
||||
|
||||
#ifdef USE_MAG
|
||||
{"magADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
|
||||
|
@ -339,6 +342,9 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
|
|||
{"hwHealthStatus", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"powerSupplyImpedance", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"sagCompensatedVBat", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"wind", 0, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"wind", 1, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"wind", 2, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
};
|
||||
|
||||
typedef enum BlackboxState {
|
||||
|
@ -388,8 +394,8 @@ typedef struct blackboxMainState_s {
|
|||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
|
||||
uint16_t vbatLatest;
|
||||
uint16_t amperageLatest;
|
||||
uint16_t vbat;
|
||||
int16_t amperage;
|
||||
|
||||
#ifdef USE_BARO
|
||||
int32_t BaroAlt;
|
||||
|
@ -413,7 +419,7 @@ typedef struct blackboxMainState_s {
|
|||
int16_t navRealVel[XYZ_AXIS_COUNT];
|
||||
int16_t navAccNEU[XYZ_AXIS_COUNT];
|
||||
int16_t navTargetVel[XYZ_AXIS_COUNT];
|
||||
int16_t navTargetPos[XYZ_AXIS_COUNT];
|
||||
int32_t navTargetPos[XYZ_AXIS_COUNT];
|
||||
int16_t navHeading;
|
||||
int16_t navTargetHeading;
|
||||
int16_t navSurface;
|
||||
|
@ -436,6 +442,7 @@ typedef struct blackboxSlowState_s {
|
|||
int32_t hwHealthStatus;
|
||||
uint16_t powerSupplyImpedance;
|
||||
uint16_t sagCompensatedVBat;
|
||||
int16_t wind[XYZ_AXIS_COUNT];
|
||||
} __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
|
||||
|
||||
//From rc_controls.c
|
||||
|
@ -549,7 +556,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
|
|||
case FLIGHT_LOG_FIELD_CONDITION_VBAT:
|
||||
return feature(FEATURE_VBAT);
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
|
||||
case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE:
|
||||
return feature(FEATURE_CURRENT_METER) && batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC;
|
||||
|
||||
case FLIGHT_LOG_FIELD_CONDITION_SURFACE:
|
||||
|
@ -699,12 +706,12 @@ static void writeIntraframe(void)
|
|||
*
|
||||
* Write 14 bits even if the number is negative (which would otherwise result in 32 bits)
|
||||
*/
|
||||
blackboxWriteUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF);
|
||||
blackboxWriteUnsignedVB((vbatReference - blackboxCurrent->vbat) & 0x3FFF);
|
||||
}
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC)) {
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE)) {
|
||||
// 12bit value directly from ADC
|
||||
blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest);
|
||||
blackboxWriteSignedVB(blackboxCurrent->amperage);
|
||||
}
|
||||
|
||||
#ifdef USE_MAG
|
||||
|
@ -907,11 +914,11 @@ static void writeInterframe(void)
|
|||
int optionalFieldCount = 0;
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
|
||||
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest;
|
||||
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbat - blackboxLast->vbat;
|
||||
}
|
||||
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC)) {
|
||||
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest;
|
||||
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE)) {
|
||||
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperage - blackboxLast->amperage;
|
||||
}
|
||||
|
||||
#ifdef USE_MAG
|
||||
|
@ -983,7 +990,7 @@ static void writeInterframe(void)
|
|||
}
|
||||
|
||||
for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
|
||||
blackboxWriteSignedVB(blackboxHistory[0]->navTargetPos[x] - (blackboxHistory[1]->navTargetPos[x] + blackboxHistory[2]->navTargetPos[x]) / 2);
|
||||
blackboxWriteSignedVB(blackboxHistory[0]->navTargetPos[x] - blackboxLast->navTargetPos[x]);
|
||||
}
|
||||
|
||||
blackboxWriteSignedVB(blackboxCurrent->navSurface - blackboxLast->navSurface);
|
||||
|
@ -1021,6 +1028,8 @@ static void writeSlowFrame(void)
|
|||
blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance);
|
||||
blackboxWriteUnsignedVB(slowHistory.sagCompensatedVBat);
|
||||
|
||||
blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);
|
||||
|
||||
blackboxSlowFrameIterationTimer = 0;
|
||||
}
|
||||
|
||||
|
@ -1043,6 +1052,16 @@ static void loadSlowState(blackboxSlowState_t *slow)
|
|||
(getHwPitotmeterStatus() << 2 * 6);
|
||||
slow->powerSupplyImpedance = getPowerSupplyImpedance();
|
||||
slow->sagCompensatedVBat = getBatterySagCompensatedVoltage();
|
||||
|
||||
for (int i = 0; i < XYZ_AXIS_COUNT; i++)
|
||||
{
|
||||
#ifdef USE_WIND_ESTIMATOR
|
||||
slow->wind[i] = getEstimatedWindSpeed(i);
|
||||
#else
|
||||
slow->wind[i] = 0;
|
||||
#endif
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -1139,7 +1158,7 @@ void blackboxStart(void)
|
|||
blackboxHistory[1] = &blackboxHistoryRing[1];
|
||||
blackboxHistory[2] = &blackboxHistoryRing[2];
|
||||
|
||||
vbatReference = getBatteryVoltageLatestADC();
|
||||
vbatReference = getBatteryRawVoltage();
|
||||
|
||||
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
|
||||
|
||||
|
@ -1256,25 +1275,34 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
#endif
|
||||
#ifdef USE_NAV
|
||||
if (!STATE(FIXED_WING)) {
|
||||
blackboxCurrent->mcPosAxisP[i] = lrintf(nav_pids->pos[i].output_constrained / 10);
|
||||
blackboxCurrent->mcVelAxisPID[0][i] = lrintf(nav_pids->vel[i].proportional / 10);
|
||||
blackboxCurrent->mcVelAxisPID[1][i] = lrintf(nav_pids->vel[i].integral / 10);
|
||||
blackboxCurrent->mcVelAxisPID[2][i] = lrintf(nav_pids->vel[i].derivative / 10);
|
||||
|
||||
// log requested velocity in cm/s
|
||||
blackboxCurrent->mcPosAxisP[i] = lrintf(nav_pids->pos[i].output_constrained);
|
||||
|
||||
// log requested acceleration in cm/s^2 and throttle adjustment in µs
|
||||
blackboxCurrent->mcVelAxisPID[0][i] = lrintf(nav_pids->vel[i].proportional);
|
||||
blackboxCurrent->mcVelAxisPID[1][i] = lrintf(nav_pids->vel[i].integral);
|
||||
blackboxCurrent->mcVelAxisPID[2][i] = lrintf(nav_pids->vel[i].derivative);
|
||||
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_NAV
|
||||
if (STATE(FIXED_WING)) {
|
||||
blackboxCurrent->fwAltPID[0] = lrintf(nav_pids->fw_alt.proportional / 10);
|
||||
blackboxCurrent->fwAltPID[1] = lrintf(nav_pids->fw_alt.integral / 10);
|
||||
blackboxCurrent->fwAltPID[2] = lrintf(nav_pids->fw_alt.derivative / 10);
|
||||
blackboxCurrent->fwAltPIDOutput = lrintf(nav_pids->fw_alt.output_constrained / 10);
|
||||
|
||||
// log requested pitch in decidegrees
|
||||
blackboxCurrent->fwAltPID[0] = lrintf(nav_pids->fw_alt.proportional);
|
||||
blackboxCurrent->fwAltPID[1] = lrintf(nav_pids->fw_alt.integral);
|
||||
blackboxCurrent->fwAltPID[2] = lrintf(nav_pids->fw_alt.derivative);
|
||||
blackboxCurrent->fwAltPIDOutput = lrintf(nav_pids->fw_alt.output_constrained);
|
||||
|
||||
// log requested roll in decidegrees
|
||||
blackboxCurrent->fwPosPID[0] = lrintf(nav_pids->fw_nav.proportional / 10);
|
||||
blackboxCurrent->fwPosPID[1] = lrintf(nav_pids->fw_nav.integral / 10);
|
||||
blackboxCurrent->fwPosPID[2] = lrintf(nav_pids->fw_nav.derivative / 10);
|
||||
blackboxCurrent->fwPosPIDOutput = lrintf(nav_pids->fw_nav.output_constrained / 10);
|
||||
|
||||
} else {
|
||||
blackboxCurrent->mcSurfacePID[0] = lrintf(nav_pids->surface.proportional / 10);
|
||||
blackboxCurrent->mcSurfacePID[1] = lrintf(nav_pids->surface.integral / 10);
|
||||
|
@ -1301,8 +1329,8 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
blackboxCurrent->motor[i] = motor[i];
|
||||
}
|
||||
|
||||
blackboxCurrent->vbatLatest = getBatteryVoltageLatestADC();
|
||||
blackboxCurrent->amperageLatest = getAmperageLatestADC();
|
||||
blackboxCurrent->vbat = getBatteryRawVoltage();
|
||||
blackboxCurrent->amperage = getAmperage();
|
||||
|
||||
#ifdef USE_BARO
|
||||
blackboxCurrent->BaroAlt = baro.BaroAlt;
|
||||
|
@ -1461,7 +1489,7 @@ static char *blackboxGetStartDateTime(char *buf)
|
|||
// rtcGetDateTime will fill dt with 0000-01-01T00:00:00
|
||||
// when time is not known.
|
||||
rtcGetDateTime(&dt);
|
||||
dateTimeFormatUTC(buf, &dt);
|
||||
dateTimeFormatLocal(buf, &dt);
|
||||
return buf;
|
||||
}
|
||||
|
||||
|
|
|
@ -38,7 +38,7 @@ typedef enum FlightLogFieldCondition {
|
|||
FLIGHT_LOG_FIELD_CONDITION_BARO,
|
||||
FLIGHT_LOG_FIELD_CONDITION_PITOT,
|
||||
FLIGHT_LOG_FIELD_CONDITION_VBAT,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC,
|
||||
FLIGHT_LOG_FIELD_CONDITION_AMPERAGE,
|
||||
FLIGHT_LOG_FIELD_CONDITION_SURFACE,
|
||||
FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV,
|
||||
FLIGHT_LOG_FIELD_CONDITION_MC_NAV,
|
||||
|
|
|
@ -56,6 +56,7 @@
|
|||
#include "config/parameter_group_ids.h"
|
||||
|
||||
// For 'ARM' related
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
@ -428,7 +429,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
|||
if (IS_PRINTVALUE(p, screenRow) && p->data) {
|
||||
buff[0] = '\0';
|
||||
const OSD_SETTING_t *ptr = p->data;
|
||||
const setting_t *var = &settingsTable[ptr->val];
|
||||
const setting_t *var = settingGet(ptr->val);
|
||||
int32_t value;
|
||||
const void *valuePointer = settingGetValuePointer(var);
|
||||
switch (SETTING_TYPE(var)) {
|
||||
|
@ -476,13 +477,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
|||
break;
|
||||
case MODE_LOOKUP:
|
||||
{
|
||||
const char *str = NULL;
|
||||
if (var->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) {
|
||||
const lookupTableEntry_t *tableEntry = &settingLookupTables[var->config.lookup.tableIndex];
|
||||
if (value < tableEntry->valueCount) {
|
||||
str = tableEntry->values[value];
|
||||
}
|
||||
}
|
||||
const char *str = settingLookupValueName(var, value);
|
||||
strncpy(buff, str ? str : "INVALID", sizeof(buff) - 1);
|
||||
}
|
||||
break;
|
||||
|
@ -764,11 +759,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
|
|||
|
||||
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing?
|
||||
|
||||
stopMotors();
|
||||
stopPwmAllMotors();
|
||||
delay(200);
|
||||
|
||||
systemReset();
|
||||
fcReboot(false);
|
||||
}
|
||||
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_CMS_MENU);
|
||||
|
@ -1008,7 +999,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
case OME_Setting:
|
||||
if (p->data) {
|
||||
const OSD_SETTING_t *ptr = p->data;
|
||||
const setting_t *var = &settingsTable[ptr->val];
|
||||
const setting_t *var = settingGet(ptr->val);
|
||||
setting_min_t min = settingGetMin(var);
|
||||
setting_max_t max = settingGetMax(var);
|
||||
float step = ptr->step ?: 1;
|
||||
|
|
|
@ -148,8 +148,7 @@ static const OSD_Entry menuMainEntries[] =
|
|||
OSD_SUBMENU_ENTRY("PID TUNING", &cmsx_menuImu),
|
||||
OSD_SUBMENU_ENTRY("FEATURES", &menuFeatures),
|
||||
#if defined(USE_OSD) && defined(CMS_MENU_OSD)
|
||||
OSD_SUBMENU_ENTRY("OSD LAYOUTS", &cmsx_menuOsdLayout),
|
||||
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
|
||||
OSD_SUBMENU_ENTRY("OSD", &cmsx_menuOsd),
|
||||
#endif
|
||||
OSD_SUBMENU_ENTRY("BATTERY", &cmsx_menuBattery),
|
||||
OSD_SUBMENU_ENTRY("FC&FW INFO", &menuInfo),
|
||||
|
|
|
@ -61,9 +61,9 @@ static const OSD_Entry cmsx_menuAlarmsEntries[] = {
|
|||
OSD_END_ENTRY,
|
||||
};
|
||||
|
||||
const CMS_Menu cmsx_menuAlarms = {
|
||||
static const CMS_Menu cmsx_menuAlarms = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUALARMS",
|
||||
.GUARD_text = "MENUOSDA",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
|
@ -144,7 +144,7 @@ static long osdElemActionsOnEnter(const OSD_Entry *from)
|
|||
|
||||
static const OSD_Entry menuOsdElemsEntries[] =
|
||||
{
|
||||
OSD_LABEL_ENTRY("--- OSD ---"),
|
||||
OSD_LABEL_ENTRY("--- OSD ITEMS ---"),
|
||||
|
||||
OSD_ELEMENT_ENTRY("RSSI", OSD_RSSI_VALUE),
|
||||
OSD_ELEMENT_ENTRY("MAIN BATTERY", OSD_MAIN_BATT_VOLTAGE),
|
||||
|
@ -257,7 +257,7 @@ _Static_assert(ARRAYLEN(menuOsdElemsEntries) - 3 + 1 == OSD_ITEM_COUNT, "missing
|
|||
|
||||
const CMS_Menu menuOsdElements = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUOSDELEMS",
|
||||
.GUARD_text = "MENUOSDE",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = osdElementsOnEnter,
|
||||
|
@ -290,7 +290,7 @@ static const OSD_Entry cmsx_menuOsdLayoutEntries[] =
|
|||
|
||||
const CMS_Menu cmsx_menuOsdLayout = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENULAYOUT",
|
||||
.GUARD_text = "MENUOSDL",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
|
@ -317,4 +317,53 @@ static long osdElementsOnExit(const OSD_Entry *from)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static const OSD_Entry menuOsdSettingsEntries[] = {
|
||||
OSD_LABEL_ENTRY("--- OSD SETTINGS ---"),
|
||||
|
||||
OSD_SETTING_ENTRY("VOLT. DECIMALS", SETTING_OSD_MAIN_VOLTAGE_DECIMALS),
|
||||
OSD_SETTING_ENTRY("COORD. DIGITS", SETTING_OSD_COORDINATE_DIGITS),
|
||||
OSD_SETTING_ENTRY("CROSSHAIRS STYLE", SETTING_OSD_CROSSHAIRS_STYLE),
|
||||
OSD_SETTING_ENTRY("LEFT SCROLL", SETTING_OSD_LEFT_SIDEBAR_SCROLL),
|
||||
OSD_SETTING_ENTRY("RIGHT SCROLL", SETTING_OSD_RIGHT_SIDEBAR_SCROLL),
|
||||
OSD_SETTING_ENTRY("SCROLL ARROWS", SETTING_OSD_SIDEBAR_SCROLL_ARROWS),
|
||||
|
||||
|
||||
OSD_BACK_ENTRY,
|
||||
OSD_END_ENTRY,
|
||||
};
|
||||
|
||||
static const CMS_Menu cmsx_menuOsdSettings = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUOSDS",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = menuOsdSettingsEntries,
|
||||
};
|
||||
|
||||
static const OSD_Entry menuOsdEntries[] = {
|
||||
OSD_LABEL_ENTRY("--- OSD ---"),
|
||||
|
||||
OSD_SUBMENU_ENTRY("LAYOUTS", &cmsx_menuOsdLayout),
|
||||
OSD_SUBMENU_ENTRY("SETTINGS", &cmsx_menuOsdSettings),
|
||||
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
|
||||
|
||||
OSD_BACK_ENTRY,
|
||||
OSD_END_ENTRY,
|
||||
};
|
||||
|
||||
|
||||
const CMS_Menu cmsx_menuOsd = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUOSD",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = menuOsdEntries,
|
||||
};
|
||||
|
||||
#endif // CMS
|
||||
|
|
|
@ -17,5 +17,4 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
extern const CMS_Menu cmsx_menuAlarms;
|
||||
extern const CMS_Menu cmsx_menuOsdLayout;
|
||||
extern const CMS_Menu cmsx_menuOsd;
|
||||
|
|
|
@ -89,7 +89,7 @@ static const OSD_TAB_t trampCmsEntChan = { &trampCmsChan, VTX_TRAMP_CHANNEL_COUN
|
|||
|
||||
static uint8_t trampCmsPower = 1;
|
||||
|
||||
static const OSD_TAB_t trampCmsEntPower = { &trampCmsPower, sizeof(trampPowerTable), trampPowerNames };
|
||||
static const OSD_TAB_t trampCmsEntPower = { &trampCmsPower, VTX_TRAMP_POWER_COUNT, trampPowerNames };
|
||||
|
||||
static void trampCmsUpdateFreqRef(void)
|
||||
{
|
||||
|
|
|
@ -205,6 +205,13 @@ float biquadFilterApply(biquadFilter_t *filter, float input)
|
|||
return result;
|
||||
}
|
||||
|
||||
float biquadFilterReset(biquadFilter_t *filter, float value)
|
||||
{
|
||||
filter->d1 = value - (value * filter->b0);
|
||||
filter->d2 = (filter->b2 - filter->a2) * value;
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* FIR filter
|
||||
*/
|
||||
|
|
|
@ -73,6 +73,7 @@ void biquadFilterInitNotch(biquadFilter_t *filter, uint32_t samplingIntervalUs,
|
|||
void biquadFilterInitLPF(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs);
|
||||
void biquadFilterInit(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs, float Q, biquadFilterType_e filterType);
|
||||
float biquadFilterApply(biquadFilter_t *filter, float sample);
|
||||
float biquadFilterReset(biquadFilter_t *filter, float value);
|
||||
float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff);
|
||||
|
||||
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);
|
||||
|
|
|
@ -58,7 +58,7 @@ PG_RESET_TEMPLATE(timeConfig_t, timeConfig,
|
|||
.tz_automatic_dst = TZ_AUTO_DST_OFF,
|
||||
);
|
||||
|
||||
static rtcTime_t dateTimeToRtcTime(dateTime_t *dt)
|
||||
static rtcTime_t dateTimeToRtcTime(const dateTime_t *dt)
|
||||
{
|
||||
unsigned int second = dt->seconds; // 0-59
|
||||
unsigned int minute = dt->minutes; // 0-59
|
||||
|
@ -157,6 +157,26 @@ static bool isDST(rtcTime_t t)
|
|||
switch ((tz_automatic_dst_e) timeConfig()->tz_automatic_dst) {
|
||||
case TZ_AUTO_DST_OFF:
|
||||
break;
|
||||
case TZ_AUTO_DST_EU: // begins at 1:00 a.m. on the last Sunday of March and ends at 1:00 a.m. on the last Sunday of October
|
||||
if (dateTime.month < 3 || dateTime.month > 10) {
|
||||
return false;
|
||||
}
|
||||
if (dateTime.month > 3 && dateTime.month < 10) {
|
||||
return true;
|
||||
}
|
||||
lastSunday = lastSundayOfMonth(dateTime.year, dateTime.month);
|
||||
if ((dateTime.day < lastSunday) || (dateTime.day > lastSunday)) {
|
||||
return !(dateTime.month == 3);
|
||||
}
|
||||
if (dateTime.day == lastSunday) {
|
||||
if (dateTime.month == 3) {
|
||||
return dateTime.hours >= 1;
|
||||
}
|
||||
if (dateTime.month == 10) {
|
||||
return dateTime.hours < 1;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TZ_AUTO_DST_USA: // begins at 2:00 a.m. on the second Sunday of March and ends at 2:00 a.m. on the first Sunday of November
|
||||
if (dateTime.month < 3 || dateTime.month > 11) {
|
||||
return false;
|
||||
|
@ -180,39 +200,24 @@ static bool isDST(rtcTime_t t)
|
|||
return dateTime.day < firstSunday;
|
||||
}
|
||||
break;
|
||||
case TZ_AUTO_DST_EU: // begins at 1:00 a.m. on the last Sunday of March and ends at 1:00 a.m. on the last Sunday of October
|
||||
if (dateTime.month < 3 || dateTime.month > 10) {
|
||||
return false;
|
||||
}
|
||||
if (dateTime.month > 3 && dateTime.month < 10) {
|
||||
return true;
|
||||
}
|
||||
lastSunday = lastSundayOfMonth(dateTime.year, dateTime.month);
|
||||
if ((dateTime.day < lastSunday) || (dateTime.day > lastSunday)) {
|
||||
return !(dateTime.month == 3);
|
||||
}
|
||||
if (dateTime.day == lastSunday) {
|
||||
if (dateTime.month == 3) {
|
||||
return dateTime.hours >= 1;
|
||||
}
|
||||
if (dateTime.month == 10) {
|
||||
return dateTime.hours < 1;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void dateTimeWithOffset(dateTime_t *dateTimeOffset, dateTime_t *dateTimeInitial, int16_t minutes, bool automatic_dst)
|
||||
static void dateTimeWithOffset(dateTime_t *dateTimeOffset, const dateTime_t *dateTimeInitial, int16_t *minutes, bool automatic_dst)
|
||||
{
|
||||
rtcTime_t initialTime = dateTimeToRtcTime(dateTimeInitial);
|
||||
rtcTime_t offsetTime = rtcTimeMake(rtcTimeGetSeconds(&initialTime) + minutes * 60, rtcTimeGetMillis(&initialTime));
|
||||
rtcTime_t offsetTime = rtcTimeMake(rtcTimeGetSeconds(&initialTime) + *minutes * 60, rtcTimeGetMillis(&initialTime));
|
||||
#if defined(RTC_AUTOMATIC_DST)
|
||||
if (automatic_dst && isDST(offsetTime)) {
|
||||
offsetTime += 3600;
|
||||
// Add one hour. Tell the caller that the
|
||||
// offset has changed.
|
||||
*minutes += 60;
|
||||
offsetTime += 60 * 60 * MILLIS_PER_SECOND;
|
||||
}
|
||||
#else
|
||||
UNUSED(automatic_dst);
|
||||
#endif
|
||||
rtcTimeToDateTime(dateTimeOffset, offsetTime);
|
||||
}
|
||||
|
@ -226,10 +231,10 @@ static bool dateTimeFormat(char *buf, dateTime_t *dateTime, int16_t offset, bool
|
|||
bool retVal = true;
|
||||
|
||||
// Apply offset if necessary
|
||||
if (offset != 0) {
|
||||
if (offset != 0 || automatic_dst) {
|
||||
dateTimeWithOffset(&local, dateTime, &offset, automatic_dst);
|
||||
tz_hours = offset / 60;
|
||||
tz_minutes = ABS(offset % 60);
|
||||
dateTimeWithOffset(&local, dateTime, offset, automatic_dst);
|
||||
dateTime = &local;
|
||||
}
|
||||
|
||||
|
@ -271,12 +276,13 @@ bool dateTimeFormatUTC(char *buf, dateTime_t *dt)
|
|||
|
||||
bool dateTimeFormatLocal(char *buf, dateTime_t *dt)
|
||||
{
|
||||
return dateTimeFormat(buf, dt, timeConfig()->tz_offset, timeConfig()->tz_automatic_dst);
|
||||
return dateTimeFormat(buf, dt, timeConfig()->tz_offset, true);
|
||||
}
|
||||
|
||||
void dateTimeUTCToLocal(dateTime_t *utcDateTime, dateTime_t *localDateTime)
|
||||
void dateTimeUTCToLocal(dateTime_t *localDateTime, const dateTime_t *utcDateTime)
|
||||
{
|
||||
dateTimeWithOffset(localDateTime, utcDateTime, timeConfig()->tz_offset, timeConfig()->tz_automatic_dst);
|
||||
int16_t offset = timeConfig()->tz_offset;
|
||||
dateTimeWithOffset(localDateTime, utcDateTime, &offset, true);
|
||||
}
|
||||
|
||||
bool dateTimeSplitFormatted(char *formatted, char **date, char **time)
|
||||
|
@ -326,6 +332,15 @@ bool rtcGetDateTime(dateTime_t *dt)
|
|||
return false;
|
||||
}
|
||||
|
||||
bool rtcGetDateTimeLocal(dateTime_t *dt)
|
||||
{
|
||||
if (rtcGetDateTime(dt)) {
|
||||
dateTimeUTCToLocal(dt, dt);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool rtcSetDateTime(dateTime_t *dt)
|
||||
{
|
||||
rtcTime_t t = dateTimeToRtcTime(dt);
|
||||
|
|
|
@ -93,7 +93,7 @@ typedef struct _dateTime_s {
|
|||
bool dateTimeFormatUTC(char *buf, dateTime_t *dt);
|
||||
bool dateTimeFormatLocal(char *buf, dateTime_t *dt);
|
||||
|
||||
void dateTimeUTCToLocal(dateTime_t *utcDateTime, dateTime_t *localDateTime);
|
||||
void dateTimeUTCToLocal(dateTime_t *localDateTime, const dateTime_t *utcDateTime);
|
||||
// dateTimeSplitFormatted splits a formatted date into its date
|
||||
// and time parts. Note that the string pointed by formatted will
|
||||
// be modifed and will become invalid after calling this function.
|
||||
|
@ -105,4 +105,5 @@ bool rtcGet(rtcTime_t *t);
|
|||
bool rtcSet(rtcTime_t *t);
|
||||
|
||||
bool rtcGetDateTime(dateTime_t *dt);
|
||||
bool rtcGetDateTimeLocal(dateTime_t *dt);
|
||||
bool rtcSetDateTime(dateTime_t *dt);
|
||||
|
|
|
@ -113,3 +113,7 @@
|
|||
#define PG_RESERVED_FOR_TESTING_2 4094
|
||||
#define PG_RESERVED_FOR_TESTING_3 4093
|
||||
|
||||
#define PG_ID_INVALID 0
|
||||
#define PG_ID_FIRST PG_CF_START
|
||||
#define PG_ID_LAST PG_INAV_END
|
||||
|
||||
|
|
|
@ -102,6 +102,7 @@ typedef enum {
|
|||
DEVHW_IST8308,
|
||||
DEVHW_QMC5883,
|
||||
DEVHW_MAG3110,
|
||||
DEVHW_LIS3MDL,
|
||||
|
||||
/* OSD chips */
|
||||
DEVHW_MAX7456,
|
||||
|
|
|
@ -33,6 +33,12 @@ void spiBusSetSpeed(const busDevice_t * dev, busSpeed_e speed)
|
|||
{
|
||||
const SPIClockSpeed_e spiClock[] = { SPI_CLOCK_INITIALIZATON, SPI_CLOCK_SLOW, SPI_CLOCK_STANDARD, SPI_CLOCK_FAST, SPI_CLOCK_ULTRAFAST };
|
||||
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);
|
||||
|
||||
#ifdef BUS_SPI_SPEED_MAX
|
||||
if (speed > BUS_SPI_SPEED_MAX)
|
||||
speed = BUS_SPI_SPEED_MAX;
|
||||
#endif
|
||||
|
||||
spiSetSpeed(instance, spiClock[speed]);
|
||||
}
|
||||
|
||||
|
|
|
@ -92,6 +92,7 @@
|
|||
#define IST8310_REG_CNTRL1 0x0A
|
||||
#define IST8310_REG_CNTRL2 0x0B
|
||||
#define IST8310_REG_AVERAGE 0x41
|
||||
#define IST8310_REG_PDCNTL 0x42
|
||||
|
||||
// Parameter
|
||||
// ODR = Output Data Rate, we use single measure mode for getting more data.
|
||||
|
@ -104,6 +105,7 @@
|
|||
// Device ID (ist8310 -> 0x10)
|
||||
#define IST8310_CHIP_ID 0x10
|
||||
#define IST8310_AVG_16 0x24
|
||||
#define IST8310_PULSE_DURATION_NORMAL 0xC0
|
||||
|
||||
#define IST8310_CNTRL2_RESET 0x01
|
||||
#define IST8310_CNTRL2_DRPOL 0x04
|
||||
|
@ -117,6 +119,9 @@ static bool ist8310Init(magDev_t * mag)
|
|||
busWrite(mag->busDev, IST8310_REG_AVERAGE, IST8310_AVG_16);
|
||||
delay(5);
|
||||
|
||||
busWrite(mag->busDev, IST8310_REG_PDCNTL, IST8310_PULSE_DURATION_NORMAL);
|
||||
delay(5);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -135,9 +140,9 @@ static bool ist8310Read(magDev_t * mag)
|
|||
return false;
|
||||
}
|
||||
|
||||
// need to modify when confirming the pcb direction
|
||||
// Looks like datasheet is incorrect and we need to invert Y axis to conform to right hand rule
|
||||
mag->magADCRaw[X] = (int16_t)(buf[1] << 8 | buf[0]) * LSB2FSV;
|
||||
mag->magADCRaw[Y] = (int16_t)(buf[3] << 8 | buf[2]) * LSB2FSV;
|
||||
mag->magADCRaw[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * LSB2FSV;
|
||||
mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]) * LSB2FSV;
|
||||
|
||||
return true;
|
||||
|
|
184
src/main/drivers/compass/compass_lis3mdl.c
Normal file
184
src/main/drivers/compass/compass_lis3mdl.c
Normal file
|
@ -0,0 +1,184 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_MAG_LIS3MDL
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
||||
#include "drivers/compass/compass.h"
|
||||
|
||||
#include "compass_lis3mdl.h"
|
||||
|
||||
#define LIS3MDL_MAG_I2C_ADDRESS 0x1E
|
||||
#define LIS3MDL_MAG_I2C_ADDRESS2 0x1C // LIS3MDL has two possible addresses, selected by a physical pin
|
||||
#define LIS3MDL_DEVICE_ID 0x3D
|
||||
|
||||
#define LIS3MDL_REG_WHO_AM_I 0x0F
|
||||
|
||||
#define LIS3MDL_REG_CTRL_REG1 0x20
|
||||
#define LIS3MDL_REG_CTRL_REG2 0x21
|
||||
#define LIS3MDL_REG_CTRL_REG3 0x22
|
||||
#define LIS3MDL_REG_CTRL_REG4 0x23
|
||||
#define LIS3MDL_REG_CTRL_REG5 0x24
|
||||
|
||||
#define LIS3MDL_REG_STATUS_REG 0x27
|
||||
|
||||
#define LIS3MDL_REG_OUT_X_L 0x28
|
||||
#define LIS3MDL_REG_OUT_X_H 0x29
|
||||
#define LIS3MDL_REG_OUT_Y_L 0x2A
|
||||
#define LIS3MDL_REG_OUT_Y_H 0x2B
|
||||
#define LIS3MDL_REG_OUT_Z_L 0x2C
|
||||
#define LIS3MDL_REG_OUT_Z_H 0x2D
|
||||
|
||||
#define LIS3MDL_TEMP_OUT_L 0x2E
|
||||
#define LIS3MDL_TEMP_OUT_H 0x2F
|
||||
|
||||
#define LIS3MDL_INT_CFG 0x30
|
||||
#define LIS3MDL_INT_SRC 0x31
|
||||
#define LIS3MDL_THS_L 0x32
|
||||
#define LIS3MDL_THS_H 0x33
|
||||
|
||||
// CTRL_REG1
|
||||
#define LIS3MDL_TEMP_EN 0x80 // Default 0
|
||||
#define LIS3MDL_OM_LOW_POWER 0x00 // Default
|
||||
#define LIS3MDL_OM_MED_PROF 0x20
|
||||
#define LIS3MDL_OM_HI_PROF 0x40
|
||||
#define LIS3MDL_OM_ULTRA_HI_PROF 0x60
|
||||
#define LIS3MDL_DO_0_625 0x00
|
||||
#define LIS3MDL_DO_1_25 0x04
|
||||
#define LIS3MDL_DO_2_5 0x08
|
||||
#define LIS3MDL_DO_5 0x0C
|
||||
#define LIS3MDL_DO_10 0x10 // Default
|
||||
#define LIS3MDL_DO_20 0x14
|
||||
#define LIS3MDL_DO_40 0x18
|
||||
#define LIS3MDL_DO_80 0x1C
|
||||
#define LIS3MDL_FAST_ODR 0x02
|
||||
|
||||
// CTRL_REG2
|
||||
#define LIS3MDL_FS_4GAUSS 0x00 // Default
|
||||
#define LIS3MDL_FS_8GAUSS 0x20
|
||||
#define LIS3MDL_FS_12GAUSS 0x40
|
||||
#define LIS3MDL_FS_16GAUSS 0x60
|
||||
#define LIS3MDL_REBOOT 0x08
|
||||
#define LIS3MDL_SOFT_RST 0x04
|
||||
|
||||
// CTRL_REG3
|
||||
#define LIS3MDL_LP 0x20 // Default 0
|
||||
#define LIS3MDL_SIM 0x04 // Default 0
|
||||
#define LIS3MDL_MD_CONTINUOUS 0x00 // Default
|
||||
#define LIS3MDL_MD_SINGLE 0x01
|
||||
#define LIS3MDL_MD_POWERDOWN 0x03
|
||||
|
||||
// CTRL_REG4
|
||||
#define LIS3MDL_ZOM_LP 0x00 // Default
|
||||
#define LIS3MDL_ZOM_MP 0x04
|
||||
#define LIS3MDL_ZOM_HP 0x08
|
||||
#define LIS3MDL_ZOM_UHP 0x0C
|
||||
#define LIS3MDL_BLE 0x02 // Default 0
|
||||
|
||||
// CTRL_REG5
|
||||
#define LIS3MDL_FAST_READ 0x80 // Default 0
|
||||
#define LIS3MDL_BDU 0x40 // Default 0
|
||||
|
||||
static bool lis3mdlRead(magDev_t * mag)
|
||||
{
|
||||
bool ack;
|
||||
uint8_t status = 0;
|
||||
|
||||
ack = busRead(mag->busDev, LIS3MDL_REG_STATUS_REG, &status);
|
||||
|
||||
if ( !( ack && ( ( status & 0x08 ) >> 3 ) ) ) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t buf[6];
|
||||
|
||||
ack = busReadBuf(mag->busDev, LIS3MDL_REG_OUT_X_L, buf, 6);
|
||||
|
||||
if (!ack) {
|
||||
mag->magADCRaw[X] = 0;
|
||||
mag->magADCRaw[Y] = 0;
|
||||
mag->magADCRaw[Z] = 0;
|
||||
return false;
|
||||
}
|
||||
|
||||
mag->magADCRaw[X] = (int16_t)(buf[1] << 8 | buf[0]) / 4;
|
||||
mag->magADCRaw[Y] = (int16_t)(buf[3] << 8 | buf[2]) / 4;
|
||||
mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]) / 4;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#define DETECTION_MAX_RETRY_COUNT 5
|
||||
static bool deviceDetect(magDev_t * mag)
|
||||
{
|
||||
for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
|
||||
delay(10);
|
||||
|
||||
uint8_t sig = 0;
|
||||
bool ack = busRead(mag->busDev, LIS3MDL_REG_WHO_AM_I, &sig);
|
||||
|
||||
if (ack && sig == LIS3MDL_DEVICE_ID) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool lis3mdlInit(magDev_t *mag)
|
||||
{
|
||||
busWrite(mag->busDev, LIS3MDL_REG_CTRL_REG2, LIS3MDL_FS_4GAUSS); // Configuration Register 2
|
||||
busWrite(mag->busDev, LIS3MDL_REG_CTRL_REG1, LIS3MDL_TEMP_EN | LIS3MDL_OM_ULTRA_HI_PROF | LIS3MDL_DO_80); // Configuration Register 1
|
||||
busWrite(mag->busDev, LIS3MDL_REG_CTRL_REG5, LIS3MDL_BDU); // Configuration Register 5
|
||||
busWrite(mag->busDev, LIS3MDL_REG_CTRL_REG4, LIS3MDL_ZOM_UHP); // Configuration Register 4
|
||||
busWrite(mag->busDev, LIS3MDL_REG_CTRL_REG3, 0x00); // Configuration Register 3
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool lis3mdlDetect(magDev_t * mag)
|
||||
{
|
||||
mag->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_LIS3MDL, mag->magSensorToUse, OWNER_COMPASS);
|
||||
if (mag->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// TODO: Add check for second possible I2C address
|
||||
|
||||
if (!deviceDetect(mag)) {
|
||||
busDeviceDeInit(mag->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
mag->init = lis3mdlInit;
|
||||
mag->read = lis3mdlRead;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
23
src/main/drivers/compass/compass_lis3mdl.h
Normal file
23
src/main/drivers/compass/compass_lis3mdl.h
Normal file
|
@ -0,0 +1,23 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
||||
bool lis3mdlDetect(magDev_t* mag);
|
|
@ -122,20 +122,24 @@ static bool qmc5883Read(magDev_t * mag)
|
|||
#define DETECTION_MAX_RETRY_COUNT 5
|
||||
static bool deviceDetect(magDev_t * mag)
|
||||
{
|
||||
for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
|
||||
// Must write reset first - don't care about the result
|
||||
busWrite(mag->busDev, QMC5883L_REG_CONF2, QMC5883L_RST);
|
||||
delay(20);
|
||||
|
||||
for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
|
||||
delay(10);
|
||||
delay(30);
|
||||
|
||||
uint8_t sig = 0;
|
||||
bool ack = busRead(mag->busDev, QMC5883L_REG_ID, &sig);
|
||||
|
||||
if (ack && sig == QMC5883_ID_VAL) {
|
||||
// Should be in standby mode after soft reset and sensor is really present
|
||||
// Reading ChipID of 0xFF alone is not sufficient to be sure the QMC is present
|
||||
|
||||
ack = busRead(mag->busDev, QMC5883L_REG_CONF1, &sig);
|
||||
if (ack && sig == QMC5883L_MODE_STANDBY) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -154,6 +154,7 @@ static bool m25p16_readIdentification(void)
|
|||
switch (chipID) {
|
||||
case JEDEC_ID_MICRON_M25P16:
|
||||
case JEDEC_ID_SPANSION_S25FL116:
|
||||
case JEDEC_ID_WINBOND_W25Q16:
|
||||
geometry.sectors = 32;
|
||||
geometry.pagesPerSector = 256;
|
||||
break;
|
||||
|
|
|
@ -1,117 +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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "io_impl.h"
|
||||
|
||||
#include "inverter.h"
|
||||
|
||||
#ifdef USE_INVERTER
|
||||
static void inverterSet(IO_t pin, bool on)
|
||||
{
|
||||
IOWrite(pin, on);
|
||||
}
|
||||
|
||||
static void initInverter(ioTag_t ioTag)
|
||||
{
|
||||
IO_t pin = IOGetByTag(ioTag);
|
||||
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterSet(pin, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
void initInverters(void)
|
||||
{
|
||||
#ifdef INVERTER_PIN_UART1
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART1));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART2
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART2));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART3
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART3));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART4
|
||||
initInverter(IO_TAG(INVERTER_PIN_USART4));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART5
|
||||
initInverter(IO_TAG(INVERTER_PIN_USART5));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART6
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART6));
|
||||
#endif
|
||||
}
|
||||
|
||||
void enableInverter(USART_TypeDef *USARTx, bool on)
|
||||
{
|
||||
#ifdef USE_INVERTER
|
||||
IO_t pin = IO_NONE;
|
||||
|
||||
#ifdef INVERTER_PIN_UART1
|
||||
if (USARTx == USART1) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART1));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART2
|
||||
if (USARTx == USART2) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART2));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART3
|
||||
if (USARTx == USART3) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART3));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART4
|
||||
if (USARTx == USART4) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_USART4));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART5
|
||||
if (USARTx == USART5) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_USART5));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART6
|
||||
if (USARTx == USART6) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART6));
|
||||
}
|
||||
#endif
|
||||
|
||||
inverterSet(pin, on);
|
||||
#else
|
||||
UNUSED(USARTx);
|
||||
UNUSED(on);
|
||||
#endif
|
||||
}
|
|
@ -13,7 +13,6 @@
|
|||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
#define PCA9685_ADDR 0x40
|
||||
#define PCA9685_MODE1 0x00
|
||||
#define PCA9685_PRESCALE 0xFE
|
||||
|
||||
|
|
|
@ -227,7 +227,7 @@ bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
|
|||
|
||||
void pwmWriteServo(uint8_t index, uint16_t value)
|
||||
{
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
|
||||
/*
|
||||
* If PCA9685 is enabled and but not detected, we do not want to write servo
|
||||
|
|
|
@ -28,23 +28,28 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "inverter.h"
|
||||
|
||||
#include "drivers/uart_inverter.h"
|
||||
|
||||
#include "serial.h"
|
||||
#include "serial_uart.h"
|
||||
#include "serial_uart_impl.h"
|
||||
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
|
||||
#if !defined(USE_UART_INVERTER) && !defined(STM32F303xC)
|
||||
UNUSED(uartPort);
|
||||
#else
|
||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||
|
||||
#ifdef USE_INVERTER
|
||||
if (inverted) {
|
||||
// Enable hardware inverter if available.
|
||||
enableInverter(uartPort->USARTx, true);
|
||||
#ifdef USE_UART_INVERTER
|
||||
uartInverterLine_e invertedLines = UART_INVERTER_LINE_NONE;
|
||||
if (uartPort->port.mode & MODE_RX) {
|
||||
invertedLines |= UART_INVERTER_LINE_RX;
|
||||
}
|
||||
if (uartPort->port.mode & MODE_TX) {
|
||||
invertedLines |= UART_INVERTER_LINE_TX;
|
||||
}
|
||||
uartInverterSet(uartPort->USARTx, invertedLines, inverted);
|
||||
#endif
|
||||
|
||||
#ifdef STM32F303xC
|
||||
|
|
|
@ -31,7 +31,6 @@
|
|||
#include "common/utils.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "inverter.h"
|
||||
#include "dma.h"
|
||||
|
||||
#include "serial.h"
|
||||
|
|
|
@ -52,6 +52,7 @@ void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
|
|||
STATIC_UNIT_TESTED timeUs_t usTicks = 0;
|
||||
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
|
||||
STATIC_UNIT_TESTED volatile timeMs_t sysTickUptime = 0;
|
||||
STATIC_UNIT_TESTED volatile uint32_t sysTickValStamp = 0;
|
||||
// cached value of RCC->CSR
|
||||
uint32_t cachedRccCsrValue;
|
||||
|
||||
|
@ -81,6 +82,7 @@ void SysTick_Handler(void)
|
|||
{
|
||||
ATOMIC_BLOCK(NVIC_PRIO_MAX) {
|
||||
sysTickUptime++;
|
||||
sysTickValStamp = SysTick->VAL;
|
||||
sysTickPending = 0;
|
||||
(void)(SysTick->CTRL);
|
||||
}
|
||||
|
@ -148,12 +150,8 @@ timeUs_t micros(void)
|
|||
do {
|
||||
ms = sysTickUptime;
|
||||
cycle_cnt = SysTick->VAL;
|
||||
/*
|
||||
* If the SysTick timer expired during the previous instruction, we need to give it a little time for that
|
||||
* interrupt to be delivered before we can recheck sysTickUptime:
|
||||
*/
|
||||
asm volatile("\tnop\n");
|
||||
} while (ms != sysTickUptime);
|
||||
} while (ms != sysTickUptime || cycle_cnt > sysTickValStamp);
|
||||
|
||||
return ((timeUs_t)ms * 1000LL) + (usTicks * 1000LL - (timeUs_t)cycle_cnt) / usTicks;
|
||||
}
|
||||
|
||||
|
|
|
@ -94,10 +94,10 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
|
|||
RCC_APB1Periph_I2C1 |
|
||||
RCC_APB1Periph_I2C2 |
|
||||
RCC_APB1Periph_I2C3 |
|
||||
RCC_APB1Periph_CAN1 |
|
||||
RCC_APB1Periph_CAN2 |
|
||||
// RCC_APB1Periph_CAN1 |
|
||||
// RCC_APB1Periph_CAN2 |
|
||||
RCC_APB1Periph_PWR |
|
||||
RCC_APB1Periph_DAC |
|
||||
// RCC_APB1Periph_DAC |
|
||||
0, ENABLE);
|
||||
|
||||
RCC_APB2PeriphClockCmd(
|
||||
|
@ -109,7 +109,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
|
|||
RCC_APB2Periph_ADC1 |
|
||||
RCC_APB2Periph_ADC2 |
|
||||
RCC_APB2Periph_ADC3 |
|
||||
RCC_APB2Periph_SDIO |
|
||||
// RCC_APB2Periph_SDIO |
|
||||
RCC_APB2Periph_SPI1 |
|
||||
RCC_APB2Periph_SYSCFG |
|
||||
RCC_APB2Periph_TIM9 |
|
||||
|
@ -119,7 +119,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
|
|||
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone
|
||||
|
|
|
@ -188,9 +188,15 @@ void timerInit(void)
|
|||
/* enable the timer peripherals */
|
||||
for (int i = 0; i < timerHardwareCount; i++) {
|
||||
unsigned timer = lookupTimerIndex(timerHardware[i].tim);
|
||||
|
||||
RCC_ClockCmd(timerDefinitions[timer].rcc, ENABLE);
|
||||
}
|
||||
|
||||
/* Before 2.0 timer outputs were initialized to IOCFG_AF_PP_PD even if not used */
|
||||
/* To keep compatibility make sure all timer output pins are mapped to INPUT with weak pull-down */
|
||||
for (int i = 0; i < timerHardwareCount; i++) {
|
||||
const timerHardware_t *timerHardwarePtr = &timerHardware[i];
|
||||
IOConfigGPIO(IOGetByTag(timerHardwarePtr->tag), IOCFG_IPD);
|
||||
}
|
||||
}
|
||||
|
||||
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
|
||||
|
|
188
src/main/drivers/uart_inverter.c
Normal file
188
src/main/drivers/uart_inverter.c
Normal file
|
@ -0,0 +1,188 @@
|
|||
/*
|
||||
* 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 <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/uart_inverter.h"
|
||||
|
||||
#if defined(USE_UART_INVERTER)
|
||||
|
||||
static void inverterPinSet(IO_t pin, bool on)
|
||||
{
|
||||
IOWrite(pin, on);
|
||||
}
|
||||
|
||||
static void initInverter(ioTag_t ioTag)
|
||||
{
|
||||
IO_t pin = IOGetByTag(ioTag);
|
||||
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterPinSet(pin, false);
|
||||
}
|
||||
|
||||
void uartInverterInit(void)
|
||||
{
|
||||
|
||||
// UART1
|
||||
#ifdef INVERTER_PIN_UART1_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART1_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART1_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART1_TX));
|
||||
#endif
|
||||
|
||||
// UART2
|
||||
#ifdef INVERTER_PIN_UART2_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART2_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART2_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART2_TX));
|
||||
#endif
|
||||
|
||||
// UART3
|
||||
#ifdef INVERTER_PIN_UART3_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART3_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART3_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART3_TX));
|
||||
#endif
|
||||
|
||||
// UART4
|
||||
#ifdef INVERTER_PIN_UART4_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART4_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART4_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART4_TX));
|
||||
#endif
|
||||
|
||||
// UART5
|
||||
#ifdef INVERTER_PIN_UART5_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART5_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART5_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART5_TX));
|
||||
#endif
|
||||
|
||||
// UART6
|
||||
#ifdef INVERTER_PIN_UART6_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART6_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART6_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART6_TX));
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void uartInverterSet(USART_TypeDef *USARTx, uartInverterLine_e line, bool enable)
|
||||
{
|
||||
IO_t rx_pin = IO_NONE;
|
||||
IO_t tx_pin = IO_NONE;
|
||||
|
||||
// UART1
|
||||
#if defined(INVERTER_PIN_UART1_RX) || defined(INVERTER_PIN_UART1_TX)
|
||||
if (USARTx == USART1) {
|
||||
#if defined(INVERTER_PIN_UART1_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART1_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART1_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART1_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART2
|
||||
#if defined(INVERTER_PIN_UART2_RX) || defined(INVERTER_PIN_UART2_TX)
|
||||
if (USARTx == USART2) {
|
||||
#if defined(INVERTER_PIN_UART2_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART2_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART2_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART2_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART3
|
||||
#if defined(INVERTER_PIN_UART3_RX) || defined(INVERTER_PIN_UART3_TX)
|
||||
if (USARTx == USART3) {
|
||||
#if defined(INVERTER_PIN_UART3_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART3_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART3_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART3_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART4
|
||||
#if defined(INVERTER_PIN_UART4_RX) || defined(INVERTER_PIN_UART4_TX)
|
||||
if (USARTx == USART4) {
|
||||
#if defined(INVERTER_PIN_UART4_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART4_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART4_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART4_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART5
|
||||
#if defined(INVERTER_PIN_UART5_RX) || defined(INVERTER_PIN_UART5_TX)
|
||||
if (USARTx == USART5) {
|
||||
#if defined(INVERTER_PIN_UART5_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART5_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART5_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART5_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART6
|
||||
#if defined(INVERTER_PIN_UART6_RX) || defined(INVERTER_PIN_UART6_TX)
|
||||
if (USARTx == USART6) {
|
||||
#if defined(INVERTER_PIN_UART6_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART6_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART6_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART6_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// Now do the actual work
|
||||
if (rx_pin != IO_NONE && (line & UART_INVERTER_LINE_RX)) {
|
||||
inverterPinSet(rx_pin, enable);
|
||||
}
|
||||
if (tx_pin != IO_NONE && (line & UART_INVERTER_LINE_TX)) {
|
||||
inverterPinSet(tx_pin, enable);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -17,10 +17,12 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if defined(INVERTER_PIN_UART1) || defined(INVERTER_PIN_UART2) || defined(INVERTER_PIN_UART3) || defined(INVERTER_PIN_UART4) || defined(INVERTER_PIN_UART5) || defined(INVERTER_PIN_UART6)
|
||||
#define USE_INVERTER
|
||||
#endif
|
||||
typedef enum {
|
||||
UART_INVERTER_LINE_NONE = 0,
|
||||
UART_INVERTER_LINE_RX = 1 << 0,
|
||||
UART_INVERTER_LINE_TX = 1 << 1,
|
||||
} uartInverterLine_e;
|
||||
|
||||
void initInverters(void);
|
||||
void uartInverterInit(void);
|
||||
|
||||
void enableInverter(USART_TypeDef *USARTx, bool on);
|
||||
void uartInverterSet(USART_TypeDef *USARTx, uartInverterLine_e line, bool enable);
|
|
@ -47,7 +47,7 @@
|
|||
|
||||
#define VTX_SETTINGS_POWER_COUNT 5
|
||||
#define VTX_SETTINGS_DEFAULT_POWER 1
|
||||
#define VTX_SETTINGS_MIN_POWER 0
|
||||
#define VTX_SETTINGS_MIN_POWER 1
|
||||
#define VTX_SETTINGS_MIN_USER_FREQ 5000
|
||||
#define VTX_SETTINGS_MAX_USER_FREQ 5999
|
||||
#define VTX_SETTINGS_FREQCMD
|
||||
|
|
|
@ -65,6 +65,7 @@ extern uint8_t __config_end;
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/cli.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
|
@ -352,14 +353,17 @@ static void printValuePointer(const setting_t *var, const void *valuePointer, ui
|
|||
}
|
||||
break;
|
||||
case MODE_LOOKUP:
|
||||
if (var->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) {
|
||||
cliPrintf(settingLookupTables[var->config.lookup.tableIndex].values[value]);
|
||||
{
|
||||
const char *name = settingLookupValueName(var, value);
|
||||
if (name) {
|
||||
cliPrintf(name);
|
||||
} else {
|
||||
settingGetName(var, buf);
|
||||
cliPrintLinef("VALUE %s OUT OF RANGE", buf);
|
||||
cliPrintLinef("VALUE %d OUT OF RANGE FOR %s", (int)value, buf);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool valuePtrEqualsDefault(const setting_t *value, const void *ptr, const void *ptrDefault)
|
||||
|
@ -425,8 +429,8 @@ static void dumpPgValue(const setting_t *value, uint8_t dumpMask)
|
|||
|
||||
static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask)
|
||||
{
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
const setting_t *value = &settingsTable[i];
|
||||
for (unsigned i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
const setting_t *value = settingGet(i);
|
||||
bufWriterFlush(cliWriter);
|
||||
if (SETTING_SECTION(value) == valueSection) {
|
||||
dumpPgValue(value, dumpMask);
|
||||
|
@ -453,7 +457,7 @@ static void cliPrintVarRange(const setting_t *var)
|
|||
break;
|
||||
case MODE_LOOKUP:
|
||||
{
|
||||
const lookupTableEntry_t *tableEntry = &settingLookupTables[var->config.lookup.tableIndex];
|
||||
const lookupTableEntry_t *tableEntry = settingLookupTable(var);
|
||||
cliPrint("Allowed values:");
|
||||
for (uint32_t i = 0; i < tableEntry->valueCount ; i++) {
|
||||
if (i > 0)
|
||||
|
@ -1263,7 +1267,7 @@ static void cliModeColor(char *cmdline)
|
|||
static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const servoParam_t *defaultServoParam)
|
||||
{
|
||||
// print out servo settings
|
||||
const char *format = "servo %u %d %d %d %d ";
|
||||
const char *format = "servo %u %d %d %d %d";
|
||||
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
const servoParam_t *servoConf = &servoParam[i];
|
||||
bool equalsDefault = false;
|
||||
|
@ -2020,15 +2024,7 @@ static void cliRebootEx(bool bootLoader)
|
|||
bufWriterFlush(cliWriter);
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
|
||||
stopMotors();
|
||||
stopPwmAllMotors();
|
||||
|
||||
delay(1000);
|
||||
if (bootLoader) {
|
||||
systemResetToBootloader();
|
||||
return;
|
||||
}
|
||||
systemReset();
|
||||
fcReboot(bootLoader);
|
||||
}
|
||||
|
||||
static void cliReboot(void)
|
||||
|
@ -2256,7 +2252,7 @@ static void cliGet(char *cmdline)
|
|||
char name[SETTING_MAX_NAME_LENGTH];
|
||||
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
val = &settingsTable[i];
|
||||
val = settingGet(i);
|
||||
if (settingNameContains(val, name, cmdline)) {
|
||||
cliPrintf("%s = ", name);
|
||||
cliPrintVar(val, 0);
|
||||
|
@ -2288,7 +2284,7 @@ static void cliSet(char *cmdline)
|
|||
if (len == 0 || (len == 1 && cmdline[0] == '*')) {
|
||||
cliPrintLine("Current settings:");
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
val = &settingsTable[i];
|
||||
val = settingGet(i);
|
||||
settingGetName(val, name);
|
||||
cliPrintf("%s = ", name);
|
||||
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
|
||||
|
@ -2310,7 +2306,7 @@ static void cliSet(char *cmdline)
|
|||
}
|
||||
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
val = &settingsTable[i];
|
||||
val = settingGet(i);
|
||||
// ensure exact match when setting to prevent setting variables with shorter names
|
||||
if (settingNameIsExactMatch(val, name, cmdline, variableNameLength)) {
|
||||
const setting_type_e type = SETTING_TYPE(val);
|
||||
|
@ -2341,7 +2337,7 @@ static void cliSet(char *cmdline)
|
|||
}
|
||||
break;
|
||||
case MODE_LOOKUP: {
|
||||
const lookupTableEntry_t *tableEntry = &settingLookupTables[settingsTable[i].config.lookup.tableIndex];
|
||||
const lookupTableEntry_t *tableEntry = settingLookupTable(val);
|
||||
bool matched = false;
|
||||
for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
|
||||
matched = sl_strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
|
||||
|
@ -2387,7 +2383,7 @@ static void cliStatus(char *cmdline)
|
|||
{
|
||||
UNUSED(cmdline);
|
||||
|
||||
char buf[FORMATTED_DATE_TIME_BUFSIZE];
|
||||
char buf[MAX(FORMATTED_DATE_TIME_BUFSIZE, SETTING_MAX_NAME_LENGTH)];
|
||||
dateTime_t dt;
|
||||
|
||||
cliPrintLinef("System Uptime: %d seconds", millis() / 1000);
|
||||
|
@ -2496,6 +2492,13 @@ static void cliStatus(char *cmdline)
|
|||
if (bitpos > 6) cliPrintf(" %s", armingDisableFlagNames[bitpos - 7]);
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
if (armingFlags & ARMING_DISABLED_INVALID_SETTING) {
|
||||
unsigned invalidIndex;
|
||||
if (!settingsValidate(&invalidIndex)) {
|
||||
settingGetName(settingGet(invalidIndex), buf);
|
||||
cliPrintLinef("Invalid setting: %s", buf);
|
||||
}
|
||||
}
|
||||
#else
|
||||
cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS);
|
||||
#endif
|
||||
|
|
|
@ -73,6 +73,7 @@
|
|||
#include "fc/rc_curves.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/settings.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
|
@ -283,7 +284,7 @@ void validateAndFixConfig(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifndef USE_PMW_SERVO_DRIVER
|
||||
#ifndef USE_PWM_SERVO_DRIVER
|
||||
featureClear(FEATURE_PWM_SERVO_DRIVER);
|
||||
#endif
|
||||
|
||||
|
@ -323,6 +324,12 @@ void validateAndFixConfig(void)
|
|||
gyroConfigMutable()->gyroSync = false;
|
||||
systemConfigMutable()->asyncMode = ASYNC_MODE_NONE;
|
||||
#endif
|
||||
|
||||
if (settingsValidate(NULL)) {
|
||||
DISABLE_ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING);
|
||||
} else {
|
||||
ENABLE_ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING);
|
||||
}
|
||||
}
|
||||
|
||||
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch)
|
||||
|
|
|
@ -35,6 +35,7 @@
|
|||
#include "drivers/serial.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/diagnostics.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
@ -607,7 +608,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
}
|
||||
|
||||
#if defined(AUTOTUNE_FIXED_WING) || defined(AUTOTUNE_MULTIROTOR)
|
||||
#if defined(USE_AUTOTUNE_FIXED_WING) || defined(USE_AUTOTUNE_MULTIROTOR)
|
||||
autotuneUpdateState();
|
||||
#endif
|
||||
|
||||
|
@ -706,7 +707,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
cycleTime = getTaskDeltaTime(TASK_SELF);
|
||||
dT = (float)cycleTime * 0.000001f;
|
||||
|
||||
if (ARMING_FLAG(ARMED) && ((!STATE(FIXED_WING)) || (isNavLaunchEnabled() && isFixedWingLaunchDetected()))) {
|
||||
if (ARMING_FLAG(ARMED) && ((!STATE(FIXED_WING)) || (!isNavLaunchEnabled()) || (isNavLaunchEnabled() && isFixedWingLaunchDetected()))) {
|
||||
flightTime += cycleTime;
|
||||
}
|
||||
|
||||
|
@ -833,6 +834,26 @@ void taskUpdateRxMain(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
// returns seconds
|
||||
float getFlightTime() {
|
||||
float getFlightTime()
|
||||
{
|
||||
return (float)(flightTime / 1000) / 1000;
|
||||
}
|
||||
|
||||
void fcReboot(bool bootLoader)
|
||||
{
|
||||
// stop motor/servo outputs
|
||||
stopMotors();
|
||||
stopPwmAllMotors();
|
||||
|
||||
// extra delay before reboot to give ESCs chance to reset
|
||||
delay(1000);
|
||||
|
||||
if (bootLoader) {
|
||||
systemResetToBootloader();
|
||||
}
|
||||
else {
|
||||
systemReset();
|
||||
}
|
||||
|
||||
while (true);
|
||||
}
|
||||
|
|
|
@ -40,3 +40,5 @@ disarmReason_t getDisarmReason(void);
|
|||
|
||||
bool isCalibrating(void);
|
||||
float getFlightTime();
|
||||
|
||||
void fcReboot(bool bootLoader);
|
|
@ -48,7 +48,6 @@
|
|||
#include "drivers/dma.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/inverter.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
@ -69,6 +68,7 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/uart_inverter.h"
|
||||
#include "drivers/vcd.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
|
@ -336,7 +336,7 @@ void init(void)
|
|||
pwmRxInit(systemConfig()->pwmRxInputFilteringMode);
|
||||
#endif
|
||||
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
/*
|
||||
If external PWM driver is enabled, for example PCA9685, disable internal
|
||||
servo handling mechanism, since external device will do that
|
||||
|
@ -375,8 +375,8 @@ void init(void)
|
|||
lightsInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_INVERTER
|
||||
initInverters();
|
||||
#ifdef USE_UART_INVERTER
|
||||
uartInverterInit();
|
||||
#endif
|
||||
|
||||
// Initialize buses
|
||||
|
@ -652,7 +652,7 @@ void init(void)
|
|||
pitotStartCalibration();
|
||||
#endif
|
||||
|
||||
#ifdef USE_VTX_CONTROL
|
||||
#if defined(USE_VTX_COMMON) && defined(USE_VTX_CONTROL)
|
||||
vtxControlInit();
|
||||
|
||||
#if defined(USE_VTX_COMMON)
|
||||
|
@ -668,13 +668,13 @@ void init(void)
|
|||
vtxTrampInit();
|
||||
#endif
|
||||
|
||||
#endif // USE_VTX_CONTROL
|
||||
#endif // USE_VTX_COMMON && USE_VTX_CONTROL
|
||||
|
||||
// Now that everything has powered up the voltage and cell count be determined.
|
||||
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
|
||||
batteryInit();
|
||||
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
if (feature(FEATURE_PWM_SERVO_DRIVER)) {
|
||||
pwmDriverInitialize();
|
||||
}
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#include "common/time.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
@ -47,6 +49,7 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/fc_msp.h"
|
||||
|
@ -185,16 +188,7 @@ static void mspFc4waySerialCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr
|
|||
static void mspRebootFn(serialPort_t *serialPort)
|
||||
{
|
||||
UNUSED(serialPort);
|
||||
|
||||
stopMotors();
|
||||
stopPwmAllMotors();
|
||||
|
||||
// extra delay before reboot to give ESCs chance to reset
|
||||
delay(1000);
|
||||
systemReset();
|
||||
|
||||
// control should never return here.
|
||||
while (true) ;
|
||||
fcReboot(false);
|
||||
}
|
||||
|
||||
static void serializeSDCardSummaryReply(sbuf_t *dst)
|
||||
|
@ -484,7 +478,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
|
||||
case MSP_RC:
|
||||
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
|
||||
sbufWriteU16(dst, rcData[i]);
|
||||
sbufWriteU16(dst, rcRaw[i]);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -2571,9 +2565,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
static const setting_t *mspReadSettingName(sbuf_t *src)
|
||||
static const setting_t *mspReadSetting(sbuf_t *src)
|
||||
{
|
||||
char name[SETTING_MAX_NAME_LENGTH];
|
||||
uint16_t id;
|
||||
uint8_t c;
|
||||
size_t s = 0;
|
||||
while (1) {
|
||||
|
@ -2582,6 +2577,14 @@ static const setting_t *mspReadSettingName(sbuf_t *src)
|
|||
}
|
||||
name[s++] = c;
|
||||
if (c == '\0') {
|
||||
if (s == 1) {
|
||||
// Payload starts with a zero, setting index
|
||||
// as uint16_t follows
|
||||
if (sbufReadU16Safe(&id, src)) {
|
||||
return settingGet(id);
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
break;
|
||||
}
|
||||
if (s == SETTING_MAX_NAME_LENGTH) {
|
||||
|
@ -2594,7 +2597,7 @@ static const setting_t *mspReadSettingName(sbuf_t *src)
|
|||
|
||||
static bool mspSettingCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
const setting_t *setting = mspReadSettingName(src);
|
||||
const setting_t *setting = mspReadSetting(src);
|
||||
if (!setting) {
|
||||
return false;
|
||||
}
|
||||
|
@ -2609,7 +2612,7 @@ static bool mspSetSettingCommand(sbuf_t *dst, sbuf_t *src)
|
|||
{
|
||||
UNUSED(dst);
|
||||
|
||||
const setting_t *setting = mspReadSettingName(src);
|
||||
const setting_t *setting = mspReadSetting(src);
|
||||
if (!setting) {
|
||||
return false;
|
||||
}
|
||||
|
@ -2701,6 +2704,94 @@ static bool mspSetSettingCommand(sbuf_t *dst, sbuf_t *src)
|
|||
return true;
|
||||
}
|
||||
|
||||
static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
const setting_t *setting = mspReadSetting(src);
|
||||
if (!setting) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Parameter Group ID
|
||||
sbufWriteU16(dst, settingGetPgn(setting));
|
||||
|
||||
// Type, section and mode
|
||||
sbufWriteU8(dst, SETTING_TYPE(setting));
|
||||
sbufWriteU8(dst, SETTING_SECTION(setting));
|
||||
sbufWriteU8(dst, SETTING_MODE(setting));
|
||||
|
||||
// Min as int32_t
|
||||
int32_t min = settingGetMin(setting);
|
||||
sbufWriteU32(dst, (uint32_t)min);
|
||||
// Max as uint32_t
|
||||
uint32_t max = settingGetMax(setting);
|
||||
sbufWriteU32(dst, max);
|
||||
|
||||
// Absolute setting index
|
||||
sbufWriteU16(dst, settingGetIndex(setting));
|
||||
|
||||
// If the setting is profile based, send the current one
|
||||
// and the count, both as uint8_t. For MASTER_VALUE, we
|
||||
// send two zeroes, so the MSP client can assume there
|
||||
// will always be two bytes.
|
||||
switch (SETTING_SECTION(setting)) {
|
||||
case MASTER_VALUE:
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
break;
|
||||
case PROFILE_VALUE:
|
||||
FALLTHROUGH;
|
||||
case CONTROL_RATE_VALUE:
|
||||
sbufWriteU8(dst, getConfigProfile());
|
||||
sbufWriteU8(dst, MAX_PROFILE_COUNT);
|
||||
break;
|
||||
case BATTERY_CONFIG_VALUE:
|
||||
sbufWriteU8(dst, getConfigBatteryProfile());
|
||||
sbufWriteU8(dst, MAX_BATTERY_PROFILE_COUNT);
|
||||
break;
|
||||
}
|
||||
|
||||
// If the setting uses a table, send each possible string (null terminated)
|
||||
if (SETTING_MODE(setting) == MODE_LOOKUP) {
|
||||
for (int ii = (int)min; ii <= (int)max; ii++) {
|
||||
const char *name = settingLookupValueName(setting, ii);
|
||||
sbufWriteDataSafe(dst, name, strlen(name) + 1);
|
||||
}
|
||||
}
|
||||
|
||||
// Finally, include the setting value. This way resource constrained callers
|
||||
// (e.g. a script in the radio) don't need to perform another call to retrieve
|
||||
// the value.
|
||||
const void *ptr = settingGetValuePointer(setting);
|
||||
size_t size = settingGetValueSize(setting);
|
||||
sbufWriteDataSafe(dst, ptr, size);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool mspParameterGroupsCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
uint16_t first;
|
||||
uint16_t last;
|
||||
uint16_t start;
|
||||
uint16_t end;
|
||||
|
||||
if (sbufReadU16Safe(&first, src)) {
|
||||
last = first;
|
||||
} else {
|
||||
first = PG_ID_FIRST;
|
||||
last = PG_ID_LAST;
|
||||
}
|
||||
|
||||
for (int ii = first; ii <= last; ii++) {
|
||||
if (settingsGetParameterGroupIndexes(ii, &start, &end)) {
|
||||
sbufWriteU16(dst, ii);
|
||||
sbufWriteU16(dst, start);
|
||||
sbufWriteU16(dst, end);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResult_e *ret)
|
||||
{
|
||||
switch (cmdMSP) {
|
||||
|
@ -2727,6 +2818,14 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
|
|||
*ret = mspSetSettingCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_COMMON_SETTING_INFO:
|
||||
*ret = mspSettingInfoCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_COMMON_PG_LIST:
|
||||
*ret = mspParameterGroupsCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
#if defined(USE_OSD)
|
||||
case MSP2_INAV_OSD_LAYOUTS:
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
|
|
|
@ -217,7 +217,7 @@ void initActiveBoxIds(void)
|
|||
activeBoxIds[activeBoxIdCount++] = BOXNAVLAUNCH;
|
||||
}
|
||||
activeBoxIds[activeBoxIdCount++] = BOXAUTOTRIM;
|
||||
#if defined(AUTOTUNE_FIXED_WING)
|
||||
#if defined(USE_AUTOTUNE_FIXED_WING)
|
||||
activeBoxIds[activeBoxIdCount++] = BOXAUTOTUNE;
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -101,12 +101,12 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
|
|||
static timeUs_t batMonitoringLastServiced = 0;
|
||||
timeUs_t BatMonitoringTimeSinceLastServiced = cmpTimeUs(currentTimeUs, batMonitoringLastServiced);
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER))
|
||||
if (isAmperageConfigured())
|
||||
currentMeterUpdate(BatMonitoringTimeSinceLastServiced);
|
||||
#ifdef USE_ADC
|
||||
if (feature(FEATURE_VBAT))
|
||||
batteryUpdate(BatMonitoringTimeSinceLastServiced);
|
||||
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) {
|
||||
if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
|
||||
powerMeterUpdate(BatMonitoringTimeSinceLastServiced);
|
||||
sagCompensatedVBatUpdate(currentTimeUs, BatMonitoringTimeSinceLastServiced);
|
||||
}
|
||||
|
@ -239,7 +239,7 @@ void taskLedStrip(timeUs_t currentTimeUs)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
void taskSyncPwmDriver(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
@ -306,7 +306,7 @@ void fcTasksInit(void)
|
|||
#ifdef USE_LIGHTS
|
||||
setTaskEnabled(TASK_LIGHTS, true);
|
||||
#endif
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || isAmperageConfigured());
|
||||
setTaskEnabled(TASK_TEMPERATURE, true);
|
||||
setTaskEnabled(TASK_RX, true);
|
||||
#ifdef USE_GPS
|
||||
|
@ -340,7 +340,7 @@ void fcTasksInit(void)
|
|||
#ifdef STACK_CHECK
|
||||
setTaskEnabled(TASK_STACK_CHECK, true);
|
||||
#endif
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER));
|
||||
#endif
|
||||
#ifdef USE_OSD
|
||||
|
@ -540,7 +540,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
[TASK_PWMDRIVER] = {
|
||||
.taskName = "PWMDRIVER",
|
||||
.taskFunc = taskSyncPwmDriver,
|
||||
|
@ -603,7 +603,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_VTX_CONTROL
|
||||
#if defined(USE_VTX_COMMON) && defined(USE_VTX_CONTROL)
|
||||
[TASK_VTXCTRL] = {
|
||||
.taskName = "VTXCTRL",
|
||||
.taskFunc = vtxUpdate,
|
||||
|
|
|
@ -638,12 +638,18 @@ void updateAdjustmentStates(bool canUseRxData)
|
|||
{
|
||||
for (int index = 0; index < MAX_ADJUSTMENT_RANGE_COUNT; index++) {
|
||||
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(index);
|
||||
if (adjustmentRange->adjustmentFunction == ADJUSTMENT_NONE) {
|
||||
// Range not set up
|
||||
continue;
|
||||
}
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentFunction - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
adjustmentState_t * const adjustmentState = &adjustmentStates[adjustmentRange->adjustmentIndex];
|
||||
|
||||
if (canUseRxData && isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range)) {
|
||||
if (!adjustmentState->config) {
|
||||
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
|
||||
}
|
||||
} else {
|
||||
adjustmentState_t * const adjustmentState = &adjustmentStates[index];
|
||||
if (adjustmentState->config == adjustmentConfig) {
|
||||
adjustmentState->config = NULL;
|
||||
}
|
||||
|
|
|
@ -17,9 +17,12 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
|
@ -31,7 +34,7 @@
|
|||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define YAW_LOOKUP_LENGTH 7
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
#define THROTTLE_LOOKUP_LENGTH 11
|
||||
|
||||
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
int16_t lookupThrottleRCMid; // THROTTLE curve mid point
|
||||
|
@ -55,12 +58,15 @@ void generateThrottleCurve(const controlRateConfig_t *controlRateConfig)
|
|||
int16_t rcLookup(int32_t stickDeflection, uint8_t expo)
|
||||
{
|
||||
float tmpf = stickDeflection / 100.0f;
|
||||
return (int16_t)((2500.0f + (float)expo * (tmpf * tmpf - 25.0f)) * tmpf / 25.0f);
|
||||
return lrintf((2500.0f + (float)expo * (tmpf * tmpf - 25.0f)) * tmpf / 25.0f);
|
||||
}
|
||||
|
||||
int16_t rcLookupThrottle(int32_t absoluteDeflection)
|
||||
uint16_t rcLookupThrottle(uint16_t absoluteDeflection)
|
||||
{
|
||||
const int32_t lookupStep = absoluteDeflection / 100;
|
||||
if (absoluteDeflection > 999)
|
||||
return motorConfig()->maxthrottle;
|
||||
|
||||
const uint8_t lookupStep = absoluteDeflection / 100;
|
||||
return lookupThrottleRC[lookupStep] + (absoluteDeflection - lookupStep * 100) * (lookupThrottleRC[lookupStep + 1] - lookupThrottleRC[lookupStep]) / 100;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,5 +21,5 @@ struct controlRateConfig_s;
|
|||
void generateThrottleCurve(const struct controlRateConfig_s *controlRateConfig);
|
||||
|
||||
int16_t rcLookup(int32_t stickDeflection, uint8_t expo);
|
||||
int16_t rcLookupThrottle(int32_t tmp);
|
||||
uint16_t rcLookupThrottle(uint16_t tmp);
|
||||
int16_t rcLookupThrottleMid(void);
|
||||
|
|
|
@ -34,7 +34,8 @@ static uint32_t enabledSensors = 0;
|
|||
const char *armingDisableFlagNames[]= {
|
||||
"FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS",
|
||||
"ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX",
|
||||
"THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM"
|
||||
"THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM",
|
||||
"SETTINGFAIL",
|
||||
};
|
||||
#endif
|
||||
|
||||
|
|
|
@ -42,12 +42,13 @@ typedef enum {
|
|||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23),
|
||||
ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24),
|
||||
ARMING_DISABLED_OOM = (1 << 25),
|
||||
ARMING_DISABLED_INVALID_SETTING = (1 << 26),
|
||||
|
||||
ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED |
|
||||
ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
|
||||
ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_BOXKILLSWITCH |
|
||||
ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU |
|
||||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM)
|
||||
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING)
|
||||
} armingFlag_e;
|
||||
|
||||
extern uint32_t armingFlags;
|
||||
|
|
|
@ -77,6 +77,76 @@ const setting_t *settingFind(const char *name)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
const setting_t *settingGet(unsigned index)
|
||||
{
|
||||
return index < SETTINGS_TABLE_COUNT ? &settingsTable[index] : NULL;
|
||||
}
|
||||
|
||||
unsigned settingGetIndex(const setting_t *val)
|
||||
{
|
||||
return val - settingsTable;
|
||||
}
|
||||
|
||||
bool settingsValidate(unsigned *invalidIndex)
|
||||
{
|
||||
for (unsigned ii = 0; ii < SETTINGS_TABLE_COUNT; ii++) {
|
||||
const setting_t *setting = settingGet(ii);
|
||||
setting_min_t min = settingGetMin(setting);
|
||||
setting_max_t max = settingGetMax(setting);
|
||||
void *ptr = settingGetValuePointer(setting);
|
||||
bool isValid = false;
|
||||
switch (SETTING_TYPE(setting)) {
|
||||
case VAR_UINT8:
|
||||
{
|
||||
uint8_t *value = ptr;
|
||||
isValid = *value >= min && *value <= max;
|
||||
break;
|
||||
}
|
||||
case VAR_INT8:
|
||||
{
|
||||
int8_t *value = ptr;
|
||||
isValid = *value >= min && *value <= (int8_t)max;
|
||||
break;
|
||||
}
|
||||
case VAR_UINT16:
|
||||
{
|
||||
uint16_t *value = ptr;
|
||||
isValid = *value >= min && *value <= max;
|
||||
break;
|
||||
}
|
||||
case VAR_INT16:
|
||||
{
|
||||
int16_t *value = ptr;
|
||||
isValid = *value >= min && *value <= (int16_t)max;
|
||||
break;
|
||||
}
|
||||
case VAR_UINT32:
|
||||
{
|
||||
uint32_t *value = ptr;
|
||||
isValid = *value >= (uint32_t)min && *value <= max;
|
||||
break;
|
||||
}
|
||||
case VAR_FLOAT:
|
||||
{
|
||||
float *value = ptr;
|
||||
isValid = *value >= min && *value <= max;
|
||||
break;
|
||||
}
|
||||
case VAR_STRING:
|
||||
// We assume all strings are valid
|
||||
isValid = true;
|
||||
break;
|
||||
}
|
||||
if (!isValid) {
|
||||
if (invalidIndex) {
|
||||
*invalidIndex = ii;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
size_t settingGetValueSize(const setting_t *val)
|
||||
{
|
||||
switch (SETTING_TYPE(val)) {
|
||||
|
@ -154,6 +224,23 @@ setting_max_t settingGetMax(const setting_t *val)
|
|||
return settingMinMaxTable[SETTING_INDEXES_GET_MAX(val)];
|
||||
}
|
||||
|
||||
const lookupTableEntry_t * settingLookupTable(const setting_t *val)
|
||||
{
|
||||
if (SETTING_MODE(val) == MODE_LOOKUP && val->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) {
|
||||
return &settingLookupTables[val->config.lookup.tableIndex];
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const char * settingLookupValueName(const setting_t *val, unsigned v)
|
||||
{
|
||||
const lookupTableEntry_t *table = settingLookupTable(val);
|
||||
if (table && v < table->valueCount) {
|
||||
return table->values[v];
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const char * settingGetString(const setting_t *val)
|
||||
{
|
||||
if (SETTING_TYPE(val) == VAR_STRING) {
|
||||
|
@ -180,3 +267,21 @@ setting_max_t settingGetStringMaxLength(const setting_t *val)
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool settingsGetParameterGroupIndexes(pgn_t pg, uint16_t *start, uint16_t *end)
|
||||
{
|
||||
unsigned acc = 0;
|
||||
for (int ii = 0; ii < SETTINGS_PGN_COUNT; ii++) {
|
||||
if (settingsPgn[ii] == pg) {
|
||||
if (start) {
|
||||
*start = acc;
|
||||
}
|
||||
if (end) {
|
||||
*end = acc + settingsPgnCounts[ii] - 1;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
acc += settingsPgnCounts[ii];
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -13,8 +13,6 @@ typedef struct lookupTableEntry_s {
|
|||
const uint8_t valueCount;
|
||||
} lookupTableEntry_t;
|
||||
|
||||
extern const lookupTableEntry_t settingLookupTables[];
|
||||
|
||||
#define SETTING_TYPE_OFFSET 0
|
||||
#define SETTING_SECTION_OFFSET 4
|
||||
#define SETTING_MODE_OFFSET 6
|
||||
|
@ -69,8 +67,6 @@ typedef struct {
|
|||
|
||||
} __attribute__((packed)) setting_t;
|
||||
|
||||
extern const setting_t settingsTable[];
|
||||
|
||||
static inline setting_type_e SETTING_TYPE(const setting_t *s) { return s->type & SETTING_TYPE_MASK; }
|
||||
static inline setting_section_e SETTING_SECTION(const setting_t *s) { return s->type & SETTING_SECTION_MASK; }
|
||||
static inline setting_mode_e SETTING_MODE(const setting_t *s) { return s->type & SETTING_MODE_MASK; }
|
||||
|
@ -81,6 +77,15 @@ bool settingNameIsExactMatch(const setting_t *val, char *buf, const char *cmdlin
|
|||
// Returns a setting_t with the exact name (case sensitive), or
|
||||
// NULL if no setting with that name exists.
|
||||
const setting_t *settingFind(const char *name);
|
||||
// Returns the setting at the given index, or NULL if
|
||||
// the index is greater than the total count.
|
||||
const setting_t *settingGet(unsigned index);
|
||||
// Returns the setting index for the given setting.
|
||||
unsigned settingGetIndex(const setting_t *val);
|
||||
// Checks if all settings have values in their valid ranges.
|
||||
// If they don't, invalidIndex is filled with the first invalid
|
||||
// settings index and false is returned.
|
||||
bool settingsValidate(unsigned *invalidIndex);
|
||||
// Returns the size in bytes of the setting value.
|
||||
size_t settingGetValueSize(const setting_t *val);
|
||||
pgn_t settingGetPgn(const setting_t *val);
|
||||
|
@ -100,6 +105,13 @@ setting_min_t settingGetMin(const setting_t *val);
|
|||
// depends on the target and build options, but will always be an unsigned
|
||||
// integer (e.g. uintxx_t,)
|
||||
setting_max_t settingGetMax(const setting_t *val);
|
||||
// Returns the lookup table for the given setting. If the setting mode
|
||||
// is not MODE_LOOKUP, it returns NULL;
|
||||
const lookupTableEntry_t * settingLookupTable(const setting_t *val);
|
||||
// Returns the string in the table which corresponds to the value v
|
||||
// for the given setting. If the setting mode is not MODE_LOOKUP or
|
||||
// if the value is out of range, it returns NULL.
|
||||
const char * settingLookupValueName(const setting_t *val, unsigned v);
|
||||
// Returns the setting value as a const char * iff the setting is of type
|
||||
// VAR_STRING. Otherwise it returns NULL.
|
||||
const char * settingGetString(const setting_t *val);
|
||||
|
@ -110,3 +122,7 @@ void settingSetString(const setting_t *val, const char *s, size_t size);
|
|||
// Returns the max string length (without counting the '\0' terminator)
|
||||
// for setting of type VAR_STRING. Otherwise it returns 0.
|
||||
setting_max_t settingGetStringMaxLength(const setting_t *val);
|
||||
|
||||
// Retrieve the setting indexes for the given PG. If the PG is not
|
||||
// found, these function returns false.
|
||||
bool settingsGetParameterGroupIndexes(pgn_t pg, uint16_t *start, uint16_t *end);
|
|
@ -10,7 +10,7 @@ tables:
|
|||
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"]
|
||||
enum: rangefinderType_e
|
||||
- name: mag_hardware
|
||||
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "FAKE"]
|
||||
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "FAKE"]
|
||||
enum: magSensor_e
|
||||
- name: opflow_hardware
|
||||
values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"]
|
||||
|
@ -343,12 +343,18 @@ groups:
|
|||
- name: rssi_channel
|
||||
min: 0
|
||||
max: MAX_SUPPORTED_RC_CHANNEL_COUNT
|
||||
- name: rssi_scale
|
||||
min: RSSI_SCALE_MIN
|
||||
max: RSSI_SCALE_MAX
|
||||
- name: rssi_invert
|
||||
field: rssiInvert
|
||||
type: bool
|
||||
- name: rssi_min
|
||||
field: rssiMin
|
||||
min: RSSI_VISIBLE_VALUE_MIN
|
||||
max: RSSI_VISIBLE_VALUE_MAX
|
||||
- name: rssi_max
|
||||
field: rssiMax
|
||||
min: RSSI_VISIBLE_VALUE_MIN
|
||||
max: RSSI_VISIBLE_VALUE_MAX
|
||||
- name: sbus_sync_interval
|
||||
field: sbusSyncInterval
|
||||
min: 500
|
||||
max: 10000
|
||||
- name: rc_smoothing
|
||||
field: rcSmoothing
|
||||
type: bool
|
||||
|
@ -545,6 +551,10 @@ groups:
|
|||
- name: rth_energy_margin
|
||||
min: 0
|
||||
max: 100
|
||||
- name: thr_comp_weight
|
||||
field: throttle_compensation_weight
|
||||
min: 0
|
||||
max: 2
|
||||
|
||||
- name: PG_BATTERY_PROFILES
|
||||
type: batteryProfile_t
|
||||
|
@ -815,8 +825,8 @@ groups:
|
|||
max: 250
|
||||
- name: 3d_deadband_throttle
|
||||
field: deadband3d_throttle
|
||||
min: PWM_RANGE_MIN
|
||||
max: PWM_RANGE_MAX
|
||||
min: 0
|
||||
max: 200
|
||||
|
||||
- name: PG_PID_PROFILE
|
||||
type: pidProfile_t
|
||||
|
@ -1082,7 +1092,7 @@ groups:
|
|||
|
||||
- name: PG_PID_AUTOTUNE_CONFIG
|
||||
type: pidAutotuneConfig_t
|
||||
condition: USE_NAV
|
||||
condition: USE_NAV && USE_AUTOTUNE_FIXED_WING
|
||||
members:
|
||||
- name: fw_autotune_overshoot_time
|
||||
field: fw_overshoot_time
|
||||
|
@ -1102,7 +1112,7 @@ groups:
|
|||
max: 100
|
||||
- name: fw_autotune_ff_to_i_tc
|
||||
field: fw_ff_to_i_time_constant
|
||||
min: 1000
|
||||
min: 100
|
||||
max: 5000
|
||||
|
||||
- name: PG_POSITION_ESTIMATION_CONFIG
|
||||
|
@ -1254,6 +1264,9 @@ groups:
|
|||
field: general.min_rth_distance
|
||||
min: 0
|
||||
max: 5000
|
||||
- name: nav_overrides_motor_stop
|
||||
field: general.flags.auto_overrides_motor_stop
|
||||
type: bool
|
||||
- name: nav_rth_climb_first
|
||||
field: general.flags.rth_climb_first
|
||||
type: bool
|
||||
|
@ -1452,6 +1465,8 @@ groups:
|
|||
- name: frsky_vfas_precision
|
||||
min: FRSKY_VFAS_PRECISION_LOW
|
||||
max: FRSKY_VFAS_PRECISION_HIGH
|
||||
- name: frsky_pitch_roll
|
||||
type: bool
|
||||
- name: report_cell_voltage
|
||||
type: bool
|
||||
- name: hott_alarm_sound_interval
|
||||
|
@ -1580,12 +1595,13 @@ groups:
|
|||
field: main_voltage_decimals
|
||||
min: 1
|
||||
max: 2
|
||||
- name: osd_attitude_angle_decimals
|
||||
field: attitude_angle_decimals
|
||||
min: 0
|
||||
max: 1
|
||||
- name: osd_coordinate_digits
|
||||
field: coordinate_digits
|
||||
min: 8
|
||||
max: 11
|
||||
|
||||
- name: osd_estimations_wind_compensation
|
||||
condition: USE_WIND_ESTIMATOR
|
||||
field: estimations_wind_compensation
|
||||
type: bool
|
||||
|
||||
|
@ -1681,6 +1697,7 @@ groups:
|
|||
- name: PG_VTX_SETTINGS_CONFIG
|
||||
type: vtxSettingsConfig_t
|
||||
headers: ["drivers/vtx_common.h", "io/vtx.h"]
|
||||
condition: defined(VTX_COMMON) || (defined(USE_CMS) && defined(USE_VTX_SMARTAUDIO))
|
||||
members:
|
||||
- name: vtx_band
|
||||
field: band
|
||||
|
|
|
@ -57,7 +57,7 @@ void statsOnDisarm(void)
|
|||
statsConfigMutable()->stats_total_time += dt; //[s]
|
||||
statsConfigMutable()->stats_total_dist += (getTotalTravelDistance() - arm_distance_cm) / 100; //[m]
|
||||
#ifdef USE_ADC
|
||||
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) {
|
||||
if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
|
||||
const uint32_t energy = getMWhDrawn() - arm_mWhDrawn;
|
||||
statsConfigMutable()->stats_total_energy += energy;
|
||||
flyingEnergy += energy;
|
||||
|
|
|
@ -71,7 +71,7 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
|
|||
.failsafe_recovery_delay = 5, // 0.5 seconds (plus 200ms explicit delay)
|
||||
.failsafe_off_delay = 200, // 20sec
|
||||
.failsafe_throttle = 1000, // default throttle off.
|
||||
.failsafe_throttle_low_delay = 100, // default throttle low delay for "just disarm" on failsafe condition
|
||||
.failsafe_throttle_low_delay = 0, // default throttle low delay for "just disarm" on failsafe condition
|
||||
.failsafe_procedure = FAILSAFE_PROCEDURE_AUTO_LANDING, // default full failsafe procedure
|
||||
.failsafe_fw_roll_angle = -200, // 20 deg left
|
||||
.failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive)
|
||||
|
|
|
@ -312,7 +312,7 @@ void mixTable(const float dT)
|
|||
|
||||
// Throttle compensation based on battery voltage
|
||||
if (feature(FEATURE_THR_VBAT_COMP) && feature(FEATURE_VBAT) && isAmperageConfigured())
|
||||
throttleCommand = MIN(throttleCommand * calculateThrottleCompensationFactor(), throttleMax);
|
||||
throttleCommand = MIN(throttleMin + (throttleCommand - throttleMin) * calculateThrottleCompensationFactor(), throttleMax);
|
||||
}
|
||||
|
||||
throttleRange = throttleMax - throttleMin;
|
||||
|
@ -371,11 +371,15 @@ void mixTable(const float dT)
|
|||
|
||||
motorStatus_e getMotorStatus(void)
|
||||
{
|
||||
if (failsafeRequiresMotorStop() || (!failsafeIsActive() && STATE(NAV_MOTOR_STOP_OR_IDLE)))
|
||||
if (failsafeRequiresMotorStop() || (!failsafeIsActive() && STATE(NAV_MOTOR_STOP_OR_IDLE))) {
|
||||
return MOTOR_STOPPED_AUTO;
|
||||
}
|
||||
|
||||
if ((STATE(FIXED_WING) || !isAirmodeActive()) && (!navigationIsFlyingAutonomousMode()) && (!failsafeIsActive()) && (rcData[THROTTLE] < rxConfig()->mincheck))
|
||||
if (rcData[THROTTLE] < rxConfig()->mincheck) {
|
||||
if ((STATE(FIXED_WING) || !isAirmodeActive()) && (!(navigationIsFlyingAutonomousMode() && navConfig()->general.flags.auto_overrides_motor_stop)) && (!failsafeIsActive())) {
|
||||
return MOTOR_STOPPED_USER;
|
||||
}
|
||||
}
|
||||
|
||||
return MOTOR_RUNNING;
|
||||
}
|
||||
|
|
|
@ -137,8 +137,8 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
.D = 0, // not used
|
||||
},
|
||||
[PID_VEL_Z] = {
|
||||
.P = 100, // NAV_VEL_Z_P * 100
|
||||
.I = 50, // NAV_VEL_Z_I * 100
|
||||
.P = 100, // NAV_VEL_Z_P * 66.7
|
||||
.I = 50, // NAV_VEL_Z_I * 20
|
||||
.D = 10, // NAV_VEL_Z_D * 100
|
||||
}
|
||||
}
|
||||
|
@ -156,14 +156,14 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
},
|
||||
[PID_HEADING] = { 60, 0, 0 },
|
||||
[PID_POS_Z] = {
|
||||
.P = 50, // FW_POS_Z_P * 100
|
||||
.I = 0, // not used
|
||||
.D = 0, // not used
|
||||
.P = 40, // FW_POS_Z_P * 10
|
||||
.I = 5, // FW_POS_Z_I * 10
|
||||
.D = 10, // FW_POS_Z_D * 10
|
||||
},
|
||||
[PID_POS_XY] = {
|
||||
.P = 75, // FW_NAV_P * 100
|
||||
.I = 5, // FW_NAV_I * 100
|
||||
.D = 8, // FW_NAV_D * 100
|
||||
.P = 75, // FW_POS_XY_P * 100
|
||||
.I = 5, // FW_POS_XY_I * 100
|
||||
.D = 8, // FW_POS_XY_D * 100
|
||||
}
|
||||
}
|
||||
},
|
||||
|
@ -483,7 +483,7 @@ static void pidApplyFixedWingRateController(pidState_t *pidState, flight_dynamic
|
|||
pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit);
|
||||
}
|
||||
|
||||
#ifdef AUTOTUNE_FIXED_WING
|
||||
#ifdef USE_AUTOTUNE_FIXED_WING
|
||||
if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) {
|
||||
autotuneFixedWingUpdate(axis, pidState->rateTarget, pidState->gyroRate, newPTerm + newFFTerm);
|
||||
}
|
||||
|
|
|
@ -79,7 +79,7 @@ typedef struct {
|
|||
|
||||
#define AUTOTUNE_SAVE_PERIOD 5000 // Save interval is 5 seconds - when we turn off autotune we'll restore values from previous update at most 5 sec ago
|
||||
|
||||
#if defined(AUTOTUNE_FIXED_WING) || defined(AUTOTUNE_MULTIROTOR)
|
||||
#if defined(USE_AUTOTUNE_FIXED_WING) || defined(USE_AUTOTUNE_MULTIROTOR)
|
||||
|
||||
static pidAutotuneData_t tuneCurrent[XYZ_AXIS_COUNT];
|
||||
static pidAutotuneData_t tuneSaved[XYZ_AXIS_COUNT];
|
||||
|
@ -159,7 +159,7 @@ static void blackboxLogAutotuneEvent(adjustmentFunction_e adjustmentFunction, in
|
|||
#endif
|
||||
}
|
||||
|
||||
#if defined(AUTOTUNE_FIXED_WING)
|
||||
#if defined(USE_AUTOTUNE_FIXED_WING)
|
||||
|
||||
void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRateDps, float reachedRateDps, float pidOutput)
|
||||
{
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
#include "build/debug.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_core.h"
|
||||
|
@ -114,11 +115,12 @@ static uint16_t estimateRTHAltitudeChangeEnergy(float altitudeChange, float vert
|
|||
// *heading is in degrees
|
||||
static float estimateRTHDistanceAndHeadingAfterAltitudeChange(float altitudeChange, float horizontalWindSpeed, float windHeading, float verticalWindSpeed, float *heading) {
|
||||
float estimatedAltitudeChangeGroundDistance = estimateRTHAltitudeChangeGroundDistance(altitudeChange, horizontalWindSpeed, windHeading, verticalWindSpeed);
|
||||
if (altitudeChange > 0) {
|
||||
if (navConfig()->general.flags.rth_climb_first && (altitudeChange > 0)) {
|
||||
float headingDiff = DEGREES_TO_RADIANS(DECIDEGREES_TO_DEGREES((float)attitude.values.yaw) - GPS_directionToHome);
|
||||
float triangleAltitude = GPS_distanceToHome * sin_approx(headingDiff);
|
||||
float triangleAltitudeToReturnStart = estimatedAltitudeChangeGroundDistance - GPS_distanceToHome * cos_approx(headingDiff);
|
||||
*heading = RADIANS_TO_DEGREES(atan2_approx(triangleAltitude, triangleAltitudeToReturnStart));
|
||||
const float reverseHeadingDiff = RADIANS_TO_DEGREES(atan2_approx(triangleAltitude, triangleAltitudeToReturnStart));
|
||||
*heading = CENTIDEGREES_TO_DEGREES(wrap_36000(DEGREES_TO_CENTIDEGREES(180 + reverseHeadingDiff + DECIDEGREES_TO_DEGREES((float)attitude.values.yaw))));
|
||||
return sqrt(sq(triangleAltitude) + sq(triangleAltitudeToReturnStart));
|
||||
} else {
|
||||
*heading = GPS_directionToHome;
|
||||
|
@ -132,13 +134,24 @@ static int32_t calculateRemainingEnergyBeforeRTH(bool takeWindIntoAccount) {
|
|||
if (!STATE(FIXED_WING))
|
||||
return -1;
|
||||
|
||||
if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER) && navigationPositionEstimateIsHealthy() && (batteryMetersConfig()->cruise_power > 0) && (ARMING_FLAG(ARMED)) && ((!STATE(FIXED_WING)) || (isNavLaunchEnabled() && isFixedWingLaunchDetected())) && (navConfig()->fw.cruise_speed > 0) && (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH) && (currentBatteryProfile->capacity.value > 0) && batteryWasFullWhenPluggedIn() && isEstimatedWindSpeedValid() && isImuHeadingValid()))
|
||||
if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER) && navigationPositionEstimateIsHealthy() && (batteryMetersConfig()->cruise_power > 0) && (ARMING_FLAG(ARMED)) && ((!STATE(FIXED_WING)) || (isNavLaunchEnabled() && isFixedWingLaunchDetected())) && (navConfig()->fw.cruise_speed > 0) && (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH) && (currentBatteryProfile->capacity.value > 0) && batteryWasFullWhenPluggedIn() && isImuHeadingValid()
|
||||
#ifdef USE_WIND_ESTIMATOR
|
||||
&& isEstimatedWindSpeedValid()
|
||||
#endif
|
||||
))
|
||||
return -1;
|
||||
|
||||
#ifdef USE_WIND_ESTIMATOR
|
||||
uint16_t windHeading; // centidegrees
|
||||
const float horizontalWindSpeed = takeWindIntoAccount ? getEstimatedHorizontalWindSpeed(&windHeading) / 100 : 0; // m/s
|
||||
const float windHeadingDegrees = CENTIDEGREES_TO_DEGREES((float)windHeading);
|
||||
const float verticalWindSpeed = getEstimatedWindSpeed(Z) / 100;
|
||||
#else
|
||||
UNUSED(takeWindIntoAccount);
|
||||
const float horizontalWindSpeed = 0; // m/s
|
||||
const float windHeadingDegrees = 0;
|
||||
const float verticalWindSpeed = 0;
|
||||
#endif
|
||||
|
||||
const float RTH_altitude_change = (RTHAltitude() - getEstimatedActualPosition(Z)) / 100;
|
||||
float RTH_heading; // degrees
|
||||
|
|
|
@ -177,6 +177,7 @@ static void filterServos(void)
|
|||
if (!servoFilterIsSet) {
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
biquadFilterInitLPF(&servoFilter[i], servoConfig()->servo_lowpass_freq, gyro.targetLooptime);
|
||||
biquadFilterReset(&servoFilter[i], servo[i]);
|
||||
}
|
||||
servoFilterIsSet = true;
|
||||
}
|
||||
|
|
|
@ -21,7 +21,6 @@
|
|||
#if !defined(USE_GPS)
|
||||
#error Wind Estimator requires GPS support
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/time.h"
|
||||
|
@ -34,3 +33,5 @@ float getEstimatedWindSpeed(int axis);
|
|||
float getEstimatedHorizontalWindSpeed(uint16_t *angle);
|
||||
|
||||
void updateWindEstimator(timeUs_t currentTimeUs);
|
||||
|
||||
#endif
|
||||
|
|
|
@ -2605,7 +2605,7 @@ static void afatfs_createFileContinue(afatfsFile_t *file)
|
|||
|
||||
memcpy(entry->filename, opState->filename, FAT_FILENAME_LENGTH);
|
||||
entry->attrib = file->attrib;
|
||||
if (rtcGetDateTime(&now)) {
|
||||
if (rtcGetDateTimeLocal(&now)) {
|
||||
entry->creationDate = FAT_MAKE_DATE(now.year, now.month, now.day);
|
||||
entry->creationTime = FAT_MAKE_TIME(now.hours, now.minutes, now.seconds);
|
||||
} else {
|
||||
|
|
|
@ -62,14 +62,15 @@
|
|||
#include "io/osd.h"
|
||||
#include "io/vtx_string.h"
|
||||
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/config.h"
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/fc_tasks.h"
|
||||
#include "fc/rc_adjustments.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_modes.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/fc_tasks.h"
|
||||
#include "fc/settings.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
|
@ -479,36 +480,34 @@ static inline void osdFormatFlyTime(char *buff, textAttributes_t *attr)
|
|||
*/
|
||||
static uint16_t osdConvertRSSI(void)
|
||||
{
|
||||
uint16_t osdRssi = getRSSI() * 100 / 1024; // change range
|
||||
if (osdRssi >= 100) {
|
||||
osdRssi = 99;
|
||||
}
|
||||
return osdRssi;
|
||||
// change range to [0, 99]
|
||||
return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99);
|
||||
}
|
||||
|
||||
static void osdFormatCoordinate(char *buff, char sym, int32_t val)
|
||||
{
|
||||
const int coordinateMaxLength = 12; // 11 for the number + 1 for the symbol
|
||||
// up to 4 for number + 1 for the symbol + null terminator + fill the rest with decimals
|
||||
const int coordinateLength = osdConfig()->coordinate_digits + 1;
|
||||
|
||||
buff[0] = sym;
|
||||
int32_t integerPart = val / GPS_DEGREES_DIVIDER;
|
||||
int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
|
||||
// Latitude maximum integer width is 3 (-90) while
|
||||
// longitude maximum integer width is 4 (-180). We always
|
||||
// show 7 decimals, so we need to use 11 spaces because
|
||||
// we're embedding the decimal separator between the
|
||||
// two numbers.
|
||||
int written = tfp_sprintf(buff + 1, "%d", integerPart);
|
||||
tfp_sprintf(buff + 1 + written, "%07d", decimalPart);
|
||||
// longitude maximum integer width is 4 (-180).
|
||||
int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", integerPart);
|
||||
// We can show up to 7 digits in decimalPart.
|
||||
int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
|
||||
STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits);
|
||||
int decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", decimalPart);
|
||||
// Embbed the decimal separator
|
||||
buff[1+written-1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
|
||||
buff[1+written] += SYM_ZERO_HALF_LEADING_DOT - '0';
|
||||
// Pad to 11 coordinateMaxLength
|
||||
while(1 + 7 + written < coordinateMaxLength) {
|
||||
buff[1 + 7 + written] = SYM_BLANK;
|
||||
written++;
|
||||
buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
|
||||
buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0';
|
||||
// Fill up to coordinateLength with zeros
|
||||
int total = 1 + integerDigits + decimalDigits;
|
||||
while(total < coordinateLength) {
|
||||
buff[total] = '0';
|
||||
total++;
|
||||
}
|
||||
buff[coordinateMaxLength] = '\0';
|
||||
buff[coordinateLength] = '\0';
|
||||
}
|
||||
|
||||
// Used twice, make sure it's exactly the same string
|
||||
|
@ -588,6 +587,8 @@ static const char * osdArmingDisabledReasonMessage(void)
|
|||
return OSD_MESSAGE_STR("AUTOTRIM IS ACTIVE");
|
||||
case ARMING_DISABLED_OOM:
|
||||
return OSD_MESSAGE_STR("NOT ENOUGH MEMORY");
|
||||
case ARMING_DISABLED_INVALID_SETTING:
|
||||
return OSD_MESSAGE_STR("INVALID SETTING");
|
||||
case ARMING_DISABLED_CLI:
|
||||
return OSD_MESSAGE_STR("CLI IS ACTIVE");
|
||||
// Cases without message
|
||||
|
@ -681,7 +682,10 @@ static const char * navigationStateMessage(void)
|
|||
// Not used
|
||||
break;
|
||||
case MW_NAV_STATE_LAND_START:
|
||||
return OSD_MESSAGE_STR("STARTING EMERGENCY LANDING");
|
||||
// Not used
|
||||
break;
|
||||
case MW_NAV_STATE_EMERGENCY_LANDING:
|
||||
return OSD_MESSAGE_STR("EMERGENCY LANDING");
|
||||
case MW_NAV_STATE_LAND_IN_PROGRESS:
|
||||
return OSD_MESSAGE_STR("LANDING");
|
||||
case MW_NAV_STATE_HOVER_ABOVE_HOME:
|
||||
|
@ -918,7 +922,7 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
|
|||
char symUnscaled;
|
||||
char symScaled;
|
||||
int maxDecimals;
|
||||
const int scaleMultiplier = 2;
|
||||
const unsigned scaleMultiplier = 2;
|
||||
// We try to reduce the scale when the POI will be around half the distance
|
||||
// between the center and the closers map edge, to avoid too much jumping
|
||||
const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2;
|
||||
|
@ -961,19 +965,22 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
|
|||
float poiCos = cos_approx(poiAngle);
|
||||
|
||||
// Now start looking for a valid scale that lets us draw everything
|
||||
for (int ii = 0; ii < 50; ii++, scale *= scaleMultiplier) {
|
||||
int ii;
|
||||
for (ii = 0; ii < 50; ii++) {
|
||||
// Calculate location of the aircraft in map
|
||||
int points = poiDistance / (float)(scale / charHeight);
|
||||
int points = poiDistance / ((float)scale / charHeight);
|
||||
|
||||
float pointsX = points * poiSin;
|
||||
int poiX = midX - roundf(pointsX / charWidth);
|
||||
if (poiX < minX || poiX > maxX) {
|
||||
scale *= scaleMultiplier;
|
||||
continue;
|
||||
}
|
||||
|
||||
float pointsY = points * poiCos;
|
||||
int poiY = midY + roundf(pointsY / charHeight);
|
||||
if (poiY < minY || poiY > maxY) {
|
||||
scale *= scaleMultiplier;
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -987,9 +994,21 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
|
|||
} else {
|
||||
|
||||
uint8_t c;
|
||||
if (displayReadCharWithAttr(osdDisplayPort, poiY, poiY, &c, NULL) && c != SYM_BLANK) {
|
||||
if (displayReadCharWithAttr(osdDisplayPort, poiX, poiY, &c, NULL) && c != SYM_BLANK) {
|
||||
// Something else written here, increase scale. If the display doesn't support reading
|
||||
// back characters, we assume there's nothing.
|
||||
//
|
||||
// If we're close to the center, decrease scale. Otherwise increase it.
|
||||
uint8_t centerDeltaX = (maxX - minX) / (scaleMultiplier * 2);
|
||||
uint8_t centerDeltaY = (maxY - minY) / (scaleMultiplier * 2);
|
||||
if (poiX >= midX - centerDeltaX && poiX <= midX + centerDeltaX &&
|
||||
poiY >= midY - centerDeltaY && poiY <= midY + centerDeltaY &&
|
||||
scale > scaleMultiplier) {
|
||||
|
||||
scale /= scaleMultiplier;
|
||||
} else {
|
||||
scale *= scaleMultiplier;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
@ -1036,17 +1055,17 @@ static void osdDrawRadar(uint16_t *drawn, uint32_t *usedScale)
|
|||
|
||||
#endif
|
||||
|
||||
void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController) {
|
||||
static void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController, uint8_t scale, bool showDecimal) {
|
||||
strcpy(buff, label);
|
||||
uint8_t label_len = strlen(label);
|
||||
for (uint8_t i = label_len; i < 5; ++i) buff[i] = ' ';
|
||||
osdFormatCentiNumber(buff + 5, pidController->proportional, 0, 1, 0, 4);
|
||||
for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' ';
|
||||
uint8_t decimals = showDecimal ? 1 : 0;
|
||||
osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4);
|
||||
buff[9] = ' ';
|
||||
osdFormatCentiNumber(buff + 10, pidController->integrator, 0, 1, 0, 4);
|
||||
osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4);
|
||||
buff[14] = ' ';
|
||||
osdFormatCentiNumber(buff + 15, pidController->derivative, 0, 1, 0, 4);
|
||||
osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4);
|
||||
buff[19] = ' ';
|
||||
osdFormatCentiNumber(buff + 20, pidController->output_constrained, 0, 1, 0, 4);
|
||||
osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4);
|
||||
buff[24] = '\0';
|
||||
}
|
||||
|
||||
|
@ -1210,6 +1229,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_HOME_DIR:
|
||||
{
|
||||
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) {
|
||||
// There are 16 orientations for the home direction arrow.
|
||||
// so we use 22.5deg per image, where the 1st image is used
|
||||
// for [349, 11], the 2nd for [12, 33], etc...
|
||||
|
@ -1218,6 +1238,14 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
int homeArrowDir = osdGetHeadingAngle(homeDirection + 11);
|
||||
unsigned arrowOffset = homeArrowDir * 2 / 45;
|
||||
buff[0] = SYM_ARROW_UP + arrowOffset;
|
||||
} else {
|
||||
// No home or no fix or unknown heading, blink.
|
||||
// If we're unarmed, show the arrow pointing up so users can see the arrow
|
||||
// while configuring the OSD. If we're armed, show a '-' indicating that
|
||||
// we don't know the direction to home.
|
||||
buff[0] = ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP;
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
}
|
||||
buff[1] = 0;
|
||||
break;
|
||||
}
|
||||
|
@ -1552,19 +1580,19 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_ATTITUDE_ROLL:
|
||||
buff[0] = SYM_ROLL_LEVEL;
|
||||
if (ABS(attitude.values.roll) >= (osdConfig()->attitude_angle_decimals ? 1 : 10))
|
||||
if (ABS(attitude.values.roll) >= 1)
|
||||
buff[0] += (attitude.values.roll < 0 ? -1 : 1);
|
||||
osdFormatCentiNumber(buff + 1, ABS(attitude.values.roll) * 10, 0, osdConfig()->attitude_angle_decimals, 0, 2 + osdConfig()->attitude_angle_decimals);
|
||||
osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3);
|
||||
break;
|
||||
|
||||
case OSD_ATTITUDE_PITCH:
|
||||
if (ABS(attitude.values.pitch) < (osdConfig()->attitude_angle_decimals ? 1 : 10))
|
||||
if (ABS(attitude.values.pitch) < 1)
|
||||
buff[0] = 'P';
|
||||
else if (attitude.values.pitch > 0)
|
||||
buff[0] = SYM_PITCH_DOWN;
|
||||
else if (attitude.values.pitch < 0)
|
||||
buff[0] = SYM_PITCH_UP;
|
||||
osdFormatCentiNumber(buff + 1, ABS(attitude.values.pitch) * 10, 0, osdConfig()->attitude_angle_decimals, 0, 2 + osdConfig()->attitude_angle_decimals);
|
||||
osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3);
|
||||
break;
|
||||
|
||||
case OSD_ARTIFICIAL_HORIZON:
|
||||
|
@ -1601,7 +1629,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
osdCrosshairsBounds(&cx, &cy, &cl);
|
||||
crosshairsX = cx - elemPosX;
|
||||
crosshairsY = cy - elemPosY;
|
||||
crosshairsXEnd = crosshairsX + cl;
|
||||
crosshairsXEnd = crosshairsX + cl - 1;
|
||||
}
|
||||
|
||||
for (int x = -4; x <= 4; x++) {
|
||||
|
@ -1618,25 +1646,32 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
int wx = x + 4; // map the -4 to the 1st element in the writtenY array
|
||||
int pwy = writtenY[wx]; // previously written Y at this X value
|
||||
int wy = (y / AH_SYMBOL_COUNT);
|
||||
// Check if we're overlapping with the crosshairs. Saves a few
|
||||
// trips to the video driver.
|
||||
|
||||
unsigned chX = elemPosX + x;
|
||||
unsigned chY = elemPosY + wy;
|
||||
uint8_t c;
|
||||
|
||||
// Check if we're overlapping with the crosshairs directly. Saves a few
|
||||
// trips to the video driver. Also, test for other arbitrary overlapping
|
||||
// elements if the display supports reading back characters.
|
||||
bool overlaps = (crosshairsVisible &&
|
||||
crosshairsY == wy &&
|
||||
x >= crosshairsX && x <= crosshairsXEnd);
|
||||
x >= crosshairsX && x <= crosshairsXEnd) ||
|
||||
(pwy != wy && displayReadCharWithAttr(osdDisplayPort, chX, chY, &c, NULL) && c != SYM_BLANK);
|
||||
|
||||
if (y >= 0 && y <= 80 && !overlaps) {
|
||||
if (pwy != -1 && pwy != wy) {
|
||||
// Erase previous character at pwy rows below elemPosY
|
||||
// iff we're writing at a different Y coordinate. Otherwise
|
||||
// we just overwrite the previous one.
|
||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + pwy, SYM_BLANK);
|
||||
displayWriteChar(osdDisplayPort, chX, elemPosY + pwy, SYM_BLANK);
|
||||
}
|
||||
uint8_t ch = SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT);
|
||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + wy, ch);
|
||||
displayWriteChar(osdDisplayPort, chX, chY, ch);
|
||||
writtenY[wx] = wy;
|
||||
} else {
|
||||
if (pwy != -1) {
|
||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + pwy, SYM_BLANK);
|
||||
displayWriteChar(osdDisplayPort, chX, elemPosY + pwy, SYM_BLANK);
|
||||
writtenY[wx] = -1;
|
||||
}
|
||||
}
|
||||
|
@ -1888,35 +1923,35 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
case OSD_FW_ALT_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt);
|
||||
osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt, 10, true); // display requested pitch degrees
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_FW_POS_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav);
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees
|
||||
osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true);
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_MC_VEL_Z_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z]);
|
||||
osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z], 100, false); // display throttle adjustment µs
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_MC_VEL_X_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X]);
|
||||
osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X], 100, false); // display requested acceleration cm/s^2
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_MC_VEL_Y_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y]);
|
||||
osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y], 100, false); // display requested acceleration cm/s^2
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1924,11 +1959,12 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
strcpy(buff, "POSO ");
|
||||
osdFormatCentiNumber(buff + 5, nav_pids->pos[X].output_constrained, 0, 1, 0, 4);
|
||||
// display requested velocity cm/s
|
||||
tfp_sprintf(buff + 5, "%4d", lrintf(nav_pids->pos[X].output_constrained * 100));
|
||||
buff[9] = ' ';
|
||||
osdFormatCentiNumber(buff + 10, nav_pids->pos[Y].output_constrained, 0, 1, 0, 4);
|
||||
tfp_sprintf(buff + 10, "%4d", lrintf(nav_pids->pos[Y].output_constrained * 100));
|
||||
buff[14] = ' ';
|
||||
osdFormatCentiNumber(buff + 15, nav_pids->pos[Z].output_constrained, 0, 1, 0, 4);
|
||||
tfp_sprintf(buff + 15, "%4d", lrintf(nav_pids->pos[Z].output_constrained * 100));
|
||||
buff[19] = '\0';
|
||||
break;
|
||||
}
|
||||
|
@ -1955,9 +1991,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
{
|
||||
// RTC not configured will show 00:00
|
||||
dateTime_t dateTime;
|
||||
if (rtcGetDateTime(&dateTime)) {
|
||||
dateTimeUTCToLocal(&dateTime, &dateTime);
|
||||
}
|
||||
rtcGetDateTimeLocal(&dateTime);
|
||||
buff[0] = SYM_CLOCK;
|
||||
tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes);
|
||||
break;
|
||||
|
@ -1966,6 +2000,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
case OSD_MESSAGES:
|
||||
{
|
||||
const char *message = NULL;
|
||||
char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)];
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
// Aircraft is armed. We might have up to 4
|
||||
// messages to show.
|
||||
|
@ -2000,7 +2035,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
// will cause it to be missing from some frames.
|
||||
}
|
||||
} else {
|
||||
if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE)) {
|
||||
if (FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding()) {
|
||||
const char *navStateMessage = navigationStateMessage();
|
||||
if (navStateMessage) {
|
||||
messages[messageCount++] = navStateMessage;
|
||||
|
@ -2030,7 +2065,21 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
}
|
||||
}
|
||||
} else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) {
|
||||
unsigned invalidIndex;
|
||||
// Check if we're unable to arm for some reason
|
||||
if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) {
|
||||
if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) {
|
||||
const setting_t *setting = settingGet(invalidIndex);
|
||||
settingGetName(setting, messageBuf);
|
||||
for (int ii = 0; messageBuf[ii]; ii++) {
|
||||
messageBuf[ii] = sl_toupper(messageBuf[ii]);
|
||||
}
|
||||
message = messageBuf;
|
||||
} else {
|
||||
message = "INVALID SETTING";
|
||||
TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr);
|
||||
}
|
||||
} else {
|
||||
if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) {
|
||||
message = "UNABLE TO ARM";
|
||||
TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr);
|
||||
|
@ -2039,6 +2088,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
message = osdArmingDisabledReasonMessage();
|
||||
}
|
||||
}
|
||||
}
|
||||
osdFormatMessage(buff, sizeof(buff), message);
|
||||
break;
|
||||
}
|
||||
|
@ -2422,9 +2472,9 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
|
||||
osdConfig->units = OSD_UNIT_METRIC;
|
||||
osdConfig->main_voltage_decimals = 1;
|
||||
osdConfig->attitude_angle_decimals = 0;
|
||||
|
||||
osdConfig->estimations_wind_compensation = true;
|
||||
osdConfig->coordinate_digits = 9;
|
||||
}
|
||||
|
||||
static void osdSetNextRefreshIn(uint32_t timeMs) {
|
||||
|
@ -2652,13 +2702,21 @@ static void osdShowArmed(void)
|
|||
displayWrite(osdDisplayPort, 12, y, "ARMED");
|
||||
y += 2;
|
||||
|
||||
if (STATE(GPS_FIX)) {
|
||||
#if defined(USE_GPS)
|
||||
if (feature(FEATURE_GPS)) {
|
||||
if (STATE(GPS_FIX_HOME)) {
|
||||
osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat);
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf);
|
||||
osdFormatCoordinate(buf, SYM_LON, gpsSol.llh.lon);
|
||||
osdFormatCoordinate(buf, SYM_LON, GPS_home.lon);
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf);
|
||||
y += 3;
|
||||
} else {
|
||||
strcpy(buf, "!NO HOME POSITION!");
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf);
|
||||
y += 1;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (rtcGetDateTime(&dt)) {
|
||||
dateTimeFormatLocal(buf, &dt);
|
||||
|
@ -2671,7 +2729,11 @@ static void osdShowArmed(void)
|
|||
|
||||
static void osdRefresh(timeUs_t currentTimeUs)
|
||||
{
|
||||
#ifdef USE_CMS
|
||||
if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu)) {
|
||||
#else
|
||||
if (IS_RC_MODE_ACTIVE(BOXOSD)) {
|
||||
#endif
|
||||
displayClearScreen(osdDisplayPort);
|
||||
armState = ARMING_FLAG(ARMED);
|
||||
return;
|
||||
|
|
|
@ -163,7 +163,6 @@ typedef struct osdConfig_s {
|
|||
|
||||
// Preferences
|
||||
uint8_t main_voltage_decimals;
|
||||
uint8_t attitude_angle_decimals;
|
||||
uint8_t ahi_reverse_roll;
|
||||
uint8_t crosshairs_style; // from osd_crosshairs_style_e
|
||||
uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e
|
||||
|
@ -174,6 +173,7 @@ typedef struct osdConfig_s {
|
|||
uint8_t stats_energy_unit; // from osd_stats_energy_unit_e
|
||||
|
||||
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
|
||||
uint8_t coordinate_digits;
|
||||
} osdConfig_t;
|
||||
|
||||
PG_DECLARE(osdConfig_t, osdConfig);
|
||||
|
|
|
@ -100,7 +100,7 @@ static void rcdeviceCameraUpdateTime(void)
|
|||
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS) &&
|
||||
!hasSynchronizedTime && retries < 3) {
|
||||
|
||||
if (rtcGetDateTime(&dt)) {
|
||||
if (rtcGetDateTimeLocal(&dt)) {
|
||||
retries++;
|
||||
tfp_sprintf(buf, "%04d%02d%02dT%02d%02d%02d.0",
|
||||
dt.year, dt.month, dt.day,
|
||||
|
|
|
@ -200,7 +200,7 @@ static void saPrintSettings(void)
|
|||
|
||||
int saDacToPowerIndex(int dac)
|
||||
{
|
||||
for (int idx = 3 ; idx >= 0 ; idx--) {
|
||||
for (int idx = VTX_SMARTAUDIO_POWER_COUNT - 1 ; idx >= 0 ; idx--) {
|
||||
if (saPowerTable[idx].valueV1 <= dac) {
|
||||
return idx;
|
||||
}
|
||||
|
@ -447,6 +447,11 @@ static void saSendFrame(uint8_t *buf, int len)
|
|||
serialWrite(smartAudioSerialPort, buf[i]);
|
||||
}
|
||||
|
||||
// XXX: Workaround for early AKK SAudio-enabled VTX bug,
|
||||
// shouldn't cause any problems with VTX with properly
|
||||
// implemented SAudio.
|
||||
serialWrite(smartAudioSerialPort, 0x00);
|
||||
|
||||
sa_lastTransmissionMs = millis();
|
||||
saStat.pktsent++;
|
||||
}
|
||||
|
|
|
@ -60,7 +60,7 @@ static vtxDevice_t vtxTramp = {
|
|||
.vTable = &trampVTable,
|
||||
.capability.bandCount = VTX_TRAMP_BAND_COUNT,
|
||||
.capability.channelCount = VTX_TRAMP_CHANNEL_COUNT,
|
||||
.capability.powerCount = sizeof(trampPowerTable),
|
||||
.capability.powerCount = VTX_TRAMP_POWER_COUNT,
|
||||
.bandNames = (char **)vtx58BandNames,
|
||||
.channelNames = (char **)vtx58ChannelNames,
|
||||
.powerNames = (char **)trampPowerNames,
|
||||
|
@ -196,7 +196,7 @@ bool trampCommitChanges(void)
|
|||
// return false if index out of range
|
||||
static bool trampDevSetPowerByIndex(uint8_t index)
|
||||
{
|
||||
if (index > 0 && index <= sizeof(trampPowerTable)) {
|
||||
if (index > 0 && index <= VTX_TRAMP_POWER_COUNT) {
|
||||
trampSetRFPower(trampPowerTable[index - 1]);
|
||||
trampCommitChanges();
|
||||
return true;
|
||||
|
|
|
@ -22,3 +22,6 @@
|
|||
|
||||
#define MSP2_COMMON_MOTOR_MIXER 0x1005
|
||||
#define MSP2_COMMON_SET_MOTOR_MIXER 0x1006
|
||||
|
||||
#define MSP2_COMMON_SETTING_INFO 0x1007 //in/out message Returns info about a setting (PG, type, flags, min/max, etc..).
|
||||
#define MSP2_COMMON_PG_LIST 0x1008 //in/out message Returns a list of the PG ids used by the settings
|
|
@ -77,7 +77,7 @@ PG_DECLARE_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList);
|
|||
PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0);
|
||||
#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 = {
|
||||
|
@ -92,6 +92,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
|
|||
.rth_tail_first = 0,
|
||||
.disarm_on_landing = 0,
|
||||
.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS,
|
||||
.auto_overrides_motor_stop = 1,
|
||||
},
|
||||
|
||||
// General navigation parameters
|
||||
|
@ -170,7 +171,7 @@ int16_t navActualVelocity[3];
|
|||
int16_t navDesiredVelocity[3];
|
||||
int16_t navActualHeading;
|
||||
int16_t navDesiredHeading;
|
||||
int16_t navTargetPosition[3];
|
||||
int32_t navTargetPosition[3];
|
||||
int32_t navLatestActualPosition[3];
|
||||
int16_t navActualSurface;
|
||||
uint16_t navFlags;
|
||||
|
@ -508,7 +509,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
[NAV_STATE_RTH_HOVER_ABOVE_HOME] = {
|
||||
.persistentId = NAV_PERSISTENT_ID_RTH_HOVER_ABOVE_HOME,
|
||||
.onEntry = navOnEnteringState_NAV_STATE_RTH_HOVER_ABOVE_HOME,
|
||||
.timeoutMs = 500,
|
||||
.timeoutMs = 10,
|
||||
.stateFlags = NAV_CTL_ALT | NAV_CTL_POS | NAV_CTL_YAW | NAV_REQUIRE_ANGLE | NAV_REQUIRE_MAGHOLD | NAV_REQUIRE_THRTILT | NAV_AUTO_RTH | NAV_RC_POS | NAV_RC_YAW | NAV_RC_ALT,
|
||||
.mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE,
|
||||
.mwState = MW_NAV_STATE_HOVER_ABOVE_HOME,
|
||||
|
@ -711,7 +712,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
.timeoutMs = 0,
|
||||
.stateFlags = NAV_CTL_EMERG | NAV_REQUIRE_ANGLE,
|
||||
.mapToFlightModes = 0,
|
||||
.mwState = MW_NAV_STATE_LAND_START,
|
||||
.mwState = MW_NAV_STATE_EMERGENCY_LANDING,
|
||||
.mwError = MW_NAV_ERROR_LANDING,
|
||||
.onEvent = {
|
||||
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS,
|
||||
|
@ -727,7 +728,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
|
|||
.timeoutMs = 10,
|
||||
.stateFlags = NAV_CTL_EMERG | NAV_REQUIRE_ANGLE,
|
||||
.mapToFlightModes = 0,
|
||||
.mwState = MW_NAV_STATE_LAND_IN_PROGRESS,
|
||||
.mwState = MW_NAV_STATE_EMERGENCY_LANDING,
|
||||
.mwError = MW_NAV_ERROR_LANDING,
|
||||
.onEvent = {
|
||||
[NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS, // re-process the state
|
||||
|
@ -1192,20 +1193,16 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HOVER_PRIOR_TO_LAND
|
|||
// If position ok OR within valid timeout - continue
|
||||
if ((posControl.flags.estPosStatus >= EST_USABLE) || !checkForPositionSensorTimeout()) {
|
||||
|
||||
// set altitude to go to when landing is not allowed
|
||||
if (navConfig()->general.rth_home_altitude && !navigationRTHAllowsLanding()) {
|
||||
posControl.homeWaypointAbove.pos.z = navConfig()->general.rth_home_altitude;
|
||||
setDesiredPosition(&posControl.homeWaypointAbove.pos, 0, NAV_POS_UPDATE_Z);
|
||||
}
|
||||
|
||||
// Wait until target heading is reached (with 15 deg margin for error)
|
||||
if (STATE(FIXED_WING)) {
|
||||
resetLandingDetector();
|
||||
updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
|
||||
return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME;
|
||||
}
|
||||
else {
|
||||
if (ABS(wrap_18000(posControl.homeWaypointAbove.yaw - posControl.actualState.yaw)) < DEGREES_TO_CENTIDEGREES(15)) {
|
||||
resetLandingDetector();
|
||||
updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
|
||||
return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME;
|
||||
}
|
||||
else if (!validateRTHSanityChecker()) {
|
||||
|
@ -1230,6 +1227,18 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_RTH_HOVER_ABOVE_HOME(na
|
|||
if (!(validateRTHSanityChecker() || (posControl.flags.estPosStatus >= EST_USABLE) || !checkForPositionSensorTimeout()))
|
||||
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING;
|
||||
|
||||
if ((navConfig()->general.rth_home_altitude) && (posControl.desiredState.pos.z != navConfig()->general.rth_home_altitude)) {
|
||||
int8_t altitudeChangeDirection = navConfig()->general.rth_home_altitude > posControl.homeWaypointAbove.pos.z ? 1 : -1;
|
||||
float timeToReachHomeAltitude = altitudeChangeDirection * (navConfig()->general.rth_home_altitude - navGetCurrentActualPositionAndVelocity()->pos.z) / navConfig()->general.max_auto_climb_rate;
|
||||
if (timeToReachHomeAltitude < 1) {
|
||||
// we almost reached the target home altitude so set the desired altitude to the desired home altitude
|
||||
posControl.homeWaypointAbove.pos.z = navConfig()->general.rth_home_altitude;
|
||||
setDesiredPosition(&posControl.homeWaypointAbove.pos, 0, NAV_POS_UPDATE_Z);
|
||||
} else {
|
||||
updateClimbRateToAltitudeController(altitudeChangeDirection * navConfig()->general.max_auto_climb_rate, ROC_TO_ALT_NORMAL);
|
||||
}
|
||||
}
|
||||
|
||||
return NAV_FSM_EVENT_NONE;
|
||||
}
|
||||
|
||||
|
@ -1824,7 +1833,7 @@ void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, flo
|
|||
}
|
||||
|
||||
#if defined(NAV_BLACKBOX)
|
||||
navLatestActualPosition[Z] = constrain(navGetCurrentActualPositionAndVelocity()->pos.z, -32678, 32767);
|
||||
navLatestActualPosition[Z] = navGetCurrentActualPositionAndVelocity()->pos.z;
|
||||
navActualVelocity[Z] = constrain(navGetCurrentActualPositionAndVelocity()->vel.z, -32678, 32767);
|
||||
#endif
|
||||
}
|
||||
|
@ -2735,9 +2744,9 @@ void applyWaypointNavigationAndAltitudeHold(void)
|
|||
if (posControl.flags.isAdjustingAltitude) navFlags |= (1 << 7);
|
||||
if (posControl.flags.isAdjustingHeading) navFlags |= (1 << 8);
|
||||
|
||||
navTargetPosition[X] = constrain(lrintf(posControl.desiredState.pos.x), -32678, 32767);
|
||||
navTargetPosition[Y] = constrain(lrintf(posControl.desiredState.pos.y), -32678, 32767);
|
||||
navTargetPosition[Z] = constrain(lrintf(posControl.desiredState.pos.z), -32678, 32767);
|
||||
navTargetPosition[X] = lrintf(posControl.desiredState.pos.x);
|
||||
navTargetPosition[Y] = lrintf(posControl.desiredState.pos.y);
|
||||
navTargetPosition[Z] = lrintf(posControl.desiredState.pos.z);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -3061,9 +3070,9 @@ void navigationUsePIDs(void)
|
|||
(float)pidProfile()->bank_fw.pid[PID_POS_XY].I / 100.0f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_XY].D / 100.0f);
|
||||
|
||||
navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P / 9.80665f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].I / 9.80665f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 9.80665f);
|
||||
navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P / 10.0f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].I / 10.0f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 10.0f);
|
||||
}
|
||||
|
||||
void navigationInit(void)
|
||||
|
@ -3140,6 +3149,11 @@ rthState_e getStateOfForcedRTH(void)
|
|||
}
|
||||
}
|
||||
|
||||
bool navigationIsExecutingAnEmergencyLanding(void)
|
||||
{
|
||||
return navGetCurrentStateFlags() & NAV_CTL_EMERG;
|
||||
}
|
||||
|
||||
bool navigationIsControllingThrottle(void)
|
||||
{
|
||||
navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
|
||||
|
|
|
@ -126,6 +126,7 @@ typedef struct navConfig_s {
|
|||
uint8_t disarm_on_landing; //
|
||||
uint8_t rth_allow_landing; // Enable landing as last stage of RTH. Use constants in navRTHAllowLanding_e.
|
||||
uint8_t rth_climb_ignore_emerg; // Option to ignore GPS loss on initial climb stage of RTH
|
||||
uint8_t auto_overrides_motor_stop; // Autonomous modes override motor_stop setting and user command to stop motor
|
||||
} flags;
|
||||
|
||||
uint8_t pos_failure_timeout; // Time to wait before switching to emergency landing (0 - disable)
|
||||
|
@ -279,12 +280,13 @@ typedef enum {
|
|||
MW_NAV_STATE_WP_ENROUTE, // WP Enroute
|
||||
MW_NAV_STATE_PROCESS_NEXT, // Process next
|
||||
MW_NAV_STATE_DO_JUMP, // Jump
|
||||
MW_NAV_STATE_LAND_START, // Start Land
|
||||
MW_NAV_STATE_LAND_START, // Start Land (unused)
|
||||
MW_NAV_STATE_LAND_IN_PROGRESS, // Land in Progress
|
||||
MW_NAV_STATE_LANDED, // Landed
|
||||
MW_NAV_STATE_LAND_SETTLE, // Settling before land
|
||||
MW_NAV_STATE_LAND_START_DESCENT, // Start descent
|
||||
MW_NAV_STATE_HOVER_ABOVE_HOME // Hover/Loitering above home
|
||||
MW_NAV_STATE_HOVER_ABOVE_HOME, // Hover/Loitering above home
|
||||
MW_NAV_STATE_EMERGENCY_LANDING, // Emergency landing
|
||||
} navSystemStatus_State_e;
|
||||
|
||||
typedef enum {
|
||||
|
@ -391,6 +393,7 @@ rthState_e getStateOfForcedRTH(void);
|
|||
bool navigationIsControllingThrottle(void);
|
||||
bool isFixedWingAutoThrottleManuallyIncreased(void);
|
||||
bool navigationIsFlyingAutonomousMode(void);
|
||||
bool navigationIsExecutingAnEmergencyLanding(void);
|
||||
/* Returns true iff navConfig()->general.flags.rth_allow_landing is NAV_RTH_ALLOW_LANDING_ALWAYS
|
||||
* or if it's NAV_RTH_ALLOW_LANDING_FAILSAFE and failsafe mode is active.
|
||||
*/
|
||||
|
@ -420,7 +423,7 @@ extern navSystemStatus_t NAV_Status;
|
|||
extern int16_t navCurrentState;
|
||||
extern int16_t navActualVelocity[3];
|
||||
extern int16_t navDesiredVelocity[3];
|
||||
extern int16_t navTargetPosition[3];
|
||||
extern int32_t navTargetPosition[3];
|
||||
extern int32_t navLatestActualPosition[3];
|
||||
extern int16_t navActualSurface;
|
||||
extern uint16_t navFlags;
|
||||
|
|
|
@ -59,7 +59,7 @@ enum {
|
|||
CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE
|
||||
};
|
||||
|
||||
#define CRSF_PAYLOAD_SIZE_MAX 32 // !!TODO needs checking
|
||||
#define CRSF_PAYLOAD_SIZE_MAX 62
|
||||
#define CRSF_FRAME_SIZE_MAX (CRSF_PAYLOAD_SIZE_MAX + 4)
|
||||
|
||||
typedef struct crsfFrameDef_s {
|
||||
|
|
|
@ -325,7 +325,7 @@ static void telemetryRX(void)
|
|||
case 2:
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
uint16_t gpsspeed = (gpsSol.groundSpeed*9L)/250L;
|
||||
int16_t course = (gpsSol.groundCourse+360)%360;
|
||||
int16_t course = (gpsSol.groundCourse/10 + 360)%360;
|
||||
#ifdef USE_NAV
|
||||
int32_t alt = getEstimatedActualPosition(Z);
|
||||
#else
|
||||
|
|
|
@ -110,8 +110,14 @@ typedef struct fportFrame_s {
|
|||
|
||||
#if defined(USE_SERIALRX_FPORT)
|
||||
|
||||
#if defined(USE_TELEMETRY_SMARTPORT)
|
||||
|
||||
static bool telemetryEnabled = false;
|
||||
|
||||
static const smartPortPayload_t emptySmartPortFrame = { .frameId = 0, .valueId = 0, .data = 0 };
|
||||
|
||||
#endif // USE_TELEMETRY_SMARTPORT
|
||||
|
||||
#define FPORT_REQUEST_FRAME_LENGTH sizeof(fportFrame_t)
|
||||
#define FPORT_RESPONSE_FRAME_LENGTH (sizeof(uint8_t) + sizeof(smartPortPayload_t))
|
||||
|
||||
|
@ -140,7 +146,6 @@ static smartPortPayload_t *mspPayload = NULL;
|
|||
static timeUs_t lastRcFrameReceivedMs = 0;
|
||||
|
||||
static serialPort_t *fportPort;
|
||||
static bool telemetryEnabled = false;
|
||||
|
||||
static void reportFrameError(uint8_t errorReason) {
|
||||
static volatile uint16_t frameErrors = 0;
|
||||
|
@ -244,7 +249,9 @@ static bool checkChecksum(uint8_t *data, uint8_t length)
|
|||
|
||||
static uint8_t fportFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
#if defined(USE_TELEMETRY_SMARTPORT)
|
||||
static smartPortPayload_t payloadBuffer;
|
||||
#endif
|
||||
static bool hasTelemetryRequest = false;
|
||||
|
||||
uint8_t result = RX_FRAME_PENDING;
|
||||
|
@ -267,7 +274,7 @@ static uint8_t fportFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
|
|||
} else {
|
||||
result |= sbusChannelsDecode(rxRuntimeConfig, &frame->data.controlData.channels);
|
||||
|
||||
setRSSI(scaleRange(constrain(frame->data.controlData.rssi, 0, 100), 0, 100, 0, 1024), RSSI_SOURCE_RX_PROTOCOL, false);
|
||||
setRSSI(scaleRange(frame->data.controlData.rssi, 0, 100, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_PROTOCOL, false);
|
||||
|
||||
lastRcFrameReceivedMs = millis();
|
||||
}
|
||||
|
|
124
src/main/rx/rx.c
124
src/main/rx/rx.c
|
@ -84,13 +84,13 @@ static bool rxFlightChannelsValid = false;
|
|||
static bool rxIsInFailsafeMode = true;
|
||||
|
||||
static timeUs_t rxNextUpdateAtUs = 0;
|
||||
static uint32_t needRxSignalBefore = 0;
|
||||
static uint32_t suspendRxSignalUntil = 0;
|
||||
static timeUs_t needRxSignalBefore = 0;
|
||||
static timeUs_t suspendRxSignalUntil = 0;
|
||||
static uint8_t skipRxSamples = 0;
|
||||
|
||||
int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
timeMs_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
|
||||
#define MAX_INVALID_PULS_TIME 300
|
||||
|
||||
|
@ -100,7 +100,7 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
static uint8_t rcSampleIndex = 0;
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 4);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 6);
|
||||
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
|
@ -127,8 +127,9 @@ PG_RESET_TEMPLATE(rxConfig_t, rxConfig,
|
|||
.rx_min_usec = RX_MIN_USEX, // any of first 4 channels below this value will trigger rx loss detection
|
||||
.rx_max_usec = 2115, // any of first 4 channels above this value will trigger rx loss detection
|
||||
.rssi_channel = 0,
|
||||
.rssi_scale = RSSI_SCALE_DEFAULT,
|
||||
.rssiInvert = 0,
|
||||
.rssiMin = RSSI_VISIBLE_VALUE_MIN,
|
||||
.rssiMax = RSSI_VISIBLE_VALUE_MAX,
|
||||
.sbusSyncInterval = SBUS_DEFAULT_INTERFRAME_DELAY_US,
|
||||
.rcSmoothing = 1,
|
||||
);
|
||||
|
||||
|
@ -333,22 +334,40 @@ void rxUpdateRSSISource(void)
|
|||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_SERIAL_RX
|
||||
bool serialProtocolSupportsRSSI = false;
|
||||
if (rxConfig()->receiverType) {
|
||||
switch (rxConfig()->receiverType) {
|
||||
#if defined(USE_SERIAL_RX)
|
||||
case RX_TYPE_SERIAL:
|
||||
switch (rxConfig()->serialrx_provider) {
|
||||
#ifdef USE_SERIALRX_FPORT
|
||||
#if defined(USE_SERIALRX_FPORT)
|
||||
case SERIALRX_FPORT:
|
||||
serialProtocolSupportsRSSI = true;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#if defined(USE_RX_SPI)
|
||||
case RX_TYPE_SPI:
|
||||
switch (rxConfig()->rx_spi_protocol) {
|
||||
#if defined(USE_RX_ELERES)
|
||||
case RFM22_ELERES:
|
||||
serialProtocolSupportsRSSI = true;
|
||||
break;
|
||||
break;
|
||||
#endif
|
||||
default:
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
if (serialProtocolSupportsRSSI) {
|
||||
rssiSource = RSSI_SOURCE_RX_PROTOCOL;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
static uint8_t calculateChannelRemapping(const uint8_t *channelMap, uint8_t channelMapEntryCount, uint8_t channelToRemap)
|
||||
|
@ -393,25 +412,6 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(USE_PWM) || defined(USE_PPM)
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
if (isPPMDataBeingReceived()) {
|
||||
rxDataProcessingRequired = true;
|
||||
rxSignalReceived = true;
|
||||
rxIsInFailsafeMode = false;
|
||||
needRxSignalBefore = currentTimeUs + rxRuntimeConfig.rxSignalTimeout;
|
||||
resetPPMDataReceivedState();
|
||||
}
|
||||
} else if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
if (isPWMDataBeingReceived()) {
|
||||
rxDataProcessingRequired = true;
|
||||
rxSignalReceived = true;
|
||||
rxIsInFailsafeMode = false;
|
||||
needRxSignalBefore = currentTimeUs + rxRuntimeConfig.rxSignalTimeout;
|
||||
}
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
const uint8_t frameStatus = rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
|
||||
if (frameStatus & RX_FRAME_COMPLETE) {
|
||||
rxDataProcessingRequired = true;
|
||||
|
@ -423,7 +423,6 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
|
|||
if (frameStatus & RX_FRAME_PROCESSING_REQUIRED) {
|
||||
auxiliaryProcessingRequired = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (cmpTimeUs(currentTimeUs, rxNextUpdateAtUs) > 0) {
|
||||
rxDataProcessingRequired = true;
|
||||
|
@ -469,6 +468,7 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
|
|||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
int16_t rcStaging[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
|
||||
if (auxiliaryProcessingRequired) {
|
||||
|
@ -519,11 +519,21 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
|
|||
rcInvalidPulsPeriod[channel] = currentTimeMs + MAX_INVALID_PULS_TIME;
|
||||
}
|
||||
|
||||
// Update rcData channel value
|
||||
// Save channel value
|
||||
rcStaging[channel] = sample;
|
||||
}
|
||||
|
||||
// Update rcData channel value if receiver is not in failsafe mode
|
||||
// If receiver is in failsafe (not receiving signal or sending invalid channel values) - last good rcData values are retained
|
||||
if (rxFlightChannelsValid && rxSignalReceived) {
|
||||
if (rxRuntimeConfig.requireFiltering) {
|
||||
rcData[channel] = applyChannelFiltering(channel, sample);
|
||||
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
|
||||
rcData[channel] = applyChannelFiltering(channel, rcStaging[channel]);
|
||||
}
|
||||
} else {
|
||||
rcData[channel] = sample;
|
||||
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
|
||||
rcData[channel] = rcStaging[channel];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -548,7 +558,6 @@ void parseRcChannels(const char *input)
|
|||
}
|
||||
|
||||
#define RSSI_SAMPLE_COUNT 16
|
||||
#define RSSI_MAX_VALUE 1023
|
||||
|
||||
void setRSSI(uint16_t rssiValue, rssiSource_e source, bool filtered)
|
||||
{
|
||||
|
@ -574,6 +583,18 @@ void setRSSI(uint16_t rssiValue, rssiSource_e source, bool filtered)
|
|||
|
||||
rssi = rssiMean;
|
||||
}
|
||||
|
||||
// Apply min/max values
|
||||
int rssiMin = rxConfig()->rssiMin * RSSI_VISIBLE_FACTOR;
|
||||
int rssiMax = rxConfig()->rssiMax * RSSI_VISIBLE_FACTOR;
|
||||
if (rssiMin > rssiMax) {
|
||||
int tmp = rssiMax;
|
||||
rssiMax = rssiMin;
|
||||
rssiMin = tmp;
|
||||
int delta = rssi >= rssiMin ? rssi - rssiMin : 0;
|
||||
rssi = rssiMax >= delta ? rssiMax - delta : 0;
|
||||
}
|
||||
rssi = constrain(scaleRange(rssi, rssiMin, rssiMax, 0, RSSI_MAX_VALUE), 0, RSSI_MAX_VALUE);
|
||||
}
|
||||
|
||||
void setRSSIFromMSP(uint8_t newMspRssi)
|
||||
|
@ -589,52 +610,43 @@ void setRSSIFromMSP(uint8_t newMspRssi)
|
|||
}
|
||||
|
||||
#ifdef USE_RX_ELERES
|
||||
static bool updateRSSIeleres(uint32_t currentTime)
|
||||
static void updateRSSIeleres(uint32_t currentTime)
|
||||
{
|
||||
UNUSED(currentTime);
|
||||
rssi = eleresRssi();
|
||||
return true;
|
||||
setRSSI(eleresRssi(), RSSI_SOURCE_RX_PROTOCOL, true);
|
||||
}
|
||||
#endif // USE_RX_ELERES
|
||||
|
||||
static bool updateRSSIPWM(void)
|
||||
static void updateRSSIPWM(void)
|
||||
{
|
||||
int16_t pwmRssi = 0;
|
||||
// Read value of AUX channel as rssi
|
||||
if (rxConfig()->rssi_channel > 0) {
|
||||
pwmRssi = rcData[rxConfig()->rssi_channel - 1];
|
||||
pwmRssi = rcRaw[rxConfig()->rssi_channel - 1];
|
||||
|
||||
// Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023];
|
||||
uint16_t rawRSSI = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * (RSSI_MAX_VALUE * 1.0f));
|
||||
setRSSI(rawRSSI, RSSI_SOURCE_RX_CHANNEL, false);
|
||||
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool updateRSSIADC(void)
|
||||
static void updateRSSIADC(void)
|
||||
{
|
||||
#ifdef USE_ADC
|
||||
uint16_t rawRSSI = adcGetChannel(ADC_RSSI) / 4; // Reduce to [0;1023]
|
||||
setRSSI(rawRSSI, RSSI_SOURCE_ADC, false);
|
||||
return true;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
|
||||
void updateRSSI(timeUs_t currentTimeUs)
|
||||
{
|
||||
bool rssiUpdated = false;
|
||||
|
||||
// Read RSSI
|
||||
switch (rssiSource) {
|
||||
case RSSI_SOURCE_RX_CHANNEL:
|
||||
rssiUpdated = updateRSSIPWM();
|
||||
updateRSSIPWM();
|
||||
break;
|
||||
case RSSI_SOURCE_ADC:
|
||||
rssiUpdated = updateRSSIADC();
|
||||
updateRSSIADC();
|
||||
break;
|
||||
case RSSI_SOURCE_MSP:
|
||||
if (cmpTimeUs(currentTimeUs, lastMspRssiUpdateUs) > MSP_RSSI_TIMEOUT_US) {
|
||||
|
@ -644,21 +656,11 @@ void updateRSSI(timeUs_t currentTimeUs)
|
|||
default:
|
||||
#ifdef USE_RX_ELERES
|
||||
if (rxConfig()->receiverType == RX_TYPE_SPI && rxConfig()->rx_spi_protocol == RFM22_ELERES) {
|
||||
rssiUpdated = updateRSSIeleres(currentTimeUs);
|
||||
updateRSSIeleres(currentTimeUs);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
||||
if (rssiUpdated) {
|
||||
// Apply RSSI inversion
|
||||
if (rxConfig()->rssiInvert) {
|
||||
rssi = RSSI_MAX_VALUE - rssi;
|
||||
}
|
||||
|
||||
// Apply scaling
|
||||
rssi = constrain((uint32_t)rssi * rxConfig()->rssi_scale / 100, 0, RSSI_MAX_VALUE);
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t getRSSI(void)
|
||||
|
|
|
@ -47,6 +47,8 @@
|
|||
#define DELAY_10_HZ (1000000 / 10)
|
||||
#define DELAY_5_HZ (1000000 / 5)
|
||||
|
||||
#define RSSI_MAX_VALUE 1023
|
||||
|
||||
typedef enum {
|
||||
RX_FRAME_PENDING = 0, // No new data available from receiver
|
||||
RX_FRAME_COMPLETE = (1 << 0), // There is new data available
|
||||
|
@ -93,13 +95,14 @@ typedef enum {
|
|||
|
||||
extern const char rcChannelLetters[];
|
||||
|
||||
extern int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||
|
||||
#define MAX_MAPPABLE_RX_INPUTS 4
|
||||
|
||||
#define RSSI_SCALE_MIN 1
|
||||
#define RSSI_SCALE_MAX 255
|
||||
#define RSSI_SCALE_DEFAULT 100
|
||||
#define RSSI_VISIBLE_VALUE_MIN 0
|
||||
#define RSSI_VISIBLE_VALUE_MAX 100
|
||||
#define RSSI_VISIBLE_FACTOR (RSSI_MAX_VALUE/(float)RSSI_VISIBLE_VALUE_MAX)
|
||||
|
||||
typedef struct rxChannelRangeConfig_s {
|
||||
uint16_t min;
|
||||
|
@ -119,9 +122,9 @@ typedef struct rxConfig_s {
|
|||
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
||||
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
|
||||
uint8_t rssi_channel;
|
||||
uint8_t rssi_scale;
|
||||
uint8_t rssiInvert;
|
||||
uint16_t __reserved; // was micrd
|
||||
uint8_t rssiMin; // minimum RSSI sent by the RX - [RSSI_VISIBLE_VALUE_MIN, RSSI_VISIBLE_VALUE_MAX]
|
||||
uint8_t rssiMax; // maximum RSSI sent by the RX - [RSSI_VISIBLE_VALUE_MIN, RSSI_VISIBLE_VALUE_MAX]
|
||||
uint16_t sbusSyncInterval;
|
||||
uint16_t mincheck; // minimum rc end
|
||||
uint16_t maxcheck; // maximum rc end
|
||||
uint16_t rx_min_usec;
|
||||
|
@ -174,6 +177,7 @@ void parseRcChannels(const char *input);
|
|||
void setRSSI(uint16_t newRssi, rssiSource_e source, bool filtered);
|
||||
void setRSSIFromMSP(uint8_t newMspRssi);
|
||||
void updateRSSI(timeUs_t currentTimeUs);
|
||||
// Returns RSSI in [0, RSSI_MAX_VALUE] range.
|
||||
uint16_t getRSSI(void);
|
||||
rssiSource_e getRSSISource(void);
|
||||
|
||||
|
|
|
@ -52,8 +52,6 @@
|
|||
* time to send frame: 3ms.
|
||||
*/
|
||||
|
||||
#define SBUS_MIN_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case
|
||||
|
||||
#define SBUS_FRAME_SIZE (SBUS_CHANNEL_DATA_LENGTH + 2)
|
||||
|
||||
#define SBUS_FRAME_BEGIN_BYTE 0x0F
|
||||
|
@ -114,7 +112,7 @@ static void sbusDataReceive(uint16_t c, void *data)
|
|||
sbusFrameData->lastActivityTimeUs = currentTimeUs;
|
||||
|
||||
// Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire
|
||||
if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= SBUS_MIN_INTERFRAME_DELAY_US) {
|
||||
if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) {
|
||||
DEBUG_SET(DEBUG_SBUS, DEBUG_SBUS_INTERFRAME_TIME, timeSinceLastByteUs);
|
||||
sbusFrameData->state = STATE_SBUS_SYNC;
|
||||
}
|
||||
|
|
|
@ -17,4 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define SBUS_DEFAULT_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case
|
||||
|
||||
bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
|
|
@ -93,7 +93,7 @@ typedef enum {
|
|||
#ifdef USE_LED_STRIP
|
||||
TASK_LEDSTRIP,
|
||||
#endif
|
||||
#ifdef USE_PMW_SERVO_DRIVER
|
||||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
TASK_PWMDRIVER,
|
||||
#endif
|
||||
#ifdef STACK_CHECK
|
||||
|
|
|
@ -68,7 +68,7 @@
|
|||
|
||||
|
||||
// Battery monitoring stuff
|
||||
static uint8_t batteryCellCount = 3; // cell count
|
||||
static uint8_t batteryCellCount; // cell count
|
||||
static uint16_t batteryFullVoltage;
|
||||
static uint16_t batteryWarningVoltage;
|
||||
static uint16_t batteryCriticalVoltage;
|
||||
|
@ -78,8 +78,6 @@ static bool batteryFullWhenPluggedIn = false;
|
|||
static bool profileAutoswitchDisable = false;
|
||||
|
||||
static uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered)
|
||||
static uint16_t vbatLatestADC = 0; // most recent unsmoothed raw reading from vbat ADC
|
||||
static uint16_t amperageLatestADC = 0; // most recent raw reading from current ADC
|
||||
static uint16_t powerSupplyImpedance = 0; // calculated impedance in milliohm
|
||||
static uint16_t sagCompensatedVBat = 0; // calculated no load vbat
|
||||
static bool powerSupplyImpedanceIsValid = false;
|
||||
|
@ -133,23 +131,12 @@ PG_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig,
|
|||
|
||||
.cruise_power = 0,
|
||||
.idle_power = 0,
|
||||
.rth_energy_margin = 5
|
||||
.rth_energy_margin = 5,
|
||||
|
||||
.throttle_compensation_weight = 1.0f
|
||||
|
||||
);
|
||||
|
||||
uint16_t batteryAdcToVoltage(uint16_t src)
|
||||
{
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.01V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 1100 = 11:1 voltage divider (10k:1k)
|
||||
return((uint64_t)src * batteryMetersConfig()->voltage_scale * ADCVREF / (0xFFF * 1000));
|
||||
}
|
||||
|
||||
int16_t currentSensorToCentiamps(uint16_t src)
|
||||
{
|
||||
int32_t microvolts = ((uint32_t)src * ADCVREF * 100) / 0xFFF * 10 - (int32_t)batteryMetersConfig()->current.offset * 100;
|
||||
return microvolts / batteryMetersConfig()->current.scale; // current in 0.01A steps
|
||||
}
|
||||
|
||||
void batteryInit(void)
|
||||
{
|
||||
batteryState = BATTERY_NOT_PRESENT;
|
||||
|
@ -184,9 +171,8 @@ static int8_t profileDetect() {
|
|||
qsort(profile_comp_array, MAX_BATTERY_PROFILE_COUNT, sizeof(*profile_comp_array), (int (*)(const void *, const void *))profile_compare);
|
||||
|
||||
// Return index of the first profile where vbat <= profile_max_voltage
|
||||
uint16_t vbatLatest = batteryAdcToVoltage(vbatLatestADC);
|
||||
for (uint8_t i = 0; i < MAX_BATTERY_PROFILE_COUNT; ++i)
|
||||
if ((profile_comp_array[i].max_voltage > 0) && (vbatLatest <= profile_comp_array[i].max_voltage))
|
||||
if ((profile_comp_array[i].max_voltage > 0) && (vbat <= profile_comp_array[i].max_voltage))
|
||||
return profile_comp_array[i].profile_index;
|
||||
|
||||
// No matching profile found
|
||||
|
@ -203,27 +189,35 @@ void setBatteryProfile(uint8_t profileIndex)
|
|||
|
||||
void activateBatteryProfile(void)
|
||||
{
|
||||
static int8_t previous_battery_profile_index = -1;
|
||||
// Don't call batteryInit if the battery profile was not changed to prevent batteryCellCount to be reset while adjusting board alignment
|
||||
// causing the beeper to be silent when it is disabled while the board is connected through USB (beeper -ON_USB)
|
||||
if (systemConfig()->current_battery_profile_index != previous_battery_profile_index) {
|
||||
batteryInit();
|
||||
previous_battery_profile_index = systemConfig()->current_battery_profile_index;
|
||||
}
|
||||
}
|
||||
|
||||
static void updateBatteryVoltage(timeUs_t timeDelta)
|
||||
static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
|
||||
{
|
||||
uint16_t vbatSample;
|
||||
static pt1Filter_t vbatFilterState;
|
||||
|
||||
// store the battery voltage with some other recent battery voltage readings
|
||||
vbatSample = vbatLatestADC = adcGetChannel(ADC_BATTERY);
|
||||
vbatSample = pt1FilterApply4(&vbatFilterState, vbatSample, VBATT_LPF_FREQ, timeDelta * 1e-6f);
|
||||
vbat = batteryAdcToVoltage(vbatSample);
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.01V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 1100 = 11:1 voltage divider (10k:1k)
|
||||
vbat = (uint64_t)adcGetChannel(ADC_BATTERY) * batteryMetersConfig()->voltage_scale * ADCVREF / (0xFFF * 1000);
|
||||
|
||||
if (justConnected) {
|
||||
pt1FilterReset(&vbatFilterState, vbat);
|
||||
} else {
|
||||
vbat = pt1FilterApply4(&vbatFilterState, vbat, VBATT_LPF_FREQ, timeDelta * 1e-6f);
|
||||
}
|
||||
}
|
||||
|
||||
void batteryUpdate(timeUs_t timeDelta)
|
||||
{
|
||||
updateBatteryVoltage(timeDelta);
|
||||
|
||||
/* battery has just been connected*/
|
||||
if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD)
|
||||
{
|
||||
if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD) {
|
||||
|
||||
/* Actual battery state is calculated below, this is really BATTERY_PRESENT */
|
||||
batteryState = BATTERY_OK;
|
||||
/* wait for VBatt to stabilise then we can calc number of cells
|
||||
|
@ -231,7 +225,7 @@ void batteryUpdate(timeUs_t timeDelta)
|
|||
We only do this on the ground so don't care if we do block, not
|
||||
worse than original code anyway*/
|
||||
delay(VBATT_STABLE_DELAY);
|
||||
updateBatteryVoltage(timeDelta);
|
||||
updateBatteryVoltage(timeDelta, true);
|
||||
|
||||
int8_t detectedProfileIndex = -1;
|
||||
if (feature(FEATURE_BAT_PROFILE_AUTOSWITCH) && (!profileAutoswitchDisable))
|
||||
|
@ -244,7 +238,7 @@ void batteryUpdate(timeUs_t timeDelta)
|
|||
} else if (currentBatteryProfile->cells > 0)
|
||||
batteryCellCount = currentBatteryProfile->cells;
|
||||
else {
|
||||
batteryCellCount = (batteryAdcToVoltage(vbatLatestADC) / currentBatteryProfile->voltage.cellDetect) + 1;
|
||||
batteryCellCount = (vbat / currentBatteryProfile->voltage.cellDetect) + 1;
|
||||
if (batteryCellCount > 8) batteryCellCount = 8; // something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
|
||||
}
|
||||
|
||||
|
@ -252,18 +246,21 @@ void batteryUpdate(timeUs_t timeDelta)
|
|||
batteryWarningVoltage = batteryCellCount * currentBatteryProfile->voltage.cellWarning;
|
||||
batteryCriticalVoltage = batteryCellCount * currentBatteryProfile->voltage.cellMin;
|
||||
|
||||
batteryFullWhenPluggedIn = batteryAdcToVoltage(vbatLatestADC) >= (batteryFullVoltage - batteryCellCount * VBATT_CELL_FULL_MAX_DIFF);
|
||||
batteryUseCapacityThresholds = feature(FEATURE_CURRENT_METER) && batteryFullWhenPluggedIn && (currentBatteryProfile->capacity.value > 0) &&
|
||||
batteryFullWhenPluggedIn = vbat >= (batteryFullVoltage - batteryCellCount * VBATT_CELL_FULL_MAX_DIFF);
|
||||
batteryUseCapacityThresholds = isAmperageConfigured() && batteryFullWhenPluggedIn && (currentBatteryProfile->capacity.value > 0) &&
|
||||
(currentBatteryProfile->capacity.warning > 0) && (currentBatteryProfile->capacity.critical > 0);
|
||||
|
||||
}
|
||||
} else {
|
||||
updateBatteryVoltage(timeDelta, false);
|
||||
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD */
|
||||
else if (batteryState != BATTERY_NOT_PRESENT && vbat <= VBATT_PRESENT_THRESHOLD) {
|
||||
if (batteryState != BATTERY_NOT_PRESENT && vbat <= VBATT_PRESENT_THRESHOLD) {
|
||||
batteryState = BATTERY_NOT_PRESENT;
|
||||
batteryCellCount = 0;
|
||||
batteryWarningVoltage = 0;
|
||||
batteryCriticalVoltage = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (batteryState != BATTERY_NOT_PRESENT) {
|
||||
|
||||
|
@ -358,12 +355,7 @@ uint16_t getBatterySagCompensatedVoltage(void)
|
|||
|
||||
float calculateThrottleCompensationFactor(void)
|
||||
{
|
||||
return batteryFullVoltage / sagCompensatedVBat;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltageLatestADC(void)
|
||||
{
|
||||
return vbatLatestADC;
|
||||
return 1.0f + ((float)batteryFullVoltage / sagCompensatedVBat - 1.0f) * batteryMetersConfig()->throttle_compensation_weight;
|
||||
}
|
||||
|
||||
uint16_t getBatteryWarningVoltage(void)
|
||||
|
@ -415,11 +407,6 @@ int16_t getAmperage(void)
|
|||
return amperage;
|
||||
}
|
||||
|
||||
int16_t getAmperageLatestADC(void)
|
||||
{
|
||||
return amperageLatestADC;
|
||||
}
|
||||
|
||||
int32_t getPower(void)
|
||||
{
|
||||
return power;
|
||||
|
@ -443,10 +430,12 @@ void currentMeterUpdate(timeUs_t timeDelta)
|
|||
|
||||
switch (batteryMetersConfig()->current.type) {
|
||||
case CURRENT_SENSOR_ADC:
|
||||
amperageLatestADC = adcGetChannel(ADC_CURRENT);
|
||||
amperageLatestADC = pt1FilterApply4(&erageFilterState, amperageLatestADC, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f);
|
||||
amperage = currentSensorToCentiamps(amperageLatestADC);
|
||||
{
|
||||
int32_t microvolts = ((uint32_t)adcGetChannel(ADC_CURRENT) * ADCVREF * 100) / 0xFFF * 10 - (int32_t)batteryMetersConfig()->current.offset * 100;
|
||||
amperage = microvolts / batteryMetersConfig()->current.scale; // current in 0.01A steps
|
||||
amperage = pt1FilterApply4(&erageFilterState, amperage, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f);
|
||||
break;
|
||||
}
|
||||
case CURRENT_SENSOR_VIRTUAL:
|
||||
amperage = batteryMetersConfig()->current.offset;
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
|
@ -559,7 +548,7 @@ uint8_t calculateBatteryPercentage(void)
|
|||
if (batteryState == BATTERY_NOT_PRESENT)
|
||||
return 0;
|
||||
|
||||
if (batteryFullWhenPluggedIn && feature(FEATURE_CURRENT_METER) && (currentBatteryProfile->capacity.value > 0) && (currentBatteryProfile->capacity.critical > 0)) {
|
||||
if (batteryFullWhenPluggedIn && isAmperageConfigured() && (currentBatteryProfile->capacity.value > 0) && (currentBatteryProfile->capacity.critical > 0)) {
|
||||
uint32_t capacityDiffBetweenFullAndEmpty = currentBatteryProfile->capacity.value - currentBatteryProfile->capacity.critical;
|
||||
return constrain(batteryRemainingCapacity * 100 / capacityDiffBetweenFullAndEmpty, 0, 100);
|
||||
} else
|
||||
|
|
|
@ -76,6 +76,8 @@ typedef struct batteryMetersConfig_s {
|
|||
uint16_t idle_power; // power drawn by the system when the motor(s) are stopped (cW)
|
||||
uint8_t rth_energy_margin; // Energy that should be left after RTH (%), used for remaining time/distance before RTH
|
||||
|
||||
float throttle_compensation_weight;
|
||||
|
||||
} batteryMetersConfig_t;
|
||||
|
||||
typedef struct batteryProfile_s {
|
||||
|
@ -125,7 +127,6 @@ bool isPowerSupplyImpedanceValid(void);
|
|||
uint16_t getBatteryVoltage(void);
|
||||
uint16_t getBatteryRawVoltage(void);
|
||||
uint16_t getBatterySagCompensatedVoltage(void);
|
||||
uint16_t getBatteryVoltageLatestADC(void);
|
||||
uint16_t getBatteryWarningVoltage(void);
|
||||
uint8_t getBatteryCellCount(void);
|
||||
uint16_t getBatteryRawAverageCellVoltage(void);
|
||||
|
@ -136,7 +137,6 @@ uint16_t getPowerSupplyImpedance(void);
|
|||
|
||||
bool isAmperageConfigured(void);
|
||||
int16_t getAmperage(void);
|
||||
int16_t getAmperageLatestADC(void);
|
||||
int32_t getPower(void);
|
||||
int32_t getMAhDrawn(void);
|
||||
int32_t getMWhDrawn(void);
|
||||
|
|
|
@ -39,6 +39,7 @@
|
|||
#include "drivers/compass/compass_ist8308.h"
|
||||
#include "drivers/compass/compass_qmc5883l.h"
|
||||
#include "drivers/compass/compass_mpu9250.h"
|
||||
#include "drivers/compass/compass_lis3mdl.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/logging.h"
|
||||
|
@ -229,6 +230,19 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
|
|||
break;
|
||||
}
|
||||
#endif
|
||||
FALLTHROUGH;
|
||||
|
||||
case MAG_LIS3MDL:
|
||||
#ifdef USE_MAG_LIS3MDL
|
||||
if (lis3mdlDetect(dev)) {
|
||||
#ifdef MAG_LIS3MDL_ALIGN
|
||||
dev->magAlign = MAG_LIS3MDL_ALIGN;
|
||||
#endif
|
||||
magHardware = MAG_LIS3MDL;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
|
||||
if (magHardwareToUse != MAG_AUTODETECT) {
|
||||
break;
|
||||
|
|
|
@ -40,7 +40,8 @@ typedef enum {
|
|||
MAG_QMC5883 = 8,
|
||||
MAG_MPU9250 = 9,
|
||||
MAG_IST8308 = 10,
|
||||
MAG_FAKE = 11,
|
||||
MAG_LIS3MDL = 11,
|
||||
MAG_FAKE = 12,
|
||||
MAG_MAX = MAG_FAKE
|
||||
} magSensor_e;
|
||||
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE_2_SHARES_UART3
|
||||
|
@ -64,6 +62,7 @@
|
|||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C2
|
||||
|
@ -85,10 +84,13 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define INVERTER_PIN_UART1_RX PC0 // PC0 used as inverter select GPIO
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
|
|
@ -14,6 +14,7 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/pitotmeter_ms4525.c \
|
||||
drivers/pitotmeter_adc.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
|
|
|
@ -113,6 +113,7 @@
|
|||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define TARGET_MOTOR_COUNT 4
|
||||
|
|
|
@ -10,6 +10,7 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/rangefinder/rangefinder_hcsr04.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
|
|
|
@ -77,6 +77,7 @@
|
|||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define USE_VCP
|
||||
#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7)
|
||||
|
|
|
@ -16,5 +16,6 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_mag3110.c
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_lis3mdl.c
|
||||
|
||||
|
|
|
@ -66,6 +66,7 @@
|
|||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define MAG_MPU9250_ALIGN CW180_DEG_FLIP
|
||||
|
||||
|
|
|
@ -12,5 +12,6 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_mpu9250.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stdperiph.c
|
||||
|
|
|
@ -64,6 +64,7 @@
|
|||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define MAG_AK9863_ALIGN CW180_DEG_FLIP
|
||||
#define MAG_MPU9250_ALIGN CW180_DEG_FLIP
|
||||
|
@ -103,11 +104,11 @@
|
|||
// Performance logging for SD card operations:
|
||||
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
|
||||
|
||||
//#define M25P16_CS_PIN SPI2_NSS_PIN
|
||||
//#define M25P16_SPI_BUS BUS_SPI2
|
||||
#define M25P16_CS_PIN SPI2_NSS_PIN
|
||||
#define M25P16_SPI_BUS BUS_SPI2
|
||||
|
||||
//#define USE_FLASHFS
|
||||
//#define USE_FLASH_M25P16
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
|
@ -119,15 +120,15 @@
|
|||
#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_UART3
|
||||
#define UART3_RX_PIN NONE
|
||||
#define UART3_TX_PIN NONE
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC11
|
||||
#define UART4_TX_PIN PC10
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
//#define USE_ESCSERIAL
|
||||
//#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
|
||||
|
@ -158,6 +159,13 @@
|
|||
#define I2C1_SCL PB6
|
||||
#define I2C1_SDA PB7
|
||||
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI3
|
||||
#define MAX7456_CS_PIN PB12
|
||||
//#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz // XXX
|
||||
//#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST) // XXX
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
F7X2RE_TARGETS += $(TARGET)
|
||||
FEATURES += SDCARD VCP
|
||||
FEATURES += SDCARD VCP ONBOARDFLASH
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
|
@ -13,5 +13,7 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/max7456.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_hal.c
|
||||
|
|
|
@ -27,8 +27,6 @@
|
|||
#define BEEPER PB2
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART1 PC3
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
@ -53,6 +51,7 @@
|
|||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_LIS3MDL
|
||||
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
|
@ -69,9 +68,12 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PA8
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define INVERTER_PIN_UART1_RX PC3
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
|
|
@ -9,6 +9,7 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/pitotmeter_ms4525.c
|
||||
|
|
|
@ -51,6 +51,7 @@
|
|||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define USE_BARO
|
||||
|
||||
|
|
|
@ -12,6 +12,7 @@ TARGET_SRC = \
|
|||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_hal.c \
|
||||
drivers/pitotmeter_ms4525.c \
|
||||
|
|
|
@ -51,6 +51,7 @@
|
|||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C2
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue