1
0
Fork 0
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:
Pawel Spychalski (DzikuVx) 2018-08-07 09:46:58 +02:00
commit 9212209d96
236 changed files with 2570 additions and 1290 deletions

View file

@ -12,12 +12,8 @@
* Rangefinder support (sonar and laser) * Rangefinder support (sonar and laser)
* Oneshot and Multishot ESC support. * Oneshot and Multishot ESC support.
* Blackbox flight recorder logging (to onboard flash or external SD card). * 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). * Lux's new PID (uses float values internally, resistant to looptime variation).
* Simultaneous Bluetooth configuration and OSD. * Simultaneous Bluetooth configuration and OSD.
* Better PWM and PPM input and failsafe detection than baseflight.
* Better FrSky Telemetry than baseflight.
* LTM Telemetry. * LTM Telemetry.
* Smartport Telemetry. * Smartport Telemetry.
* RSSI via ADC - Uses ADC to read PWM RSSI signals, tested with FrSky D4R-II and X8R. * 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. * 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) * 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 * 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. 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 documentation](https://github.com/iNavFlight/inav/tree/master/docs)
* [Official Wiki](https://github.com/iNavFlight/inav/wiki) * [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) * [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 Painless360](https://www.youtube.com/playlist?list=PLYsWjANuAm4qdXEGFSeUhOZ10-H8YTSnH)
* [Video series by Paweł Spychalski](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLloACrA6f1_daCjhqY2x0fB) * [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. * New features.
* Telling us your ideas and suggestions. * 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 https://github.com/iNavFlight/inav/issues
@ -83,4 +84,4 @@ Please refer to the development section in the [docs/development](https://github
## INAV Releases ## INAV Releases
https://github.com/iNavFlight/inav/releases https://github.com/iNavFlight/inav/releases

View file

@ -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
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)

View file

@ -79,10 +79,10 @@ I2C requires that the WS2812 led strip is moved to S5, thus WS2812 is not usable
### Soft Serial ### 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 * 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 * Assign the desired function to the soft-serial port
### USB ### USB

View file

@ -132,6 +132,8 @@ For Omnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_
## SoftwareSerial ## 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. 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. 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 ### Omnibus F4 v3/v4/v5 SoftwareSerial Connections
The SOFTSERIAL1 is an uni-directional port mapped to UART6-TX pin. 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 # Wiring diagrams for Omnibus F4 Pro

View file

@ -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 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. 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. 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. ## Restore via CLI.
Use the cli `defaults` command first. 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 ## CLI Command Reference
@ -72,6 +70,7 @@ Re-apply any new defaults as desired.
| `color` | configure colors | | `color` | configure colors |
| `defaults` | reset to defaults and reboot | | `defaults` | reset to defaults and reboot |
| `dump` | print configurable settings in a pastable form | | `dump` | print configurable settings in a pastable form |
| `diff` | print only settings that have been modified |
| `exit` | | | `exit` | |
| `feature` | list or -val or val | | `feature` | list or -val or val |
| `get` | get variable value | | `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. | | 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) | | 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 | | 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 | 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 |
| 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. |
| 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. | | 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 | | 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. | | 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. | | 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_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_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_invert | OFF | | | 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 | | 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 | | 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. | | 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_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_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_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_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_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. | | 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_coordinates_format | 0 | FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
| frsky_unit | METRIC | METRIC , IMPERIAL | | 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_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 | | | report_cell_voltage | OFF | |
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | | 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_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. | | 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. | | 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. | | 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_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_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_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_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_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. | | 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. | | 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_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] | | 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. 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 Original Spreadsheet used to make this table can be found here https://docs.google.com/spreadsheets/d/1ubjYdMGmZ2aAMUNYkdfe3hhIF7wRfIjcuPOi_ysmp00/edit?usp=sharing

View file

@ -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. 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 | | Release | Compiler Source |
| ------- | --------------- | | ------- | --------------- |
| 16.04 or earlier | Use the 'official' PPA | | 16.04 or earlier | Use the 'official' PPA |
| 17.10 | Use the 'official' PPA as the distro compiler (5.4) *may* be too old | | 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. 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 # 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 sudo apt install gcc-arm-none-eabi
``` ```
# Using the PPA compiler # 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 sudo apt-get remove binutils-arm-none-eabi gcc-arm-none-eabi
@ -84,9 +85,9 @@ cd inav
make 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 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. 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 # Updating and rebuilding

File diff suppressed because it is too large Load diff

View file

@ -156,13 +156,13 @@ MCU_COMMON_SRC = \
drivers/adc_stm32f4xx.c \ drivers/adc_stm32f4xx.c \
drivers/adc_stm32f4xx.c \ drivers/adc_stm32f4xx.c \
drivers/bus_i2c_stm32f40x.c \ drivers/bus_i2c_stm32f40x.c \
drivers/inverter.c \
drivers/serial_softserial.c \ drivers/serial_softserial.c \
drivers/serial_uart_stm32f4xx.c \ drivers/serial_uart_stm32f4xx.c \
drivers/system_stm32f4xx.c \ drivers/system_stm32f4xx.c \
drivers/timer.c \ drivers/timer.c \
drivers/timer_impl_stdperiph.c \ drivers/timer_impl_stdperiph.c \
drivers/timer_stm32f4xx.c \ drivers/timer_stm32f4xx.c \
drivers/uart_inverter.c \
drivers/dma_stm32f4xx.c drivers/dma_stm32f4xx.c
ifeq ($(PERIPH_DRIVER), HAL) ifeq ($(PERIPH_DRIVER), HAL)

View file

@ -146,11 +146,11 @@ MCU_COMMON_SRC = \
drivers/adc_stm32f7xx.c \ drivers/adc_stm32f7xx.c \
drivers/bus_i2c_hal.c \ drivers/bus_i2c_hal.c \
drivers/dma_stm32f7xx.c \ drivers/dma_stm32f7xx.c \
drivers/inverter.c \
drivers/bus_spi_hal.c \ drivers/bus_spi_hal.c \
drivers/timer.c \ drivers/timer.c \
drivers/timer_impl_hal.c \ drivers/timer_impl_hal.c \
drivers/timer_stm32f7xx.c \ drivers/timer_stm32f7xx.c \
drivers/uart_inverter.c \
drivers/system_stm32f7xx.c \ drivers/system_stm32f7xx.c \
drivers/serial_uart_stm32f7xx.c \ drivers/serial_uart_stm32f7xx.c \
drivers/serial_softserial.c \ drivers/serial_softserial.c \

View file

@ -14,4 +14,4 @@ RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 FIREWORKSV2
RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4V3 OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4V3 OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF405SE RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF405SE MATEKF411

View file

@ -75,6 +75,7 @@
#include "sensors/pitotmeter.h" #include "sensors/pitotmeter.h"
#include "sensors/rangefinder.h" #include "sensors/rangefinder.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "flight/wind_estimator.h"
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT) #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", 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", 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)}, {"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)}, {"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)}, {"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)}, {"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)}, {"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)}, {"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)}, {"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", 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", 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)}, {"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]: */ /* 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)}, {"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}, {"vbat", -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}, {"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 #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}, {"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)}, {"hwHealthStatus", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"powerSupplyImpedance", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, {"powerSupplyImpedance", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"sagCompensatedVBat", -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 { typedef enum BlackboxState {
@ -388,8 +394,8 @@ typedef struct blackboxMainState_s {
int16_t motor[MAX_SUPPORTED_MOTORS]; int16_t motor[MAX_SUPPORTED_MOTORS];
int16_t servo[MAX_SUPPORTED_SERVOS]; int16_t servo[MAX_SUPPORTED_SERVOS];
uint16_t vbatLatest; uint16_t vbat;
uint16_t amperageLatest; int16_t amperage;
#ifdef USE_BARO #ifdef USE_BARO
int32_t BaroAlt; int32_t BaroAlt;
@ -413,7 +419,7 @@ typedef struct blackboxMainState_s {
int16_t navRealVel[XYZ_AXIS_COUNT]; int16_t navRealVel[XYZ_AXIS_COUNT];
int16_t navAccNEU[XYZ_AXIS_COUNT]; int16_t navAccNEU[XYZ_AXIS_COUNT];
int16_t navTargetVel[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 navHeading;
int16_t navTargetHeading; int16_t navTargetHeading;
int16_t navSurface; int16_t navSurface;
@ -436,6 +442,7 @@ typedef struct blackboxSlowState_s {
int32_t hwHealthStatus; int32_t hwHealthStatus;
uint16_t powerSupplyImpedance; uint16_t powerSupplyImpedance;
uint16_t sagCompensatedVBat; 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() } __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
//From rc_controls.c //From rc_controls.c
@ -549,7 +556,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
case FLIGHT_LOG_FIELD_CONDITION_VBAT: case FLIGHT_LOG_FIELD_CONDITION_VBAT:
return feature(FEATURE_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; return feature(FEATURE_CURRENT_METER) && batteryMetersConfig()->current.type == CURRENT_SENSOR_ADC;
case FLIGHT_LOG_FIELD_CONDITION_SURFACE: 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) * 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 // 12bit value directly from ADC
blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest); blackboxWriteSignedVB(blackboxCurrent->amperage);
} }
#ifdef USE_MAG #ifdef USE_MAG
@ -907,11 +914,11 @@ static void writeInterframe(void)
int optionalFieldCount = 0; int optionalFieldCount = 0;
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) { 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)) { if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE)) {
deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest; deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperage - blackboxLast->amperage;
} }
#ifdef USE_MAG #ifdef USE_MAG
@ -983,7 +990,7 @@ static void writeInterframe(void)
} }
for (int x = 0; x < XYZ_AXIS_COUNT; x++) { 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); blackboxWriteSignedVB(blackboxCurrent->navSurface - blackboxLast->navSurface);
@ -1021,6 +1028,8 @@ static void writeSlowFrame(void)
blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance); blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance);
blackboxWriteUnsignedVB(slowHistory.sagCompensatedVBat); blackboxWriteUnsignedVB(slowHistory.sagCompensatedVBat);
blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);
blackboxSlowFrameIterationTimer = 0; blackboxSlowFrameIterationTimer = 0;
} }
@ -1043,6 +1052,16 @@ static void loadSlowState(blackboxSlowState_t *slow)
(getHwPitotmeterStatus() << 2 * 6); (getHwPitotmeterStatus() << 2 * 6);
slow->powerSupplyImpedance = getPowerSupplyImpedance(); slow->powerSupplyImpedance = getPowerSupplyImpedance();
slow->sagCompensatedVBat = getBatterySagCompensatedVoltage(); 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[1] = &blackboxHistoryRing[1];
blackboxHistory[2] = &blackboxHistoryRing[2]; 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 //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 #endif
#ifdef USE_NAV #ifdef USE_NAV
if (!STATE(FIXED_WING)) { 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); // log requested velocity in cm/s
blackboxCurrent->mcVelAxisPID[1][i] = lrintf(nav_pids->vel[i].integral / 10); blackboxCurrent->mcPosAxisP[i] = lrintf(nav_pids->pos[i].output_constrained);
blackboxCurrent->mcVelAxisPID[2][i] = lrintf(nav_pids->vel[i].derivative / 10);
// 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 #endif
} }
#ifdef USE_NAV #ifdef USE_NAV
if (STATE(FIXED_WING)) { 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[0] = lrintf(nav_pids->fw_nav.proportional / 10);
blackboxCurrent->fwPosPID[1] = lrintf(nav_pids->fw_nav.integral / 10); blackboxCurrent->fwPosPID[1] = lrintf(nav_pids->fw_nav.integral / 10);
blackboxCurrent->fwPosPID[2] = lrintf(nav_pids->fw_nav.derivative / 10); blackboxCurrent->fwPosPID[2] = lrintf(nav_pids->fw_nav.derivative / 10);
blackboxCurrent->fwPosPIDOutput = lrintf(nav_pids->fw_nav.output_constrained / 10); blackboxCurrent->fwPosPIDOutput = lrintf(nav_pids->fw_nav.output_constrained / 10);
} else { } else {
blackboxCurrent->mcSurfacePID[0] = lrintf(nav_pids->surface.proportional / 10); blackboxCurrent->mcSurfacePID[0] = lrintf(nav_pids->surface.proportional / 10);
blackboxCurrent->mcSurfacePID[1] = lrintf(nav_pids->surface.integral / 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->motor[i] = motor[i];
} }
blackboxCurrent->vbatLatest = getBatteryVoltageLatestADC(); blackboxCurrent->vbat = getBatteryRawVoltage();
blackboxCurrent->amperageLatest = getAmperageLatestADC(); blackboxCurrent->amperage = getAmperage();
#ifdef USE_BARO #ifdef USE_BARO
blackboxCurrent->BaroAlt = baro.BaroAlt; blackboxCurrent->BaroAlt = baro.BaroAlt;
@ -1461,7 +1489,7 @@ static char *blackboxGetStartDateTime(char *buf)
// rtcGetDateTime will fill dt with 0000-01-01T00:00:00 // rtcGetDateTime will fill dt with 0000-01-01T00:00:00
// when time is not known. // when time is not known.
rtcGetDateTime(&dt); rtcGetDateTime(&dt);
dateTimeFormatUTC(buf, &dt); dateTimeFormatLocal(buf, &dt);
return buf; return buf;
} }

View file

@ -38,7 +38,7 @@ typedef enum FlightLogFieldCondition {
FLIGHT_LOG_FIELD_CONDITION_BARO, FLIGHT_LOG_FIELD_CONDITION_BARO,
FLIGHT_LOG_FIELD_CONDITION_PITOT, FLIGHT_LOG_FIELD_CONDITION_PITOT,
FLIGHT_LOG_FIELD_CONDITION_VBAT, 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_SURFACE,
FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV, FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV,
FLIGHT_LOG_FIELD_CONDITION_MC_NAV, FLIGHT_LOG_FIELD_CONDITION_MC_NAV,

View file

@ -56,6 +56,7 @@
#include "config/parameter_group_ids.h" #include "config/parameter_group_ids.h"
// For 'ARM' related // For 'ARM' related
#include "fc/fc_core.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.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) { if (IS_PRINTVALUE(p, screenRow) && p->data) {
buff[0] = '\0'; buff[0] = '\0';
const OSD_SETTING_t *ptr = p->data; const OSD_SETTING_t *ptr = p->data;
const setting_t *var = &settingsTable[ptr->val]; const setting_t *var = settingGet(ptr->val);
int32_t value; int32_t value;
const void *valuePointer = settingGetValuePointer(var); const void *valuePointer = settingGetValuePointer(var);
switch (SETTING_TYPE(var)) { switch (SETTING_TYPE(var)) {
@ -476,13 +477,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
break; break;
case MODE_LOOKUP: case MODE_LOOKUP:
{ {
const char *str = NULL; const char *str = settingLookupValueName(var, value);
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];
}
}
strncpy(buff, str ? str : "INVALID", sizeof(buff) - 1); strncpy(buff, str ? str : "INVALID", sizeof(buff) - 1);
} }
break; break;
@ -764,11 +759,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing? displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing?
stopMotors(); fcReboot(false);
stopPwmAllMotors();
delay(200);
systemReset();
} }
DISABLE_ARMING_FLAG(ARMING_DISABLED_CMS_MENU); 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: case OME_Setting:
if (p->data) { if (p->data) {
const OSD_SETTING_t *ptr = 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_min_t min = settingGetMin(var);
setting_max_t max = settingGetMax(var); setting_max_t max = settingGetMax(var);
float step = ptr->step ?: 1; float step = ptr->step ?: 1;

View file

@ -148,8 +148,7 @@ static const OSD_Entry menuMainEntries[] =
OSD_SUBMENU_ENTRY("PID TUNING", &cmsx_menuImu), OSD_SUBMENU_ENTRY("PID TUNING", &cmsx_menuImu),
OSD_SUBMENU_ENTRY("FEATURES", &menuFeatures), OSD_SUBMENU_ENTRY("FEATURES", &menuFeatures),
#if defined(USE_OSD) && defined(CMS_MENU_OSD) #if defined(USE_OSD) && defined(CMS_MENU_OSD)
OSD_SUBMENU_ENTRY("OSD LAYOUTS", &cmsx_menuOsdLayout), OSD_SUBMENU_ENTRY("OSD", &cmsx_menuOsd),
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
#endif #endif
OSD_SUBMENU_ENTRY("BATTERY", &cmsx_menuBattery), OSD_SUBMENU_ENTRY("BATTERY", &cmsx_menuBattery),
OSD_SUBMENU_ENTRY("FC&FW INFO", &menuInfo), OSD_SUBMENU_ENTRY("FC&FW INFO", &menuInfo),

View file

@ -61,9 +61,9 @@ static const OSD_Entry cmsx_menuAlarmsEntries[] = {
OSD_END_ENTRY, OSD_END_ENTRY,
}; };
const CMS_Menu cmsx_menuAlarms = { static const CMS_Menu cmsx_menuAlarms = {
#ifdef CMS_MENU_DEBUG #ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUALARMS", .GUARD_text = "MENUOSDA",
.GUARD_type = OME_MENU, .GUARD_type = OME_MENU,
#endif #endif
.onEnter = NULL, .onEnter = NULL,
@ -144,7 +144,7 @@ static long osdElemActionsOnEnter(const OSD_Entry *from)
static const OSD_Entry menuOsdElemsEntries[] = static const OSD_Entry menuOsdElemsEntries[] =
{ {
OSD_LABEL_ENTRY("--- OSD ---"), OSD_LABEL_ENTRY("--- OSD ITEMS ---"),
OSD_ELEMENT_ENTRY("RSSI", OSD_RSSI_VALUE), OSD_ELEMENT_ENTRY("RSSI", OSD_RSSI_VALUE),
OSD_ELEMENT_ENTRY("MAIN BATTERY", OSD_MAIN_BATT_VOLTAGE), 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 = { const CMS_Menu menuOsdElements = {
#ifdef CMS_MENU_DEBUG #ifdef CMS_MENU_DEBUG
.GUARD_text = "MENUOSDELEMS", .GUARD_text = "MENUOSDE",
.GUARD_type = OME_MENU, .GUARD_type = OME_MENU,
#endif #endif
.onEnter = osdElementsOnEnter, .onEnter = osdElementsOnEnter,
@ -290,7 +290,7 @@ static const OSD_Entry cmsx_menuOsdLayoutEntries[] =
const CMS_Menu cmsx_menuOsdLayout = { const CMS_Menu cmsx_menuOsdLayout = {
#ifdef CMS_MENU_DEBUG #ifdef CMS_MENU_DEBUG
.GUARD_text = "MENULAYOUT", .GUARD_text = "MENUOSDL",
.GUARD_type = OME_MENU, .GUARD_type = OME_MENU,
#endif #endif
.onEnter = NULL, .onEnter = NULL,
@ -317,4 +317,53 @@ static long osdElementsOnExit(const OSD_Entry *from)
return 0; 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 #endif // CMS

View file

@ -17,5 +17,4 @@
#pragma once #pragma once
extern const CMS_Menu cmsx_menuAlarms; extern const CMS_Menu cmsx_menuOsd;
extern const CMS_Menu cmsx_menuOsdLayout;

View file

@ -89,7 +89,7 @@ static const OSD_TAB_t trampCmsEntChan = { &trampCmsChan, VTX_TRAMP_CHANNEL_COUN
static uint8_t trampCmsPower = 1; 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) static void trampCmsUpdateFreqRef(void)
{ {

View file

@ -205,6 +205,13 @@ float biquadFilterApply(biquadFilter_t *filter, float input)
return result; 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 * FIR filter
*/ */

View file

@ -73,6 +73,7 @@ void biquadFilterInitNotch(biquadFilter_t *filter, uint32_t samplingIntervalUs,
void biquadFilterInitLPF(biquadFilter_t *filter, uint16_t filterFreq, 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); void biquadFilterInit(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs, float Q, biquadFilterType_e filterType);
float biquadFilterApply(biquadFilter_t *filter, float sample); float biquadFilterApply(biquadFilter_t *filter, float sample);
float biquadFilterReset(biquadFilter_t *filter, float value);
float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff); float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff);
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs); void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);

View file

@ -31,12 +31,12 @@ typedef struct {
} fpQuaternion_t; } fpQuaternion_t;
static inline fpQuaternion_t * quaternionInitUnit(fpQuaternion_t * result) static inline fpQuaternion_t * quaternionInitUnit(fpQuaternion_t * result)
{ {
result->q0 = 1.0f; result->q0 = 1.0f;
result->q1 = 0.0f; result->q1 = 0.0f;
result->q2 = 0.0f; result->q2 = 0.0f;
result->q3 = 0.0f; result->q3 = 0.0f;
return result; return result;
} }
static inline fpQuaternion_t * quaternionInitFromVector(fpQuaternion_t * result, const fpVector3_t * v) static inline fpQuaternion_t * quaternionInitFromVector(fpQuaternion_t * result, const fpVector3_t * v)

View file

@ -58,7 +58,7 @@ PG_RESET_TEMPLATE(timeConfig_t, timeConfig,
.tz_automatic_dst = TZ_AUTO_DST_OFF, .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 second = dt->seconds; // 0-59
unsigned int minute = dt->minutes; // 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) { switch ((tz_automatic_dst_e) timeConfig()->tz_automatic_dst) {
case TZ_AUTO_DST_OFF: case TZ_AUTO_DST_OFF:
break; 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 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) { if (dateTime.month < 3 || dateTime.month > 11) {
return false; return false;
@ -180,39 +200,24 @@ static bool isDST(rtcTime_t t)
return dateTime.day < firstSunday; return dateTime.day < firstSunday;
} }
break; 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; return false;
} }
#endif #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 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 defined(RTC_AUTOMATIC_DST)
if (automatic_dst && isDST(offsetTime)) { 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 #endif
rtcTimeToDateTime(dateTimeOffset, offsetTime); rtcTimeToDateTime(dateTimeOffset, offsetTime);
} }
@ -226,10 +231,10 @@ static bool dateTimeFormat(char *buf, dateTime_t *dateTime, int16_t offset, bool
bool retVal = true; bool retVal = true;
// Apply offset if necessary // Apply offset if necessary
if (offset != 0) { if (offset != 0 || automatic_dst) {
dateTimeWithOffset(&local, dateTime, &offset, automatic_dst);
tz_hours = offset / 60; tz_hours = offset / 60;
tz_minutes = ABS(offset % 60); tz_minutes = ABS(offset % 60);
dateTimeWithOffset(&local, dateTime, offset, automatic_dst);
dateTime = &local; dateTime = &local;
} }
@ -271,12 +276,13 @@ bool dateTimeFormatUTC(char *buf, dateTime_t *dt)
bool dateTimeFormatLocal(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) bool dateTimeSplitFormatted(char *formatted, char **date, char **time)
@ -326,6 +332,15 @@ bool rtcGetDateTime(dateTime_t *dt)
return false; return false;
} }
bool rtcGetDateTimeLocal(dateTime_t *dt)
{
if (rtcGetDateTime(dt)) {
dateTimeUTCToLocal(dt, dt);
return true;
}
return false;
}
bool rtcSetDateTime(dateTime_t *dt) bool rtcSetDateTime(dateTime_t *dt)
{ {
rtcTime_t t = dateTimeToRtcTime(dt); rtcTime_t t = dateTimeToRtcTime(dt);

View file

@ -93,7 +93,7 @@ typedef struct _dateTime_s {
bool dateTimeFormatUTC(char *buf, dateTime_t *dt); bool dateTimeFormatUTC(char *buf, dateTime_t *dt);
bool dateTimeFormatLocal(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 // dateTimeSplitFormatted splits a formatted date into its date
// and time parts. Note that the string pointed by formatted will // and time parts. Note that the string pointed by formatted will
// be modifed and will become invalid after calling this function. // 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 rtcSet(rtcTime_t *t);
bool rtcGetDateTime(dateTime_t *dt); bool rtcGetDateTime(dateTime_t *dt);
bool rtcGetDateTimeLocal(dateTime_t *dt);
bool rtcSetDateTime(dateTime_t *dt); bool rtcSetDateTime(dateTime_t *dt);

View file

@ -42,7 +42,7 @@ void rotationMatrixFromAngles(fpMat3_t * rmat, const fp_angles_t * angles);
void rotationMatrixFromAxisAngle(fpMat3_t * rmat, const fpAxisAngle_t * a); void rotationMatrixFromAxisAngle(fpMat3_t * rmat, const fpAxisAngle_t * a);
static inline void vectorZero(fpVector3_t * v) static inline void vectorZero(fpVector3_t * v)
{ {
v->x = 0.0f; v->x = 0.0f;
v->y = 0.0f; v->y = 0.0f;
v->z = 0.0f; v->z = 0.0f;
@ -61,7 +61,7 @@ static inline fpVector3_t * rotationMatrixRotateVector(fpVector3_t * result, con
} }
static inline float vectorNormSquared(const fpVector3_t * v) static inline float vectorNormSquared(const fpVector3_t * v)
{ {
return sq(v->x) + sq(v->y) + sq(v->z); return sq(v->x) + sq(v->y) + sq(v->z);
} }

View file

@ -113,3 +113,7 @@
#define PG_RESERVED_FOR_TESTING_2 4094 #define PG_RESERVED_FOR_TESTING_2 4094
#define PG_RESERVED_FOR_TESTING_3 4093 #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

View file

@ -62,7 +62,7 @@ const gyroFilterAndRateConfig_t * chooseGyroConfig(uint8_t desiredLpf, uint16_t
} }
} }
DEBUG_TRACE("GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X", DEBUG_TRACE("GYRO CONFIG { %d, %d } -> { %d, %d}; regs 0x%02X, 0x%02X",
desiredLpf, desiredRateHz, desiredLpf, desiredRateHz,
candidate->gyroLpf, candidate->gyroRateHz, candidate->gyroLpf, candidate->gyroRateHz,
candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]); candidate->gyroConfigValues[0], candidate->gyroConfigValues[1]);

View file

@ -153,13 +153,13 @@ static void bmi160AccAndGyroInit(gyroDev_t *gyro)
busWrite(gyro->busDev, BMI160_REG_ACC_RANGE, BMI160_RANGE_8G); busWrite(gyro->busDev, BMI160_REG_ACC_RANGE, BMI160_RANGE_8G);
delay(1); delay(1);
busWrite(gyro->busDev, BMI160_REG_GYR_RANGE, BMI160_RANGE_2000DPS); busWrite(gyro->busDev, BMI160_REG_GYR_RANGE, BMI160_RANGE_2000DPS);
delay(1); delay(1);
// Enable offset compensation // Enable offset compensation
// uint8_t val = spiBusReadRegister(bus, BMI160_REG_OFFSET_0); // uint8_t val = spiBusReadRegister(bus, BMI160_REG_OFFSET_0);
// busWrite(gyro->busDev, BMI160_REG_OFFSET_0, val | 0xC0); // busWrite(gyro->busDev, BMI160_REG_OFFSET_0, val | 0xC0);
// Enable data ready interrupt // Enable data ready interrupt
busWrite(gyro->busDev, BMI160_REG_INT_EN1, BMI160_INT_EN1_DRDY); busWrite(gyro->busDev, BMI160_REG_INT_EN1, BMI160_INT_EN1_DRDY);

View file

@ -130,7 +130,7 @@ bool l3g4200dDetect(gyroDev_t *gyro)
if (gyro->busDev == NULL) { if (gyro->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(gyro->busDev)) { if (!deviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev); busDeviceDeInit(gyro->busDev);
return false; return false;

View file

@ -105,7 +105,7 @@ bool l3gd20Detect(gyroDev_t *gyro)
if (gyro->busDev == NULL) { if (gyro->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(gyro->busDev)) { if (!deviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev); busDeviceDeInit(gyro->busDev);
return false; return false;

View file

@ -138,7 +138,7 @@
#define MPU_DLPF_188HZ 0x01 #define MPU_DLPF_188HZ 0x01
#define MPU_DLPF_256HZ 0x00 #define MPU_DLPF_256HZ 0x00
typedef struct mpuConfiguration_s { typedef struct mpuConfiguration_s {
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
} mpuConfiguration_t; } mpuConfiguration_t;

View file

@ -121,7 +121,7 @@ bool mpu3050Detect(gyroDev_t *gyro)
if (gyro->busDev == NULL) { if (gyro->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(gyro->busDev)) { if (!deviceDetect(gyro->busDev)) {
busDeviceDeInit(gyro->busDev); busDeviceDeInit(gyro->busDev);
return false; return false;

View file

@ -162,7 +162,7 @@ static bool mpu6000DeviceDetect(busDevice_t * busDev)
busSetSpeed(busDev, BUS_SPEED_INITIALIZATION); busSetSpeed(busDev, BUS_SPEED_INITIALIZATION);
busWrite(busDev, MPU_RA_PWR_MGMT_1, BIT_H_RESET); busWrite(busDev, MPU_RA_PWR_MGMT_1, BIT_H_RESET);
do { do {
delay(150); delay(150);

View file

@ -118,7 +118,7 @@ static bool mpu6500DeviceDetect(busDevice_t * dev)
busSetSpeed(dev, BUS_SPEED_INITIALIZATION); busSetSpeed(dev, BUS_SPEED_INITIALIZATION);
busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET); busWrite(dev, MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET);
do { do {
delay(150); delay(150);

View file

@ -62,7 +62,7 @@ typedef enum {
BUSTYPE_SPI = 2 BUSTYPE_SPI = 2
} busType_e; } busType_e;
/* Ultimately all hardware descriptors will go to target definition files. /* Ultimately all hardware descriptors will go to target definition files.
* Driver code will merely query for it's HW descriptor and initialize it */ * Driver code will merely query for it's HW descriptor and initialize it */
typedef enum { typedef enum {
DEVHW_NONE = 0, DEVHW_NONE = 0,
@ -102,6 +102,7 @@ typedef enum {
DEVHW_IST8308, DEVHW_IST8308,
DEVHW_QMC5883, DEVHW_QMC5883,
DEVHW_MAG3110, DEVHW_MAG3110,
DEVHW_LIS3MDL,
/* OSD chips */ /* OSD chips */
DEVHW_MAX7456, DEVHW_MAX7456,
@ -165,8 +166,8 @@ typedef struct busDevice_s {
#endif #endif
} busdev; } busdev;
IO_t irqPin; // Device IRQ pin. Bus system will only assign IO_t object to this var. Initialization is up to device driver IO_t irqPin; // Device IRQ pin. Bus system will only assign IO_t object to this var. Initialization is up to device driver
uint32_t scratchpad[BUS_SCRATCHPAD_MEMORY_SIZE / sizeof(uint32_t)]; // Memory where device driver can store persistent data. Zeroed out when initializing the device uint32_t scratchpad[BUS_SCRATCHPAD_MEMORY_SIZE / sizeof(uint32_t)]; // Memory where device driver can store persistent data. Zeroed out when initializing the device
// for the first time. Useful when once device is shared between several sensors // for the first time. Useful when once device is shared between several sensors
// (like MPU/ICM acc-gyro sensors) // (like MPU/ICM acc-gyro sensors)
} busDevice_t; } busDevice_t;
@ -250,7 +251,7 @@ bool spiBusWriteRegister(const busDevice_t * dev, uint8_t reg, uint8_t data);
bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length); bool spiBusReadBuffer(const busDevice_t * dev, uint8_t reg, uint8_t * data, uint8_t length);
bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data); bool spiBusReadRegister(const busDevice_t * dev, uint8_t reg, uint8_t * data);
/* Pre-initialize all known device descriptors to make sure hardware state is consistent and known /* Pre-initialize all known device descriptors to make sure hardware state is consistent and known
* Initialize bus hardware */ * Initialize bus hardware */
void busInit(void); void busInit(void);

View file

@ -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 }; 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); 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]); spiSetSpeed(instance, spiClock[speed]);
} }

View file

@ -73,14 +73,14 @@
#endif #endif
#if defined(STM32F3) #if defined(STM32F3)
static const uint16_t spiDivisorMapFast[] = { static const uint16_t spiDivisorMapFast[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 281.25 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 281.25 KBits/s
SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 562.5 KBits/s SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 562.5 KBits/s
SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 9.0 MBits/s SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 9.0 MBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 18.0 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 18.0 MBits/s
SPI_BaudRatePrescaler_4 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s SPI_BaudRatePrescaler_4 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s
}; };
static const uint16_t spiDivisorMapSlow[] = { static const uint16_t spiDivisorMapSlow[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 140.625 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 140.625 KBits/s
SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 562.5 KBits/s SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 562.5 KBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 9.0 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 9.0 MBits/s
@ -88,14 +88,14 @@ static const uint16_t spiDivisorMapSlow[] = {
SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 18.0 MBits/s
}; };
#elif defined(STM32F4) #elif defined(STM32F4)
static const uint16_t spiDivisorMapFast[] = { static const uint16_t spiDivisorMapFast[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 328.125 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 328.125 KBits/s
SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 656.25 KBits/s SPI_BaudRatePrescaler_128, // SPI_CLOCK_SLOW 656.25 KBits/s
SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 10.5 MBits/s SPI_BaudRatePrescaler_8, // SPI_CLOCK_STANDARD 10.5 MBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 21.0 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_FAST 21.0 MBits/s
SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 42.0 MBits/s SPI_BaudRatePrescaler_2 // SPI_CLOCK_ULTRAFAST 42.0 MBits/s
}; };
static const uint16_t spiDivisorMapSlow[] = { static const uint16_t spiDivisorMapSlow[] = {
SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 164.062 KBits/s SPI_BaudRatePrescaler_256, // SPI_CLOCK_INITIALIZATON 164.062 KBits/s
SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 656.25 KBits/s SPI_BaudRatePrescaler_64, // SPI_CLOCK_SLOW 656.25 KBits/s
SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 10.5 MBits/s SPI_BaudRatePrescaler_4, // SPI_CLOCK_STANDARD 10.5 MBits/s

View file

@ -39,7 +39,7 @@
typedef enum { typedef enum {
SPI_CLOCK_INITIALIZATON = 0, // Lowest possible SPI_CLOCK_INITIALIZATON = 0, // Lowest possible
SPI_CLOCK_SLOW = 1, // ~1 MHz SPI_CLOCK_SLOW = 1, // ~1 MHz
SPI_CLOCK_STANDARD = 2, // ~10MHz SPI_CLOCK_STANDARD = 2, // ~10MHz
SPI_CLOCK_FAST = 3, // ~20MHz SPI_CLOCK_FAST = 3, // ~20MHz
SPI_CLOCK_ULTRAFAST = 4 // Highest possible SPI_CLOCK_ULTRAFAST = 4 // Highest possible

View file

@ -68,14 +68,14 @@
#define SPI4_NSS_PIN NONE #define SPI4_NSS_PIN NONE
#endif #endif
static const uint16_t spiDivisorMapFast[] = { static const uint16_t spiDivisorMapFast[] = {
SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 421.875 KBits/s SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 421.875 KBits/s
SPI_BAUDRATEPRESCALER_128, // SPI_CLOCK_SLOW 843.75 KBits/s SPI_BAUDRATEPRESCALER_128, // SPI_CLOCK_SLOW 843.75 KBits/s
SPI_BAUDRATEPRESCALER_16, // SPI_CLOCK_STANDARD 6.75 MBits/s SPI_BAUDRATEPRESCALER_16, // SPI_CLOCK_STANDARD 6.75 MBits/s
SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_FAST 13.5 MBits/s SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_FAST 13.5 MBits/s
SPI_BAUDRATEPRESCALER_4 // SPI_CLOCK_ULTRAFAST 27.0 MBits/s SPI_BAUDRATEPRESCALER_4 // SPI_CLOCK_ULTRAFAST 27.0 MBits/s
}; };
static const uint16_t spiDivisorMapSlow[] = { static const uint16_t spiDivisorMapSlow[] = {
SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 210.937 KBits/s SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 210.937 KBits/s
SPI_BAUDRATEPRESCALER_64, // SPI_CLOCK_SLOW 843.75 KBits/s SPI_BAUDRATEPRESCALER_64, // SPI_CLOCK_SLOW 843.75 KBits/s
SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_STANDARD 6.75 MBits/s SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_STANDARD 6.75 MBits/s

View file

@ -92,6 +92,7 @@
#define IST8310_REG_CNTRL1 0x0A #define IST8310_REG_CNTRL1 0x0A
#define IST8310_REG_CNTRL2 0x0B #define IST8310_REG_CNTRL2 0x0B
#define IST8310_REG_AVERAGE 0x41 #define IST8310_REG_AVERAGE 0x41
#define IST8310_REG_PDCNTL 0x42
// Parameter // Parameter
// ODR = Output Data Rate, we use single measure mode for getting more data. // ODR = Output Data Rate, we use single measure mode for getting more data.
@ -103,7 +104,8 @@
// Device ID (ist8310 -> 0x10) // Device ID (ist8310 -> 0x10)
#define IST8310_CHIP_ID 0x10 #define IST8310_CHIP_ID 0x10
#define IST8310_AVG_16 0x24 #define IST8310_AVG_16 0x24
#define IST8310_PULSE_DURATION_NORMAL 0xC0
#define IST8310_CNTRL2_RESET 0x01 #define IST8310_CNTRL2_RESET 0x01
#define IST8310_CNTRL2_DRPOL 0x04 #define IST8310_CNTRL2_DRPOL 0x04
@ -117,6 +119,9 @@ static bool ist8310Init(magDev_t * mag)
busWrite(mag->busDev, IST8310_REG_AVERAGE, IST8310_AVG_16); busWrite(mag->busDev, IST8310_REG_AVERAGE, IST8310_AVG_16);
delay(5); delay(5);
busWrite(mag->busDev, IST8310_REG_PDCNTL, IST8310_PULSE_DURATION_NORMAL);
delay(5);
return true; return true;
} }
@ -135,10 +140,10 @@ static bool ist8310Read(magDev_t * mag)
return false; 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[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; mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]) * LSB2FSV;
return true; return true;
} }

View 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

View 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);

View file

@ -122,18 +122,22 @@ static bool qmc5883Read(magDev_t * mag)
#define DETECTION_MAX_RETRY_COUNT 5 #define DETECTION_MAX_RETRY_COUNT 5
static bool deviceDetect(magDev_t * mag) static bool deviceDetect(magDev_t * mag)
{ {
// 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++) { for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
delay(10); // Must write reset first - don't care about the result
busWrite(mag->busDev, QMC5883L_REG_CONF2, QMC5883L_RST);
delay(30);
uint8_t sig = 0; uint8_t sig = 0;
bool ack = busRead(mag->busDev, QMC5883L_REG_ID, &sig); bool ack = busRead(mag->busDev, QMC5883L_REG_ID, &sig);
if (ack && sig == QMC5883_ID_VAL) { if (ack && sig == QMC5883_ID_VAL) {
return true; // 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;
}
} }
} }

View file

@ -154,6 +154,7 @@ static bool m25p16_readIdentification(void)
switch (chipID) { switch (chipID) {
case JEDEC_ID_MICRON_M25P16: case JEDEC_ID_MICRON_M25P16:
case JEDEC_ID_SPANSION_S25FL116: case JEDEC_ID_SPANSION_S25FL116:
case JEDEC_ID_WINBOND_W25Q16:
geometry.sectors = 32; geometry.sectors = 32;
geometry.pagesPerSector = 256; geometry.pagesPerSector = 256;
break; break;

View file

@ -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
}

View file

@ -13,7 +13,6 @@
#include "drivers/bus.h" #include "drivers/bus.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#define PCA9685_ADDR 0x40
#define PCA9685_MODE1 0x00 #define PCA9685_MODE1 0x00
#define PCA9685_PRESCALE 0xFE #define PCA9685_PRESCALE 0xFE

View file

@ -21,7 +21,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*/ */
/* /*
* This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB) * This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB)
*/ */

View file

@ -227,7 +227,7 @@ bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
void pwmWriteServo(uint8_t index, uint16_t value) 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 * If PCA9685 is enabled and but not detected, we do not want to write servo

View file

@ -55,16 +55,16 @@ void hcsr04i2cUpdate(rangefinderDev_t *rangefinder)
uint8_t response[3]; uint8_t response[3];
isHcsr04i2cResponding = busReadBuf(rangefinder->busDev, HCSR04_I2C_REGISTRY_STATUS, response, 3); isHcsr04i2cResponding = busReadBuf(rangefinder->busDev, HCSR04_I2C_REGISTRY_STATUS, response, 3);
if (!isHcsr04i2cResponding) { if (!isHcsr04i2cResponding) {
hcsr04i2cMeasurementCm = RANGEFINDER_HARDWARE_FAILURE; hcsr04i2cMeasurementCm = RANGEFINDER_HARDWARE_FAILURE;
return; return;
} }
if (response[HCSR04_I2C_REGISTRY_STATUS] == 0) { if (response[HCSR04_I2C_REGISTRY_STATUS] == 0) {
hcsr04i2cMeasurementCm = hcsr04i2cMeasurementCm =
(int32_t)((int32_t)response[HCSR04_I2C_REGISTRY_DISTANCE_HIGH] << 8) + (int32_t)((int32_t)response[HCSR04_I2C_REGISTRY_DISTANCE_HIGH] << 8) +
response[HCSR04_I2C_REGISTRY_DISTANCE_LOW]; response[HCSR04_I2C_REGISTRY_DISTANCE_LOW];
} else { } else {
@ -105,7 +105,7 @@ bool hcsr04i2c0Detect(rangefinderDev_t *rangefinder)
if (rangefinder->busDev == NULL) { if (rangefinder->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(rangefinder->busDev)) { if (!deviceDetect(rangefinder->busDev)) {
busDeviceDeInit(rangefinder->busDev); busDeviceDeInit(rangefinder->busDev);
return false; return false;

View file

@ -117,7 +117,7 @@ static void srf10_start_reading(rangefinderDev_t * rangefinder)
isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeLowByte, &lowByte); isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeLowByte, &lowByte);
isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeHighByte, &highByte); isSensorResponding = busRead(rangefinder->busDev, SRF10_READ_RangeHighByte, &highByte);
srf10measurementCm = highByte << 8 | lowByte; srf10measurementCm = highByte << 8 | lowByte;
if (srf10measurementCm > SRF10_MAX_RANGE_CM) { if (srf10measurementCm > SRF10_MAX_RANGE_CM) {
@ -171,7 +171,7 @@ bool srf10Detect(rangefinderDev_t * rangefinder)
if (rangefinder->busDev == NULL) { if (rangefinder->busDev == NULL) {
return false; return false;
} }
if (!deviceDetect(rangefinder->busDev)) { if (!deviceDetect(rangefinder->busDev)) {
busDeviceDeInit(rangefinder->busDev); busDeviceDeInit(rangefinder->busDev);
return false; return false;

View file

@ -21,7 +21,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/. * along with this program. If not, see http://www.gnu.org/licenses/.
*/ */
/* /*
* This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB) * This is a bridge driver between a sensor reader that operates at high level (on top of UART or UIB)
*/ */

View file

@ -28,23 +28,28 @@
#include "build/build_config.h" #include "build/build_config.h"
#include "common/utils.h" #include "common/utils.h"
#include "inverter.h"
#include "drivers/uart_inverter.h"
#include "serial.h" #include "serial.h"
#include "serial_uart.h" #include "serial_uart.h"
#include "serial_uart_impl.h" #include "serial_uart_impl.h"
static void usartConfigurePinInversion(uartPort_t *uartPort) { static void usartConfigurePinInversion(uartPort_t *uartPort) {
#if !defined(USE_INVERTER) && !defined(STM32F303xC) #if !defined(USE_UART_INVERTER) && !defined(STM32F303xC)
UNUSED(uartPort); UNUSED(uartPort);
#else #else
bool inverted = uartPort->port.options & SERIAL_INVERTED; bool inverted = uartPort->port.options & SERIAL_INVERTED;
#ifdef USE_INVERTER #ifdef USE_UART_INVERTER
if (inverted) { uartInverterLine_e invertedLines = UART_INVERTER_LINE_NONE;
// Enable hardware inverter if available. if (uartPort->port.mode & MODE_RX) {
enableInverter(uartPort->USARTx, true); invertedLines |= UART_INVERTER_LINE_RX;
} }
if (uartPort->port.mode & MODE_TX) {
invertedLines |= UART_INVERTER_LINE_TX;
}
uartInverterSet(uartPort->USARTx, invertedLines, inverted);
#endif #endif
#ifdef STM32F303xC #ifdef STM32F303xC

View file

@ -31,7 +31,6 @@
#include "common/utils.h" #include "common/utils.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "inverter.h"
#include "dma.h" #include "dma.h"
#include "serial.h" #include "serial.h"

View file

@ -51,7 +51,8 @@ void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
// cycles per microsecond // cycles per microsecond
STATIC_UNIT_TESTED timeUs_t usTicks = 0; STATIC_UNIT_TESTED timeUs_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care. // 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 timeMs_t sysTickUptime = 0;
STATIC_UNIT_TESTED volatile uint32_t sysTickValStamp = 0;
// cached value of RCC->CSR // cached value of RCC->CSR
uint32_t cachedRccCsrValue; uint32_t cachedRccCsrValue;
@ -81,6 +82,7 @@ void SysTick_Handler(void)
{ {
ATOMIC_BLOCK(NVIC_PRIO_MAX) { ATOMIC_BLOCK(NVIC_PRIO_MAX) {
sysTickUptime++; sysTickUptime++;
sysTickValStamp = SysTick->VAL;
sysTickPending = 0; sysTickPending = 0;
(void)(SysTick->CTRL); (void)(SysTick->CTRL);
} }
@ -148,12 +150,8 @@ timeUs_t micros(void)
do { do {
ms = sysTickUptime; ms = sysTickUptime;
cycle_cnt = SysTick->VAL; cycle_cnt = SysTick->VAL;
/* } while (ms != sysTickUptime || cycle_cnt > sysTickValStamp);
* 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);
return ((timeUs_t)ms * 1000LL) + (usTicks * 1000LL - (timeUs_t)cycle_cnt) / usTicks; return ((timeUs_t)ms * 1000LL) + (usTicks * 1000LL - (timeUs_t)cycle_cnt) / usTicks;
} }

View file

@ -59,7 +59,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
GPIO_StructInit(&GPIO_InitStructure); GPIO_StructInit(&GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone
GPIO_Init(GPIOA, &GPIO_InitStructure); GPIO_Init(GPIOA, &GPIO_InitStructure);

View file

@ -94,10 +94,10 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
RCC_APB1Periph_I2C1 | RCC_APB1Periph_I2C1 |
RCC_APB1Periph_I2C2 | RCC_APB1Periph_I2C2 |
RCC_APB1Periph_I2C3 | RCC_APB1Periph_I2C3 |
RCC_APB1Periph_CAN1 | // RCC_APB1Periph_CAN1 |
RCC_APB1Periph_CAN2 | // RCC_APB1Periph_CAN2 |
RCC_APB1Periph_PWR | RCC_APB1Periph_PWR |
RCC_APB1Periph_DAC | // RCC_APB1Periph_DAC |
0, ENABLE); 0, ENABLE);
RCC_APB2PeriphClockCmd( RCC_APB2PeriphClockCmd(
@ -109,7 +109,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC1 |
RCC_APB2Periph_ADC2 | RCC_APB2Periph_ADC2 |
RCC_APB2Periph_ADC3 | RCC_APB2Periph_ADC3 |
RCC_APB2Periph_SDIO | // RCC_APB2Periph_SDIO |
RCC_APB2Periph_SPI1 | RCC_APB2Periph_SPI1 |
RCC_APB2Periph_SYSCFG | RCC_APB2Periph_SYSCFG |
RCC_APB2Periph_TIM9 | RCC_APB2Periph_TIM9 |
@ -119,7 +119,7 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
GPIO_InitTypeDef GPIO_InitStructure; GPIO_InitTypeDef GPIO_InitStructure;
GPIO_StructInit(&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_All;
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone

View file

@ -58,7 +58,7 @@ uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
return i; return i;
} }
} }
// make sure final index is out of range // make sure final index is out of range
return ~1; return ~1;
} }
@ -188,9 +188,15 @@ void timerInit(void)
/* enable the timer peripherals */ /* enable the timer peripherals */
for (int i = 0; i < timerHardwareCount; i++) { for (int i = 0; i < timerHardwareCount; i++) {
unsigned timer = lookupTimerIndex(timerHardware[i].tim); unsigned timer = lookupTimerIndex(timerHardware[i].tim);
RCC_ClockCmd(timerDefinitions[timer].rcc, ENABLE); 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) const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)

View 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

View file

@ -17,10 +17,12 @@
#pragma once #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) typedef enum {
#define USE_INVERTER UART_INVERTER_LINE_NONE = 0,
#endif 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);

View file

@ -77,7 +77,7 @@ void vtxCommonSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t ch
if ((band > vtxDevice->capability.bandCount) || (channel > vtxDevice->capability.channelCount)) if ((band > vtxDevice->capability.bandCount) || (channel > vtxDevice->capability.channelCount))
return; return;
if (vtxDevice->vTable->setBandAndChannel) { if (vtxDevice->vTable->setBandAndChannel) {
vtxDevice->vTable->setBandAndChannel(vtxDevice, band, channel); vtxDevice->vTable->setBandAndChannel(vtxDevice, band, channel);
} }
@ -91,7 +91,7 @@ void vtxCommonSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
if (index > vtxDevice->capability.powerCount) if (index > vtxDevice->capability.powerCount)
return; return;
if (vtxDevice->vTable->setPowerByIndex) { if (vtxDevice->vTable->setPowerByIndex) {
vtxDevice->vTable->setPowerByIndex(vtxDevice, index); vtxDevice->vTable->setPowerByIndex(vtxDevice, index);
} }

View file

@ -47,7 +47,7 @@
#define VTX_SETTINGS_POWER_COUNT 5 #define VTX_SETTINGS_POWER_COUNT 5
#define VTX_SETTINGS_DEFAULT_POWER 1 #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_MIN_USER_FREQ 5000
#define VTX_SETTINGS_MAX_USER_FREQ 5999 #define VTX_SETTINGS_MAX_USER_FREQ 5999
#define VTX_SETTINGS_FREQCMD #define VTX_SETTINGS_FREQCMD

View file

@ -65,6 +65,7 @@ extern uint8_t __config_end;
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "fc/fc_core.h"
#include "fc/cli.h" #include "fc/cli.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
@ -352,14 +353,17 @@ static void printValuePointer(const setting_t *var, const void *valuePointer, ui
} }
break; break;
case MODE_LOOKUP: 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 { } else {
settingGetName(var, buf); settingGetName(var, buf);
cliPrintLinef("VALUE %s OUT OF RANGE", buf); cliPrintLinef("VALUE %d OUT OF RANGE FOR %s", (int)value, buf);
} }
break; break;
} }
}
} }
static bool valuePtrEqualsDefault(const setting_t *value, const void *ptr, const void *ptrDefault) 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) static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask)
{ {
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { for (unsigned i = 0; i < SETTINGS_TABLE_COUNT; i++) {
const setting_t *value = &settingsTable[i]; const setting_t *value = settingGet(i);
bufWriterFlush(cliWriter); bufWriterFlush(cliWriter);
if (SETTING_SECTION(value) == valueSection) { if (SETTING_SECTION(value) == valueSection) {
dumpPgValue(value, dumpMask); dumpPgValue(value, dumpMask);
@ -453,7 +457,7 @@ static void cliPrintVarRange(const setting_t *var)
break; break;
case MODE_LOOKUP: case MODE_LOOKUP:
{ {
const lookupTableEntry_t *tableEntry = &settingLookupTables[var->config.lookup.tableIndex]; const lookupTableEntry_t *tableEntry = settingLookupTable(var);
cliPrint("Allowed values:"); cliPrint("Allowed values:");
for (uint32_t i = 0; i < tableEntry->valueCount ; i++) { for (uint32_t i = 0; i < tableEntry->valueCount ; i++) {
if (i > 0) 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) static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const servoParam_t *defaultServoParam)
{ {
// print out servo settings // 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++) { for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
const servoParam_t *servoConf = &servoParam[i]; const servoParam_t *servoConf = &servoParam[i];
bool equalsDefault = false; bool equalsDefault = false;
@ -2020,15 +2024,7 @@ static void cliRebootEx(bool bootLoader)
bufWriterFlush(cliWriter); bufWriterFlush(cliWriter);
waitForSerialPortToFinishTransmitting(cliPort); waitForSerialPortToFinishTransmitting(cliPort);
stopMotors(); fcReboot(bootLoader);
stopPwmAllMotors();
delay(1000);
if (bootLoader) {
systemResetToBootloader();
return;
}
systemReset();
} }
static void cliReboot(void) static void cliReboot(void)
@ -2256,7 +2252,7 @@ static void cliGet(char *cmdline)
char name[SETTING_MAX_NAME_LENGTH]; char name[SETTING_MAX_NAME_LENGTH];
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
val = &settingsTable[i]; val = settingGet(i);
if (settingNameContains(val, name, cmdline)) { if (settingNameContains(val, name, cmdline)) {
cliPrintf("%s = ", name); cliPrintf("%s = ", name);
cliPrintVar(val, 0); cliPrintVar(val, 0);
@ -2288,7 +2284,7 @@ static void cliSet(char *cmdline)
if (len == 0 || (len == 1 && cmdline[0] == '*')) { if (len == 0 || (len == 1 && cmdline[0] == '*')) {
cliPrintLine("Current settings:"); cliPrintLine("Current settings:");
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) { for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
val = &settingsTable[i]; val = settingGet(i);
settingGetName(val, name); settingGetName(val, name);
cliPrintf("%s = ", 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 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++) { 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 // ensure exact match when setting to prevent setting variables with shorter names
if (settingNameIsExactMatch(val, name, cmdline, variableNameLength)) { if (settingNameIsExactMatch(val, name, cmdline, variableNameLength)) {
const setting_type_e type = SETTING_TYPE(val); const setting_type_e type = SETTING_TYPE(val);
@ -2341,7 +2337,7 @@ static void cliSet(char *cmdline)
} }
break; break;
case MODE_LOOKUP: { case MODE_LOOKUP: {
const lookupTableEntry_t *tableEntry = &settingLookupTables[settingsTable[i].config.lookup.tableIndex]; const lookupTableEntry_t *tableEntry = settingLookupTable(val);
bool matched = false; bool matched = false;
for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) { for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
matched = sl_strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0; matched = sl_strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
@ -2387,7 +2383,7 @@ static void cliStatus(char *cmdline)
{ {
UNUSED(cmdline); UNUSED(cmdline);
char buf[FORMATTED_DATE_TIME_BUFSIZE]; char buf[MAX(FORMATTED_DATE_TIME_BUFSIZE, SETTING_MAX_NAME_LENGTH)];
dateTime_t dt; dateTime_t dt;
cliPrintLinef("System Uptime: %d seconds", millis() / 1000); cliPrintLinef("System Uptime: %d seconds", millis() / 1000);
@ -2496,6 +2492,13 @@ static void cliStatus(char *cmdline)
if (bitpos > 6) cliPrintf(" %s", armingDisableFlagNames[bitpos - 7]); if (bitpos > 6) cliPrintf(" %s", armingDisableFlagNames[bitpos - 7]);
} }
cliPrintLinefeed(); cliPrintLinefeed();
if (armingFlags & ARMING_DISABLED_INVALID_SETTING) {
unsigned invalidIndex;
if (!settingsValidate(&invalidIndex)) {
settingGetName(settingGet(invalidIndex), buf);
cliPrintLinef("Invalid setting: %s", buf);
}
}
#else #else
cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS); cliPrintLinef("Arming disabled flags: 0x%lx", armingFlags & ARMING_DISABLED_ALL_FLAGS);
#endif #endif

View file

@ -73,6 +73,7 @@
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
#include "fc/rc_modes.h" #include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/settings.h"
#include "navigation/navigation.h" #include "navigation/navigation.h"
@ -283,7 +284,7 @@ void validateAndFixConfig(void)
} }
#endif #endif
#ifndef USE_PMW_SERVO_DRIVER #ifndef USE_PWM_SERVO_DRIVER
featureClear(FEATURE_PWM_SERVO_DRIVER); featureClear(FEATURE_PWM_SERVO_DRIVER);
#endif #endif
@ -323,6 +324,12 @@ void validateAndFixConfig(void)
gyroConfigMutable()->gyroSync = false; gyroConfigMutable()->gyroSync = false;
systemConfigMutable()->asyncMode = ASYNC_MODE_NONE; systemConfigMutable()->asyncMode = ASYNC_MODE_NONE;
#endif #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) void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch)

View file

@ -35,6 +35,7 @@
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/system.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensors/diagnostics.h" #include "sensors/diagnostics.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"
@ -210,7 +211,7 @@ static void updateArmingStatus(void)
else { else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED); DISABLE_ARMING_FLAG(ARMING_DISABLED_SYSTEM_OVERLOADED);
} }
#if defined(USE_NAV) #if defined(USE_NAV)
/* CHECK: Navigation safety */ /* CHECK: Navigation safety */
if (navigationBlockArming()) { if (navigationBlockArming()) {
@ -242,7 +243,7 @@ static void updateArmingStatus(void)
/* CHECK: */ /* CHECK: */
if (!isHardwareHealthy()) { if (!isHardwareHealthy()) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE); ENABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
} }
else { else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE); DISABLE_ARMING_FLAG(ARMING_DISABLED_HARDWARE_FAILURE);
} }
@ -275,7 +276,7 @@ static void updateArmingStatus(void)
/* CHECK: Do not allow arming if Servo AutoTrim is enabled */ /* CHECK: Do not allow arming if Servo AutoTrim is enabled */
if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) {
ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); ENABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
} }
else { else {
DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM); DISABLE_ARMING_FLAG(ARMING_DISABLED_SERVO_AUTOTRIM);
} }
@ -607,7 +608,7 @@ void processRx(timeUs_t currentTimeUs)
DISABLE_FLIGHT_MODE(HEADFREE_MODE); DISABLE_FLIGHT_MODE(HEADFREE_MODE);
} }
#if defined(AUTOTUNE_FIXED_WING) || defined(AUTOTUNE_MULTIROTOR) #if defined(USE_AUTOTUNE_FIXED_WING) || defined(USE_AUTOTUNE_MULTIROTOR)
autotuneUpdateState(); autotuneUpdateState();
#endif #endif
@ -706,7 +707,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
cycleTime = getTaskDeltaTime(TASK_SELF); cycleTime = getTaskDeltaTime(TASK_SELF);
dT = (float)cycleTime * 0.000001f; 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; flightTime += cycleTime;
} }
@ -833,6 +834,26 @@ void taskUpdateRxMain(timeUs_t currentTimeUs)
} }
// returns seconds // returns seconds
float getFlightTime() { float getFlightTime()
{
return (float)(flightTime / 1000) / 1000; 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);
}

View file

@ -40,3 +40,5 @@ disarmReason_t getDisarmReason(void);
bool isCalibrating(void); bool isCalibrating(void);
float getFlightTime(); float getFlightTime();
void fcReboot(bool bootLoader);

View file

@ -48,7 +48,6 @@
#include "drivers/dma.h" #include "drivers/dma.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/flash_m25p16.h" #include "drivers/flash_m25p16.h"
#include "drivers/inverter.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/io_pca9685.h" #include "drivers/io_pca9685.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
@ -69,6 +68,7 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/uart_inverter.h"
#include "drivers/vcd.h" #include "drivers/vcd.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h" #include "drivers/exti.h"
@ -199,7 +199,7 @@ void init(void)
// Re-initialize system clock to their final values (if necessary) // Re-initialize system clock to their final values (if necessary)
systemClockSetup(systemConfig()->cpuUnderclock); systemClockSetup(systemConfig()->cpuUnderclock);
i2cSetSpeed(systemConfig()->i2c_speed); i2cSetSpeed(systemConfig()->i2c_speed);
#ifdef USE_HARDWARE_PREBOOT_SETUP #ifdef USE_HARDWARE_PREBOOT_SETUP
@ -336,7 +336,7 @@ void init(void)
pwmRxInit(systemConfig()->pwmRxInputFilteringMode); pwmRxInit(systemConfig()->pwmRxInputFilteringMode);
#endif #endif
#ifdef USE_PMW_SERVO_DRIVER #ifdef USE_PWM_SERVO_DRIVER
/* /*
If external PWM driver is enabled, for example PCA9685, disable internal If external PWM driver is enabled, for example PCA9685, disable internal
servo handling mechanism, since external device will do that servo handling mechanism, since external device will do that
@ -375,8 +375,8 @@ void init(void)
lightsInit(); lightsInit();
#endif #endif
#ifdef USE_INVERTER #ifdef USE_UART_INVERTER
initInverters(); uartInverterInit();
#endif #endif
// Initialize buses // Initialize buses
@ -652,7 +652,7 @@ void init(void)
pitotStartCalibration(); pitotStartCalibration();
#endif #endif
#ifdef USE_VTX_CONTROL #if defined(USE_VTX_COMMON) && defined(USE_VTX_CONTROL)
vtxControlInit(); vtxControlInit();
#if defined(USE_VTX_COMMON) #if defined(USE_VTX_COMMON)
@ -668,13 +668,13 @@ void init(void)
vtxTrampInit(); vtxTrampInit();
#endif #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. // Now that everything has powered up the voltage and cell count be determined.
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER)) if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
batteryInit(); batteryInit();
#ifdef USE_PMW_SERVO_DRIVER #ifdef USE_PWM_SERVO_DRIVER
if (feature(FEATURE_PWM_SERVO_DRIVER)) { if (feature(FEATURE_PWM_SERVO_DRIVER)) {
pwmDriverInitialize(); pwmDriverInitialize();
} }

View file

@ -35,6 +35,8 @@
#include "common/time.h" #include "common/time.h"
#include "common/utils.h" #include "common/utils.h"
#include "config/parameter_group_ids.h"
#include "drivers/accgyro/accgyro.h" #include "drivers/accgyro/accgyro.h"
#include "drivers/bus_i2c.h" #include "drivers/bus_i2c.h"
#include "drivers/compass/compass.h" #include "drivers/compass/compass.h"
@ -47,6 +49,7 @@
#include "drivers/timer.h" #include "drivers/timer.h"
#include "drivers/vtx_common.h" #include "drivers/vtx_common.h"
#include "fc/fc_core.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
#include "fc/fc_msp.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) static void mspRebootFn(serialPort_t *serialPort)
{ {
UNUSED(serialPort); UNUSED(serialPort);
fcReboot(false);
stopMotors();
stopPwmAllMotors();
// extra delay before reboot to give ESCs chance to reset
delay(1000);
systemReset();
// control should never return here.
while (true) ;
} }
static void serializeSDCardSummaryReply(sbuf_t *dst) static void serializeSDCardSummaryReply(sbuf_t *dst)
@ -484,7 +478,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
case MSP_RC: case MSP_RC:
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) { for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
sbufWriteU16(dst, rcData[i]); sbufWriteU16(dst, rcRaw[i]);
} }
break; break;
@ -1052,7 +1046,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif #endif
#ifdef USE_ACC_NOTCH #ifdef USE_ACC_NOTCH
sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz); sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz);
sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff); sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff);
#else #else
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
@ -1060,9 +1054,9 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif #endif
#ifdef USE_GYRO_BIQUAD_RC_FIR2 #ifdef USE_GYRO_BIQUAD_RC_FIR2
sbufWriteU16(dst, gyroConfig()->gyro_stage2_lowpass_hz); sbufWriteU16(dst, gyroConfig()->gyro_stage2_lowpass_hz);
#else #else
sbufWriteU16(dst, 0); sbufWriteU16(dst, 0);
#endif #endif
break; break;
@ -1863,7 +1857,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500); gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500);
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
#endif #endif
#ifdef USE_ACC_NOTCH #ifdef USE_ACC_NOTCH
if (dataSize >= 21) { if (dataSize >= 21) {
@ -1871,14 +1865,14 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
accelerometerConfigMutable()->acc_notch_cutoff = constrain(sbufReadU16(src), 1, 255); accelerometerConfigMutable()->acc_notch_cutoff = constrain(sbufReadU16(src), 1, 255);
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
#endif #endif
#ifdef USE_GYRO_BIQUAD_RC_FIR2 #ifdef USE_GYRO_BIQUAD_RC_FIR2
if (dataSize >= 22) { if (dataSize >= 22) {
gyroConfigMutable()->gyro_stage2_lowpass_hz = constrain(sbufReadU16(src), 0, 500); gyroConfigMutable()->gyro_stage2_lowpass_hz = constrain(sbufReadU16(src), 0, 500);
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
#endif #endif
} else } else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
break; break;
@ -2571,9 +2565,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
return MSP_RESULT_ACK; 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]; char name[SETTING_MAX_NAME_LENGTH];
uint16_t id;
uint8_t c; uint8_t c;
size_t s = 0; size_t s = 0;
while (1) { while (1) {
@ -2582,6 +2577,14 @@ static const setting_t *mspReadSettingName(sbuf_t *src)
} }
name[s++] = c; name[s++] = c;
if (c == '\0') { 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; break;
} }
if (s == SETTING_MAX_NAME_LENGTH) { 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) static bool mspSettingCommand(sbuf_t *dst, sbuf_t *src)
{ {
const setting_t *setting = mspReadSettingName(src); const setting_t *setting = mspReadSetting(src);
if (!setting) { if (!setting) {
return false; return false;
} }
@ -2609,7 +2612,7 @@ static bool mspSetSettingCommand(sbuf_t *dst, sbuf_t *src)
{ {
UNUSED(dst); UNUSED(dst);
const setting_t *setting = mspReadSettingName(src); const setting_t *setting = mspReadSetting(src);
if (!setting) { if (!setting) {
return false; return false;
} }
@ -2701,6 +2704,94 @@ static bool mspSetSettingCommand(sbuf_t *dst, sbuf_t *src)
return true; 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) bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResult_e *ret)
{ {
switch (cmdMSP) { 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; *ret = mspSetSettingCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
break; 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) #if defined(USE_OSD)
case MSP2_INAV_OSD_LAYOUTS: case MSP2_INAV_OSD_LAYOUTS:
if (sbufBytesRemaining(src) >= 1) { if (sbufBytesRemaining(src) >= 1) {

View file

@ -217,7 +217,7 @@ void initActiveBoxIds(void)
activeBoxIds[activeBoxIdCount++] = BOXNAVLAUNCH; activeBoxIds[activeBoxIdCount++] = BOXNAVLAUNCH;
} }
activeBoxIds[activeBoxIdCount++] = BOXAUTOTRIM; activeBoxIds[activeBoxIdCount++] = BOXAUTOTRIM;
#if defined(AUTOTUNE_FIXED_WING) #if defined(USE_AUTOTUNE_FIXED_WING)
activeBoxIds[activeBoxIdCount++] = BOXAUTOTUNE; activeBoxIds[activeBoxIdCount++] = BOXAUTOTUNE;
#endif #endif
} }

View file

@ -101,12 +101,12 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
static timeUs_t batMonitoringLastServiced = 0; static timeUs_t batMonitoringLastServiced = 0;
timeUs_t BatMonitoringTimeSinceLastServiced = cmpTimeUs(currentTimeUs, batMonitoringLastServiced); timeUs_t BatMonitoringTimeSinceLastServiced = cmpTimeUs(currentTimeUs, batMonitoringLastServiced);
if (feature(FEATURE_CURRENT_METER)) if (isAmperageConfigured())
currentMeterUpdate(BatMonitoringTimeSinceLastServiced); currentMeterUpdate(BatMonitoringTimeSinceLastServiced);
#ifdef USE_ADC #ifdef USE_ADC
if (feature(FEATURE_VBAT)) if (feature(FEATURE_VBAT))
batteryUpdate(BatMonitoringTimeSinceLastServiced); batteryUpdate(BatMonitoringTimeSinceLastServiced);
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
powerMeterUpdate(BatMonitoringTimeSinceLastServiced); powerMeterUpdate(BatMonitoringTimeSinceLastServiced);
sagCompensatedVBatUpdate(currentTimeUs, BatMonitoringTimeSinceLastServiced); sagCompensatedVBatUpdate(currentTimeUs, BatMonitoringTimeSinceLastServiced);
} }
@ -239,7 +239,7 @@ void taskLedStrip(timeUs_t currentTimeUs)
} }
#endif #endif
#ifdef USE_PMW_SERVO_DRIVER #ifdef USE_PWM_SERVO_DRIVER
void taskSyncPwmDriver(timeUs_t currentTimeUs) void taskSyncPwmDriver(timeUs_t currentTimeUs)
{ {
UNUSED(currentTimeUs); UNUSED(currentTimeUs);
@ -306,7 +306,7 @@ void fcTasksInit(void)
#ifdef USE_LIGHTS #ifdef USE_LIGHTS
setTaskEnabled(TASK_LIGHTS, true); setTaskEnabled(TASK_LIGHTS, true);
#endif #endif
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER)); setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || isAmperageConfigured());
setTaskEnabled(TASK_TEMPERATURE, true); setTaskEnabled(TASK_TEMPERATURE, true);
setTaskEnabled(TASK_RX, true); setTaskEnabled(TASK_RX, true);
#ifdef USE_GPS #ifdef USE_GPS
@ -340,7 +340,7 @@ void fcTasksInit(void)
#ifdef STACK_CHECK #ifdef STACK_CHECK
setTaskEnabled(TASK_STACK_CHECK, true); setTaskEnabled(TASK_STACK_CHECK, true);
#endif #endif
#ifdef USE_PMW_SERVO_DRIVER #ifdef USE_PWM_SERVO_DRIVER
setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER)); setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER));
#endif #endif
#ifdef USE_OSD #ifdef USE_OSD
@ -540,7 +540,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
}, },
#endif #endif
#ifdef USE_PMW_SERVO_DRIVER #ifdef USE_PWM_SERVO_DRIVER
[TASK_PWMDRIVER] = { [TASK_PWMDRIVER] = {
.taskName = "PWMDRIVER", .taskName = "PWMDRIVER",
.taskFunc = taskSyncPwmDriver, .taskFunc = taskSyncPwmDriver,
@ -603,7 +603,7 @@ cfTask_t cfTasks[TASK_COUNT] = {
}, },
#endif #endif
#ifdef USE_VTX_CONTROL #if defined(USE_VTX_COMMON) && defined(USE_VTX_CONTROL)
[TASK_VTXCTRL] = { [TASK_VTXCTRL] = {
.taskName = "VTXCTRL", .taskName = "VTXCTRL",
.taskFunc = vtxUpdate, .taskFunc = vtxUpdate,

View file

@ -638,12 +638,18 @@ void updateAdjustmentStates(bool canUseRxData)
{ {
for (int index = 0; index < MAX_ADJUSTMENT_RANGE_COUNT; index++) { for (int index = 0; index < MAX_ADJUSTMENT_RANGE_COUNT; index++) {
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(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]; 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 (canUseRxData && isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range)) {
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig); if (!adjustmentState->config) {
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
}
} else { } else {
adjustmentState_t * const adjustmentState = &adjustmentStates[index];
if (adjustmentState->config == adjustmentConfig) { if (adjustmentState->config == adjustmentConfig) {
adjustmentState->config = NULL; adjustmentState->config = NULL;
} }

View file

@ -17,9 +17,12 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <math.h>
#include "platform.h" #include "platform.h"
#include "common/maths.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_curves.h" #include "fc/rc_curves.h"
@ -31,7 +34,7 @@
#define PITCH_LOOKUP_LENGTH 7 #define PITCH_LOOKUP_LENGTH 7
#define YAW_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 static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
int16_t lookupThrottleRCMid; // THROTTLE curve mid point 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) int16_t rcLookup(int32_t stickDeflection, uint8_t expo)
{ {
float tmpf = stickDeflection / 100.0f; 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; return lookupThrottleRC[lookupStep] + (absoluteDeflection - lookupStep * 100) * (lookupThrottleRC[lookupStep + 1] - lookupThrottleRC[lookupStep]) / 100;
} }

View file

@ -21,5 +21,5 @@ struct controlRateConfig_s;
void generateThrottleCurve(const struct controlRateConfig_s *controlRateConfig); void generateThrottleCurve(const struct controlRateConfig_s *controlRateConfig);
int16_t rcLookup(int32_t stickDeflection, uint8_t expo); 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); int16_t rcLookupThrottleMid(void);

View file

@ -34,7 +34,8 @@ static uint32_t enabledSensors = 0;
const char *armingDisableFlagNames[]= { const char *armingDisableFlagNames[]= {
"FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS", "FS", "ANGLE", "CAL", "OVRLD", "NAV", "COMPASS",
"ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX", "ACC", "ARMSW", "HWFAIL", "BOXFS", "KILLSW", "RX",
"THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM" "THR", "CLI", "CMS", "OSD", "ROLL/PITCH", "AUTOTRIM", "OOM",
"SETTINGFAIL",
}; };
#endif #endif
@ -127,6 +128,6 @@ flightModeForTelemetry_e getFlightModeForTelemetry(void)
if (FLIGHT_MODE(NAV_LAUNCH_MODE)) if (FLIGHT_MODE(NAV_LAUNCH_MODE))
return FLM_LAUNCH; return FLM_LAUNCH;
return FLM_ACRO; return FLM_ACRO;
} }

View file

@ -42,12 +42,13 @@ typedef enum {
ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23), ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23),
ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24), ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24),
ARMING_DISABLED_OOM = (1 << 25), 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_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_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_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_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; } armingFlag_e;
extern uint32_t armingFlags; extern uint32_t armingFlags;

View file

@ -77,6 +77,76 @@ const setting_t *settingFind(const char *name)
return NULL; 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) size_t settingGetValueSize(const setting_t *val)
{ {
switch (SETTING_TYPE(val)) { switch (SETTING_TYPE(val)) {
@ -154,6 +224,23 @@ setting_max_t settingGetMax(const setting_t *val)
return settingMinMaxTable[SETTING_INDEXES_GET_MAX(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) const char * settingGetString(const setting_t *val)
{ {
if (SETTING_TYPE(val) == VAR_STRING) { if (SETTING_TYPE(val) == VAR_STRING) {
@ -180,3 +267,21 @@ setting_max_t settingGetStringMaxLength(const setting_t *val)
} }
return 0; 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;
}

View file

@ -13,8 +13,6 @@ typedef struct lookupTableEntry_s {
const uint8_t valueCount; const uint8_t valueCount;
} lookupTableEntry_t; } lookupTableEntry_t;
extern const lookupTableEntry_t settingLookupTables[];
#define SETTING_TYPE_OFFSET 0 #define SETTING_TYPE_OFFSET 0
#define SETTING_SECTION_OFFSET 4 #define SETTING_SECTION_OFFSET 4
#define SETTING_MODE_OFFSET 6 #define SETTING_MODE_OFFSET 6
@ -69,8 +67,6 @@ typedef struct {
} __attribute__((packed)) setting_t; } __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_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_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; } 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 // Returns a setting_t with the exact name (case sensitive), or
// NULL if no setting with that name exists. // NULL if no setting with that name exists.
const setting_t *settingFind(const char *name); 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. // Returns the size in bytes of the setting value.
size_t settingGetValueSize(const setting_t *val); size_t settingGetValueSize(const setting_t *val);
pgn_t settingGetPgn(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 // depends on the target and build options, but will always be an unsigned
// integer (e.g. uintxx_t,) // integer (e.g. uintxx_t,)
setting_max_t settingGetMax(const setting_t *val); 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 // Returns the setting value as a const char * iff the setting is of type
// VAR_STRING. Otherwise it returns NULL. // VAR_STRING. Otherwise it returns NULL.
const char * settingGetString(const setting_t *val); const char * settingGetString(const setting_t *val);
@ -109,4 +121,8 @@ const char * settingGetString(const setting_t *val);
void settingSetString(const setting_t *val, const char *s, size_t size); void settingSetString(const setting_t *val, const char *s, size_t size);
// Returns the max string length (without counting the '\0' terminator) // Returns the max string length (without counting the '\0' terminator)
// for setting of type VAR_STRING. Otherwise it returns 0. // for setting of type VAR_STRING. Otherwise it returns 0.
setting_max_t settingGetStringMaxLength(const setting_t *val); 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);

View file

@ -10,7 +10,7 @@ tables:
values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"] values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UIB"]
enum: rangefinderType_e enum: rangefinderType_e
- name: mag_hardware - 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 enum: magSensor_e
- name: opflow_hardware - name: opflow_hardware
values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"] values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"]
@ -343,12 +343,18 @@ groups:
- name: rssi_channel - name: rssi_channel
min: 0 min: 0
max: MAX_SUPPORTED_RC_CHANNEL_COUNT max: MAX_SUPPORTED_RC_CHANNEL_COUNT
- name: rssi_scale - name: rssi_min
min: RSSI_SCALE_MIN field: rssiMin
max: RSSI_SCALE_MAX min: RSSI_VISIBLE_VALUE_MIN
- name: rssi_invert max: RSSI_VISIBLE_VALUE_MAX
field: rssiInvert - name: rssi_max
type: bool 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 - name: rc_smoothing
field: rcSmoothing field: rcSmoothing
type: bool type: bool
@ -545,6 +551,10 @@ groups:
- name: rth_energy_margin - name: rth_energy_margin
min: 0 min: 0
max: 100 max: 100
- name: thr_comp_weight
field: throttle_compensation_weight
min: 0
max: 2
- name: PG_BATTERY_PROFILES - name: PG_BATTERY_PROFILES
type: batteryProfile_t type: batteryProfile_t
@ -815,8 +825,8 @@ groups:
max: 250 max: 250
- name: 3d_deadband_throttle - name: 3d_deadband_throttle
field: deadband3d_throttle field: deadband3d_throttle
min: PWM_RANGE_MIN min: 0
max: PWM_RANGE_MAX max: 200
- name: PG_PID_PROFILE - name: PG_PID_PROFILE
type: pidProfile_t type: pidProfile_t
@ -1082,7 +1092,7 @@ groups:
- name: PG_PID_AUTOTUNE_CONFIG - name: PG_PID_AUTOTUNE_CONFIG
type: pidAutotuneConfig_t type: pidAutotuneConfig_t
condition: USE_NAV condition: USE_NAV && USE_AUTOTUNE_FIXED_WING
members: members:
- name: fw_autotune_overshoot_time - name: fw_autotune_overshoot_time
field: fw_overshoot_time field: fw_overshoot_time
@ -1102,7 +1112,7 @@ groups:
max: 100 max: 100
- name: fw_autotune_ff_to_i_tc - name: fw_autotune_ff_to_i_tc
field: fw_ff_to_i_time_constant field: fw_ff_to_i_time_constant
min: 1000 min: 100
max: 5000 max: 5000
- name: PG_POSITION_ESTIMATION_CONFIG - name: PG_POSITION_ESTIMATION_CONFIG
@ -1254,6 +1264,9 @@ groups:
field: general.min_rth_distance field: general.min_rth_distance
min: 0 min: 0
max: 5000 max: 5000
- name: nav_overrides_motor_stop
field: general.flags.auto_overrides_motor_stop
type: bool
- name: nav_rth_climb_first - name: nav_rth_climb_first
field: general.flags.rth_climb_first field: general.flags.rth_climb_first
type: bool type: bool
@ -1452,6 +1465,8 @@ groups:
- name: frsky_vfas_precision - name: frsky_vfas_precision
min: FRSKY_VFAS_PRECISION_LOW min: FRSKY_VFAS_PRECISION_LOW
max: FRSKY_VFAS_PRECISION_HIGH max: FRSKY_VFAS_PRECISION_HIGH
- name: frsky_pitch_roll
type: bool
- name: report_cell_voltage - name: report_cell_voltage
type: bool type: bool
- name: hott_alarm_sound_interval - name: hott_alarm_sound_interval
@ -1580,12 +1595,13 @@ groups:
field: main_voltage_decimals field: main_voltage_decimals
min: 1 min: 1
max: 2 max: 2
- name: osd_attitude_angle_decimals - name: osd_coordinate_digits
field: attitude_angle_decimals field: coordinate_digits
min: 0 min: 8
max: 1 max: 11
- name: osd_estimations_wind_compensation - name: osd_estimations_wind_compensation
condition: USE_WIND_ESTIMATOR
field: estimations_wind_compensation field: estimations_wind_compensation
type: bool type: bool
@ -1681,6 +1697,7 @@ groups:
- name: PG_VTX_SETTINGS_CONFIG - name: PG_VTX_SETTINGS_CONFIG
type: vtxSettingsConfig_t type: vtxSettingsConfig_t
headers: ["drivers/vtx_common.h", "io/vtx.h"] headers: ["drivers/vtx_common.h", "io/vtx.h"]
condition: defined(VTX_COMMON) || (defined(USE_CMS) && defined(USE_VTX_SMARTAUDIO))
members: members:
- name: vtx_band - name: vtx_band
field: band field: band

View file

@ -57,7 +57,7 @@ void statsOnDisarm(void)
statsConfigMutable()->stats_total_time += dt; //[s] statsConfigMutable()->stats_total_time += dt; //[s]
statsConfigMutable()->stats_total_dist += (getTotalTravelDistance() - arm_distance_cm) / 100; //[m] statsConfigMutable()->stats_total_dist += (getTotalTravelDistance() - arm_distance_cm) / 100; //[m]
#ifdef USE_ADC #ifdef USE_ADC
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) { if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
const uint32_t energy = getMWhDrawn() - arm_mWhDrawn; const uint32_t energy = getMWhDrawn() - arm_mWhDrawn;
statsConfigMutable()->stats_total_energy += energy; statsConfigMutable()->stats_total_energy += energy;
flyingEnergy += energy; flyingEnergy += energy;

View file

@ -71,13 +71,13 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
.failsafe_recovery_delay = 5, // 0.5 seconds (plus 200ms explicit delay) .failsafe_recovery_delay = 5, // 0.5 seconds (plus 200ms explicit delay)
.failsafe_off_delay = 200, // 20sec .failsafe_off_delay = 200, // 20sec
.failsafe_throttle = 1000, // default throttle off. .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_procedure = FAILSAFE_PROCEDURE_AUTO_LANDING, // default full failsafe procedure
.failsafe_fw_roll_angle = -200, // 20 deg left .failsafe_fw_roll_angle = -200, // 20 deg left
.failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive) .failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive)
.failsafe_fw_yaw_rate = -45, // 45 deg/s left yaw (left is negative, 8s for full turn) .failsafe_fw_yaw_rate = -45, // 45 deg/s left yaw (left is negative, 8s for full turn)
.failsafe_stick_motion_threshold = 50, .failsafe_stick_motion_threshold = 50,
.failsafe_min_distance = 0, // No minimum distance for failsafe by default .failsafe_min_distance = 0, // No minimum distance for failsafe by default
.failsafe_min_distance_procedure = FAILSAFE_PROCEDURE_DROP_IT // default minimum distance failsafe procedure .failsafe_min_distance_procedure = FAILSAFE_PROCEDURE_DROP_IT // default minimum distance failsafe procedure
); );
@ -400,7 +400,7 @@ void failsafeUpdateState(void)
// Craft is closer than minimum failsafe procedure distance (if set to non-zero) // Craft is closer than minimum failsafe procedure distance (if set to non-zero)
// GPS must also be working, and home position set // GPS must also be working, and home position set
if ((failsafeConfig()->failsafe_min_distance > 0) && if ((failsafeConfig()->failsafe_min_distance > 0) &&
((GPS_distanceToHome * 100) < failsafeConfig()->failsafe_min_distance) && ((GPS_distanceToHome * 100) < failsafeConfig()->failsafe_min_distance) &&
sensors(SENSOR_GPS) && STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { sensors(SENSOR_GPS) && STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
// Use the alternate, minimum distance failsafe procedure instead // Use the alternate, minimum distance failsafe procedure instead

View file

@ -507,9 +507,9 @@ static void imuCalculateEstimatedAttitude(float dT)
fpVector3_t measuredMagBF = { .v = { mag.magADC[X], mag.magADC[Y], mag.magADC[Z] } }; fpVector3_t measuredMagBF = { .v = { mag.magADC[X], mag.magADC[Y], mag.magADC[Z] } };
imuMahonyAHRSupdate(dT, &imuMeasuredRotationBF, imuMahonyAHRSupdate(dT, &imuMeasuredRotationBF,
useAcc ? &imuMeasuredAccelBF : NULL, useAcc ? &imuMeasuredAccelBF : NULL,
useMag ? &measuredMagBF : NULL, useMag ? &measuredMagBF : NULL,
useCOG, courseOverGround); useCOG, courseOverGround);
imuUpdateEulerAngles(); imuUpdateEulerAngles();

View file

@ -155,7 +155,7 @@ void mixerUsePWMIOConfiguration(void)
currentMixer[i] = *customMotorMixer(i); currentMixer[i] = *customMotorMixer(i);
motorCount++; motorCount++;
} }
// in 3D mode, mixer gain has to be halved // in 3D mode, mixer gain has to be halved
if (feature(FEATURE_3D)) { if (feature(FEATURE_3D)) {
if (motorCount > 1) { if (motorCount > 1) {
@ -312,7 +312,7 @@ void mixTable(const float dT)
// Throttle compensation based on battery voltage // Throttle compensation based on battery voltage
if (feature(FEATURE_THR_VBAT_COMP) && feature(FEATURE_VBAT) && isAmperageConfigured()) 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; throttleRange = throttleMax - throttleMin;
@ -371,11 +371,15 @@ void mixTable(const float dT)
motorStatus_e getMotorStatus(void) 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; return MOTOR_STOPPED_AUTO;
}
if ((STATE(FIXED_WING) || !isAirmodeActive()) && (!navigationIsFlyingAutonomousMode()) && (!failsafeIsActive()) && (rcData[THROTTLE] < rxConfig()->mincheck)) if (rcData[THROTTLE] < rxConfig()->mincheck) {
return MOTOR_STOPPED_USER; if ((STATE(FIXED_WING) || !isAirmodeActive()) && (!(navigationIsFlyingAutonomousMode() && navConfig()->general.flags.auto_overrides_motor_stop)) && (!failsafeIsActive())) {
return MOTOR_STOPPED_USER;
}
}
return MOTOR_RUNNING; return MOTOR_RUNNING;
} }

View file

@ -137,8 +137,8 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
.D = 0, // not used .D = 0, // not used
}, },
[PID_VEL_Z] = { [PID_VEL_Z] = {
.P = 100, // NAV_VEL_Z_P * 100 .P = 100, // NAV_VEL_Z_P * 66.7
.I = 50, // NAV_VEL_Z_I * 100 .I = 50, // NAV_VEL_Z_I * 20
.D = 10, // NAV_VEL_Z_D * 100 .D = 10, // NAV_VEL_Z_D * 100
} }
} }
@ -156,14 +156,14 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
}, },
[PID_HEADING] = { 60, 0, 0 }, [PID_HEADING] = { 60, 0, 0 },
[PID_POS_Z] = { [PID_POS_Z] = {
.P = 50, // FW_POS_Z_P * 100 .P = 40, // FW_POS_Z_P * 10
.I = 0, // not used .I = 5, // FW_POS_Z_I * 10
.D = 0, // not used .D = 10, // FW_POS_Z_D * 10
}, },
[PID_POS_XY] = { [PID_POS_XY] = {
.P = 75, // FW_NAV_P * 100 .P = 75, // FW_POS_XY_P * 100
.I = 5, // FW_NAV_I * 100 .I = 5, // FW_POS_XY_I * 100
.D = 8, // FW_NAV_D * 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); 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)) { if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) {
autotuneFixedWingUpdate(axis, pidState->rateTarget, pidState->gyroRate, newPTerm + newFFTerm); autotuneFixedWingUpdate(axis, pidState->rateTarget, pidState->gyroRate, newPTerm + newFFTerm);
} }

View file

@ -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 #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 tuneCurrent[XYZ_AXIS_COUNT];
static pidAutotuneData_t tuneSaved[XYZ_AXIS_COUNT]; static pidAutotuneData_t tuneSaved[XYZ_AXIS_COUNT];
@ -159,7 +159,7 @@ static void blackboxLogAutotuneEvent(adjustmentFunction_e adjustmentFunction, in
#endif #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) void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRateDps, float reachedRateDps, float pidOutput)
{ {

View file

@ -2,6 +2,7 @@
#include "build/debug.h" #include "build/debug.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/utils.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/fc_core.h" #include "fc/fc_core.h"
@ -111,14 +112,15 @@ static uint16_t estimateRTHAltitudeChangeEnergy(float altitudeChange, float vert
} }
// returns distance in m // returns distance in m
// *heading is in degrees // *heading is in degrees
static float estimateRTHDistanceAndHeadingAfterAltitudeChange(float altitudeChange, float horizontalWindSpeed, float windHeading, float verticalWindSpeed, float *heading) { static float estimateRTHDistanceAndHeadingAfterAltitudeChange(float altitudeChange, float horizontalWindSpeed, float windHeading, float verticalWindSpeed, float *heading) {
float estimatedAltitudeChangeGroundDistance = estimateRTHAltitudeChangeGroundDistance(altitudeChange, horizontalWindSpeed, windHeading, verticalWindSpeed); 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 headingDiff = DEGREES_TO_RADIANS(DECIDEGREES_TO_DEGREES((float)attitude.values.yaw) - GPS_directionToHome);
float triangleAltitude = GPS_distanceToHome * sin_approx(headingDiff); float triangleAltitude = GPS_distanceToHome * sin_approx(headingDiff);
float triangleAltitudeToReturnStart = estimatedAltitudeChangeGroundDistance - GPS_distanceToHome * cos_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)); return sqrt(sq(triangleAltitude) + sq(triangleAltitudeToReturnStart));
} else { } else {
*heading = GPS_directionToHome; *heading = GPS_directionToHome;
@ -132,13 +134,24 @@ static int32_t calculateRemainingEnergyBeforeRTH(bool takeWindIntoAccount) {
if (!STATE(FIXED_WING)) if (!STATE(FIXED_WING))
return -1; 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; return -1;
#ifdef USE_WIND_ESTIMATOR
uint16_t windHeading; // centidegrees uint16_t windHeading; // centidegrees
const float horizontalWindSpeed = takeWindIntoAccount ? getEstimatedHorizontalWindSpeed(&windHeading) / 100 : 0; // m/s const float horizontalWindSpeed = takeWindIntoAccount ? getEstimatedHorizontalWindSpeed(&windHeading) / 100 : 0; // m/s
const float windHeadingDegrees = CENTIDEGREES_TO_DEGREES((float)windHeading); const float windHeadingDegrees = CENTIDEGREES_TO_DEGREES((float)windHeading);
const float verticalWindSpeed = getEstimatedWindSpeed(Z) / 100; 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; const float RTH_altitude_change = (RTHAltitude() - getEstimatedActualPosition(Z)) / 100;
float RTH_heading; // degrees float RTH_heading; // degrees

View file

@ -177,6 +177,7 @@ static void filterServos(void)
if (!servoFilterIsSet) { if (!servoFilterIsSet) {
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) { for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
biquadFilterInitLPF(&servoFilter[i], servoConfig()->servo_lowpass_freq, gyro.targetLooptime); biquadFilterInitLPF(&servoFilter[i], servoConfig()->servo_lowpass_freq, gyro.targetLooptime);
biquadFilterReset(&servoFilter[i], servo[i]);
} }
servoFilterIsSet = true; servoFilterIsSet = true;
} }
@ -230,7 +231,7 @@ void servoMixer(float dT)
input[INPUT_STABILIZED_YAW] = axisPID[YAW]; input[INPUT_STABILIZED_YAW] = axisPID[YAW];
// Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter // Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter
if (feature(FEATURE_3D) && (rcData[THROTTLE] < PWM_RANGE_MIDDLE) && if (feature(FEATURE_3D) && (rcData[THROTTLE] < PWM_RANGE_MIDDLE) &&
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) { (mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) {
input[INPUT_STABILIZED_YAW] *= -1; input[INPUT_STABILIZED_YAW] *= -1;
} }

View file

@ -21,7 +21,6 @@
#if !defined(USE_GPS) #if !defined(USE_GPS)
#error Wind Estimator requires GPS support #error Wind Estimator requires GPS support
#endif #endif
#endif
#include "common/axis.h" #include "common/axis.h"
#include "common/time.h" #include "common/time.h"
@ -34,3 +33,5 @@ float getEstimatedWindSpeed(int axis);
float getEstimatedHorizontalWindSpeed(uint16_t *angle); float getEstimatedHorizontalWindSpeed(uint16_t *angle);
void updateWindEstimator(timeUs_t currentTimeUs); void updateWindEstimator(timeUs_t currentTimeUs);
#endif

View file

@ -2605,7 +2605,7 @@ static void afatfs_createFileContinue(afatfsFile_t *file)
memcpy(entry->filename, opState->filename, FAT_FILENAME_LENGTH); memcpy(entry->filename, opState->filename, FAT_FILENAME_LENGTH);
entry->attrib = file->attrib; entry->attrib = file->attrib;
if (rtcGetDateTime(&now)) { if (rtcGetDateTimeLocal(&now)) {
entry->creationDate = FAT_MAKE_DATE(now.year, now.month, now.day); entry->creationDate = FAT_MAKE_DATE(now.year, now.month, now.day);
entry->creationTime = FAT_MAKE_TIME(now.hours, now.minutes, now.seconds); entry->creationTime = FAT_MAKE_TIME(now.hours, now.minutes, now.seconds);
} else { } else {

View file

@ -126,12 +126,12 @@ static const uint8_t beep_hardwareFailure[] = {
10, 10, BEEPER_COMMAND_STOP 10, 10, BEEPER_COMMAND_STOP
}; };
// Cam connection opened // Cam connection opened
static const uint8_t beep_camOpenBeep[] = { static const uint8_t beep_camOpenBeep[] = {
5, 15, 10, 15, 20, BEEPER_COMMAND_STOP 5, 15, 10, 15, 20, BEEPER_COMMAND_STOP
}; };
// Cam connection close // Cam connection close
static const uint8_t beep_camCloseBeep[] = { static const uint8_t beep_camCloseBeep[] = {
10, 8, 5, BEEPER_COMMAND_STOP 10, 8, 5, BEEPER_COMMAND_STOP
}; };

View file

@ -43,8 +43,8 @@ typedef enum {
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
BEEPER_USB, // Some boards have beeper powered USB connected BEEPER_USB, // Some boards have beeper powered USB connected
BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled
BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated
BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop
BEEPER_ALL, // Turn ON or OFF all beeper conditions BEEPER_ALL, // Turn ON or OFF all beeper conditions
BEEPER_PREFERENCE, // Save preferred beeper configuration BEEPER_PREFERENCE, // Save preferred beeper configuration

View file

@ -129,7 +129,7 @@ static bool cxofOpflowUpdate(opflowData_t * data)
bufferPtr = 0; bufferPtr = 0;
} }
} }
if (newPacket) { if (newPacket) {
*data = tmpData; *data = tmpData;
} }

View file

@ -62,14 +62,15 @@
#include "io/osd.h" #include "io/osd.h"
#include "io/vtx_string.h" #include "io/vtx_string.h"
#include "fc/fc_core.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
#include "fc/fc_core.h"
#include "fc/fc_tasks.h"
#include "fc/rc_adjustments.h" #include "fc/rc_adjustments.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h" #include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/fc_tasks.h" #include "fc/settings.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/mixer.h" #include "flight/mixer.h"
@ -479,36 +480,34 @@ static inline void osdFormatFlyTime(char *buff, textAttributes_t *attr)
*/ */
static uint16_t osdConvertRSSI(void) static uint16_t osdConvertRSSI(void)
{ {
uint16_t osdRssi = getRSSI() * 100 / 1024; // change range // change range to [0, 99]
if (osdRssi >= 100) { return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99);
osdRssi = 99;
}
return osdRssi;
} }
static void osdFormatCoordinate(char *buff, char sym, int32_t val) 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; buff[0] = sym;
int32_t integerPart = val / GPS_DEGREES_DIVIDER; int32_t integerPart = val / GPS_DEGREES_DIVIDER;
int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
// Latitude maximum integer width is 3 (-90) while // Latitude maximum integer width is 3 (-90) while
// longitude maximum integer width is 4 (-180). We always // longitude maximum integer width is 4 (-180).
// show 7 decimals, so we need to use 11 spaces because int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", integerPart);
// we're embedding the decimal separator between the // We can show up to 7 digits in decimalPart.
// two numbers. int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
int written = tfp_sprintf(buff + 1, "%d", integerPart); STATIC_ASSERT(GPS_DEGREES_DIVIDER == 1e7, adjust_max_decimal_digits);
tfp_sprintf(buff + 1 + written, "%07d", decimalPart); int decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%07d", decimalPart);
// Embbed the decimal separator // Embbed the decimal separator
buff[1+written-1] += SYM_ZERO_HALF_TRAILING_DOT - '0'; buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
buff[1+written] += SYM_ZERO_HALF_LEADING_DOT - '0'; buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0';
// Pad to 11 coordinateMaxLength // Fill up to coordinateLength with zeros
while(1 + 7 + written < coordinateMaxLength) { int total = 1 + integerDigits + decimalDigits;
buff[1 + 7 + written] = SYM_BLANK; while(total < coordinateLength) {
written++; buff[total] = '0';
total++;
} }
buff[coordinateMaxLength] = '\0'; buff[coordinateLength] = '\0';
} }
// Used twice, make sure it's exactly the same string // 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"); return OSD_MESSAGE_STR("AUTOTRIM IS ACTIVE");
case ARMING_DISABLED_OOM: case ARMING_DISABLED_OOM:
return OSD_MESSAGE_STR("NOT ENOUGH MEMORY"); return OSD_MESSAGE_STR("NOT ENOUGH MEMORY");
case ARMING_DISABLED_INVALID_SETTING:
return OSD_MESSAGE_STR("INVALID SETTING");
case ARMING_DISABLED_CLI: case ARMING_DISABLED_CLI:
return OSD_MESSAGE_STR("CLI IS ACTIVE"); return OSD_MESSAGE_STR("CLI IS ACTIVE");
// Cases without message // Cases without message
@ -681,7 +682,10 @@ static const char * navigationStateMessage(void)
// Not used // Not used
break; break;
case MW_NAV_STATE_LAND_START: 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: case MW_NAV_STATE_LAND_IN_PROGRESS:
return OSD_MESSAGE_STR("LANDING"); return OSD_MESSAGE_STR("LANDING");
case MW_NAV_STATE_HOVER_ABOVE_HOME: 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 symUnscaled;
char symScaled; char symScaled;
int maxDecimals; 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 // 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 // between the center and the closers map edge, to avoid too much jumping
const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2; 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); float poiCos = cos_approx(poiAngle);
// Now start looking for a valid scale that lets us draw everything // 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 // Calculate location of the aircraft in map
int points = poiDistance / (float)(scale / charHeight); int points = poiDistance / ((float)scale / charHeight);
float pointsX = points * poiSin; float pointsX = points * poiSin;
int poiX = midX - roundf(pointsX / charWidth); int poiX = midX - roundf(pointsX / charWidth);
if (poiX < minX || poiX > maxX) { if (poiX < minX || poiX > maxX) {
scale *= scaleMultiplier;
continue; continue;
} }
float pointsY = points * poiCos; float pointsY = points * poiCos;
int poiY = midY + roundf(pointsY / charHeight); int poiY = midY + roundf(pointsY / charHeight);
if (poiY < minY || poiY > maxY) { if (poiY < minY || poiY > maxY) {
scale *= scaleMultiplier;
continue; continue;
} }
@ -987,9 +994,21 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
} else { } else {
uint8_t c; 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 // Something else written here, increase scale. If the display doesn't support reading
// back characters, we assume there's nothing. // 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; continue;
} }
} }
@ -1036,17 +1055,17 @@ static void osdDrawRadar(uint16_t *drawn, uint32_t *usedScale)
#endif #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); strcpy(buff, label);
uint8_t label_len = strlen(label); for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' ';
for (uint8_t i = label_len; i < 5; ++i) buff[i] = ' '; uint8_t decimals = showDecimal ? 1 : 0;
osdFormatCentiNumber(buff + 5, pidController->proportional, 0, 1, 0, 4); osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4);
buff[9] = ' '; buff[9] = ' ';
osdFormatCentiNumber(buff + 10, pidController->integrator, 0, 1, 0, 4); osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4);
buff[14] = ' '; buff[14] = ' ';
osdFormatCentiNumber(buff + 15, pidController->derivative, 0, 1, 0, 4); osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4);
buff[19] = ' '; 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'; buff[24] = '\0';
} }
@ -1210,14 +1229,23 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_HOME_DIR: case OSD_HOME_DIR:
{ {
// There are 16 orientations for the home direction arrow. if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) {
// so we use 22.5deg per image, where the 1st image is used // There are 16 orientations for the home direction arrow.
// for [349, 11], the 2nd for [12, 33], etc... // so we use 22.5deg per image, where the 1st image is used
int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading()); // for [349, 11], the 2nd for [12, 33], etc...
// Add 11 to the angle, so first character maps to [349, 11] int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading());
int homeArrowDir = osdGetHeadingAngle(homeDirection + 11); // Add 11 to the angle, so first character maps to [349, 11]
unsigned arrowOffset = homeArrowDir * 2 / 45; int homeArrowDir = osdGetHeadingAngle(homeDirection + 11);
buff[0] = SYM_ARROW_UP + arrowOffset; 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; buff[1] = 0;
break; break;
} }
@ -1552,19 +1580,19 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_ATTITUDE_ROLL: case OSD_ATTITUDE_ROLL:
buff[0] = SYM_ROLL_LEVEL; 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); 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; break;
case OSD_ATTITUDE_PITCH: case OSD_ATTITUDE_PITCH:
if (ABS(attitude.values.pitch) < (osdConfig()->attitude_angle_decimals ? 1 : 10)) if (ABS(attitude.values.pitch) < 1)
buff[0] = 'P'; buff[0] = 'P';
else if (attitude.values.pitch > 0) else if (attitude.values.pitch > 0)
buff[0] = SYM_PITCH_DOWN; buff[0] = SYM_PITCH_DOWN;
else if (attitude.values.pitch < 0) else if (attitude.values.pitch < 0)
buff[0] = SYM_PITCH_UP; 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; break;
case OSD_ARTIFICIAL_HORIZON: case OSD_ARTIFICIAL_HORIZON:
@ -1601,7 +1629,7 @@ static bool osdDrawSingleElement(uint8_t item)
osdCrosshairsBounds(&cx, &cy, &cl); osdCrosshairsBounds(&cx, &cy, &cl);
crosshairsX = cx - elemPosX; crosshairsX = cx - elemPosX;
crosshairsY = cy - elemPosY; crosshairsY = cy - elemPosY;
crosshairsXEnd = crosshairsX + cl; crosshairsXEnd = crosshairsX + cl - 1;
} }
for (int x = -4; x <= 4; x++) { 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 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 pwy = writtenY[wx]; // previously written Y at this X value
int wy = (y / AH_SYMBOL_COUNT); 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 && bool overlaps = (crosshairsVisible &&
crosshairsY == wy && 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 (y >= 0 && y <= 80 && !overlaps) {
if (pwy != -1 && pwy != wy) { if (pwy != -1 && pwy != wy) {
// Erase previous character at pwy rows below elemPosY // Erase previous character at pwy rows below elemPosY
// iff we're writing at a different Y coordinate. Otherwise // iff we're writing at a different Y coordinate. Otherwise
// we just overwrite the previous one. // 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); 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; writtenY[wx] = wy;
} else { } else {
if (pwy != -1) { if (pwy != -1) {
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + pwy, SYM_BLANK); displayWriteChar(osdDisplayPort, chX, elemPosY + pwy, SYM_BLANK);
writtenY[wx] = -1; writtenY[wx] = -1;
} }
} }
@ -1888,35 +1923,35 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_FW_ALT_PID_OUTPUTS: case OSD_FW_ALT_PID_OUTPUTS:
{ {
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); 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; break;
} }
case OSD_FW_POS_PID_OUTPUTS: case OSD_FW_POS_PID_OUTPUTS:
{ {
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees
osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav); osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true);
break; break;
} }
case OSD_MC_VEL_Z_PID_OUTPUTS: case OSD_MC_VEL_Z_PID_OUTPUTS:
{ {
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); 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; break;
} }
case OSD_MC_VEL_X_PID_OUTPUTS: case OSD_MC_VEL_X_PID_OUTPUTS:
{ {
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); 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; break;
} }
case OSD_MC_VEL_Y_PID_OUTPUTS: case OSD_MC_VEL_Y_PID_OUTPUTS:
{ {
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); 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; break;
} }
@ -1924,11 +1959,12 @@ static bool osdDrawSingleElement(uint8_t item)
{ {
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
strcpy(buff, "POSO "); 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] = ' '; 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] = ' '; 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'; buff[19] = '\0';
break; break;
} }
@ -1955,9 +1991,7 @@ static bool osdDrawSingleElement(uint8_t item)
{ {
// RTC not configured will show 00:00 // RTC not configured will show 00:00
dateTime_t dateTime; dateTime_t dateTime;
if (rtcGetDateTime(&dateTime)) { rtcGetDateTimeLocal(&dateTime);
dateTimeUTCToLocal(&dateTime, &dateTime);
}
buff[0] = SYM_CLOCK; buff[0] = SYM_CLOCK;
tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes); tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes);
break; break;
@ -1966,6 +2000,7 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_MESSAGES: case OSD_MESSAGES:
{ {
const char *message = NULL; const char *message = NULL;
char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)];
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
// Aircraft is armed. We might have up to 4 // Aircraft is armed. We might have up to 4
// messages to show. // messages to show.
@ -2000,7 +2035,7 @@ static bool osdDrawSingleElement(uint8_t item)
// will cause it to be missing from some frames. // will cause it to be missing from some frames.
} }
} else { } 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(); const char *navStateMessage = navigationStateMessage();
if (navStateMessage) { if (navStateMessage) {
messages[messageCount++] = navStateMessage; messages[messageCount++] = navStateMessage;
@ -2030,13 +2065,28 @@ static bool osdDrawSingleElement(uint8_t item)
} }
} }
} else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) { } else if (ARMING_FLAG(ARMING_DISABLED_ALL_FLAGS)) {
unsigned invalidIndex;
// Check if we're unable to arm for some reason // Check if we're unable to arm for some reason
if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) { if (ARMING_FLAG(ARMING_DISABLED_INVALID_SETTING) && !settingsValidate(&invalidIndex)) {
message = "UNABLE TO ARM"; if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) {
TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr); 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 { } else {
// Show the reason for not arming if (OSD_ALTERNATING_CHOICES(1000, 2) == 0) {
message = osdArmingDisabledReasonMessage(); message = "UNABLE TO ARM";
TEXT_ATTRIBUTES_ADD_INVERTED(elemAttr);
} else {
// Show the reason for not arming
message = osdArmingDisabledReasonMessage();
}
} }
} }
osdFormatMessage(buff, sizeof(buff), message); osdFormatMessage(buff, sizeof(buff), message);
@ -2422,9 +2472,9 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
osdConfig->units = OSD_UNIT_METRIC; osdConfig->units = OSD_UNIT_METRIC;
osdConfig->main_voltage_decimals = 1; osdConfig->main_voltage_decimals = 1;
osdConfig->attitude_angle_decimals = 0;
osdConfig->estimations_wind_compensation = true; osdConfig->estimations_wind_compensation = true;
osdConfig->coordinate_digits = 9;
} }
static void osdSetNextRefreshIn(uint32_t timeMs) { static void osdSetNextRefreshIn(uint32_t timeMs) {
@ -2652,13 +2702,21 @@ static void osdShowArmed(void)
displayWrite(osdDisplayPort, 12, y, "ARMED"); displayWrite(osdDisplayPort, 12, y, "ARMED");
y += 2; y += 2;
if (STATE(GPS_FIX)) { #if defined(USE_GPS)
osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat); if (feature(FEATURE_GPS)) {
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); if (STATE(GPS_FIX_HOME)) {
osdFormatCoordinate(buf, SYM_LON, gpsSol.llh.lon); osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat);
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf);
y += 3; 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)) { if (rtcGetDateTime(&dt)) {
dateTimeFormatLocal(buf, &dt); dateTimeFormatLocal(buf, &dt);
@ -2671,7 +2729,11 @@ static void osdShowArmed(void)
static void osdRefresh(timeUs_t currentTimeUs) static void osdRefresh(timeUs_t currentTimeUs)
{ {
#ifdef USE_CMS
if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu)) { if (IS_RC_MODE_ACTIVE(BOXOSD) && (!cmsInMenu)) {
#else
if (IS_RC_MODE_ACTIVE(BOXOSD)) {
#endif
displayClearScreen(osdDisplayPort); displayClearScreen(osdDisplayPort);
armState = ARMING_FLAG(ARMED); armState = ARMING_FLAG(ARMED);
return; return;

View file

@ -163,7 +163,6 @@ typedef struct osdConfig_s {
// Preferences // Preferences
uint8_t main_voltage_decimals; uint8_t main_voltage_decimals;
uint8_t attitude_angle_decimals;
uint8_t ahi_reverse_roll; uint8_t ahi_reverse_roll;
uint8_t crosshairs_style; // from osd_crosshairs_style_e uint8_t crosshairs_style; // from osd_crosshairs_style_e
uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_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 uint8_t stats_energy_unit; // from osd_stats_energy_unit_e
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
uint8_t coordinate_digits;
} osdConfig_t; } osdConfig_t;
PG_DECLARE(osdConfig_t, osdConfig); PG_DECLARE(osdConfig_t, osdConfig);

View file

@ -122,7 +122,7 @@ static uint8_t runcamDeviceReceivePacket(runcamDevice_t *device, uint8_t command
if (!runcamDeviceIsResponseReceiveDone(command, data, dataPos, &isDone)) { if (!runcamDeviceIsResponseReceiveDone(command, data, dataPos, &isDone)) {
return 0; return 0;
} }
if (isDone) { if (isDone) {
responseDataLen = dataPos; responseDataLen = dataPos;
break; break;
@ -184,11 +184,11 @@ static void runcamDeviceSendPacket(runcamDevice_t *device, uint8_t command, uint
static bool runcamDeviceSendRequestAndWaitingResp(runcamDevice_t *device, uint8_t commandID, uint8_t *paramData, uint8_t paramDataLen, uint8_t *outputBuffer, uint8_t *outputBufferLen) static bool runcamDeviceSendRequestAndWaitingResp(runcamDevice_t *device, uint8_t commandID, uint8_t *paramData, uint8_t paramDataLen, uint8_t *outputBuffer, uint8_t *outputBufferLen)
{ {
int max_retries = 1; int max_retries = 1;
// here using 1000ms as timeout, because the response from 5 key simulation command need a long time about >= 600ms, // here using 1000ms as timeout, because the response from 5 key simulation command need a long time about >= 600ms,
// so set a max value to ensure we can receive the response // so set a max value to ensure we can receive the response
int timeoutMs = 1000; int timeoutMs = 1000;
// only the command sending on initializing step need retry logic, // only the command sending on initializing step need retry logic,
// otherwise, the timeout of 1000 ms is enough for the response from device // otherwise, the timeout of 1000 ms is enough for the response from device
if (commandID == RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO) { if (commandID == RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO) {
max_retries = 3; max_retries = 3;
@ -256,7 +256,7 @@ static void sendCtrlCommand(runcamDevice_t *device, rcsplit_ctrl_argument_e argu
// get the device info(firmware version, protocol version and features, see the // get the device info(firmware version, protocol version and features, see the
// definition of runcamDeviceInfo_t to know more) // definition of runcamDeviceInfo_t to know more)
static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuffer) static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuffer)
{ {
// Send "who are you" command to device to detect the device whether is running RCSplit FW1.0 or RCSplit FW1.1 // Send "who are you" command to device to detect the device whether is running RCSplit FW1.0 or RCSplit FW1.1
uint32_t max_retries = 3; uint32_t max_retries = 3;
@ -303,7 +303,7 @@ static bool runcamDeviceGetDeviceInfo(runcamDevice_t *device, uint8_t *outputBuf
} }
} }
return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, NULL, 0, outputBuffer, NULL); return runcamDeviceSendRequestAndWaitingResp(device, RCDEVICE_PROTOCOL_COMMAND_GET_DEVICE_INFO, NULL, 0, outputBuffer, NULL);
} }
static bool runcamDeviceSend5KeyOSDCableConnectionEvent(runcamDevice_t *device, uint8_t operation, uint8_t *outActionID, uint8_t *outErrorCode) static bool runcamDeviceSend5KeyOSDCableConnectionEvent(runcamDevice_t *device, uint8_t operation, uint8_t *outActionID, uint8_t *outErrorCode)
@ -434,13 +434,13 @@ static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDeta
outSettingDetail->stepSize = sbufReadU8(buf); outSettingDetail->stepSize = sbufReadU8(buf);
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_UINT16: case RCDEVICE_PROTOCOL_SETTINGTYPE_UINT16:
case RCDEVICE_PROTOCOL_SETTINGTYPE_INT16: case RCDEVICE_PROTOCOL_SETTINGTYPE_INT16:
outSettingDetail->value = sbufReadU16(buf); outSettingDetail->value = sbufReadU16(buf);
outSettingDetail->minValue = sbufReadU16(buf); outSettingDetail->minValue = sbufReadU16(buf);
outSettingDetail->maxValue = sbufReadU16(buf); outSettingDetail->maxValue = sbufReadU16(buf);
outSettingDetail->stepSize = sbufReadU8(buf); outSettingDetail->stepSize = sbufReadU8(buf);
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_FLOAT: case RCDEVICE_PROTOCOL_SETTINGTYPE_FLOAT:
outSettingDetail->value = sbufReadU32(buf); outSettingDetail->value = sbufReadU32(buf);
outSettingDetail->minValue = sbufReadU32(buf); outSettingDetail->minValue = sbufReadU32(buf);
outSettingDetail->maxValue = sbufReadU32(buf); outSettingDetail->maxValue = sbufReadU32(buf);
@ -470,7 +470,7 @@ static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDeta
result = strtok_r(NULL, delims, &saveptr); result = strtok_r(NULL, delims, &saveptr);
i++; i++;
} }
} }
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_STRING: { case RCDEVICE_PROTOCOL_SETTINGTYPE_STRING: {
const char *tmp = (const char *)sbufConstPtr(buf); const char *tmp = (const char *)sbufConstPtr(buf);
@ -478,7 +478,7 @@ static bool runcamDeviceDecodeSettingDetail(sbuf_t *buf, runcamDeviceSettingDeta
sbufAdvance(buf, strlen(tmp) + 1); sbufAdvance(buf, strlen(tmp) + 1);
outSettingDetail->maxStringSize = sbufReadU8(buf); outSettingDetail->maxStringSize = sbufReadU8(buf);
} }
break; break;
case RCDEVICE_PROTOCOL_SETTINGTYPE_FOLDER: case RCDEVICE_PROTOCOL_SETTINGTYPE_FOLDER:
break; break;
@ -586,7 +586,7 @@ bool runcamDeviceWriteSetting(runcamDevice_t *device, uint8_t settingID, const v
} }
memset(response, 0, sizeof(runcamDeviceWriteSettingResponse_t)); memset(response, 0, sizeof(runcamDeviceWriteSettingResponse_t));
response->resultCode = 1; // initialize the result code to failed response->resultCode = 1; // initialize the result code to failed
uint8_t paramsBufLen = sizeof(uint8_t) + paramDataLen; uint8_t paramsBufLen = sizeof(uint8_t) + paramDataLen;
uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE]; uint8_t paramsBuf[RCDEVICE_PROTOCOL_MAX_DATA_SIZE];

View file

@ -81,9 +81,9 @@ typedef enum {
} rcdevice_5key_simulation_operation_e; } rcdevice_5key_simulation_operation_e;
// Operation of RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION // Operation of RCDEVICE_PROTOCOL_COMMAND_5KEY_CONNECTION
typedef enum { typedef enum {
RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01, RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01,
RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02 RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02
} RCDEVICE_5key_connection_event_e; } RCDEVICE_5key_connection_event_e;
typedef enum { typedef enum {

View file

@ -100,7 +100,7 @@ static void rcdeviceCameraUpdateTime(void)
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS) && if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS) &&
!hasSynchronizedTime && retries < 3) { !hasSynchronizedTime && retries < 3) {
if (rtcGetDateTime(&dt)) { if (rtcGetDateTimeLocal(&dt)) {
retries++; retries++;
tfp_sprintf(buf, "%04d%02d%02dT%02d%02d%02d.0", tfp_sprintf(buf, "%04d%02d%02dT%02d%02d%02d.0",
dt.year, dt.month, dt.day, dt.year, dt.month, dt.day,

View file

@ -200,7 +200,7 @@ static void saPrintSettings(void)
int saDacToPowerIndex(int dac) 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) { if (saPowerTable[idx].valueV1 <= dac) {
return idx; return idx;
} }
@ -447,6 +447,11 @@ static void saSendFrame(uint8_t *buf, int len)
serialWrite(smartAudioSerialPort, buf[i]); 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(); sa_lastTransmissionMs = millis();
saStat.pktsent++; saStat.pktsent++;
} }

View file

@ -60,7 +60,7 @@ static vtxDevice_t vtxTramp = {
.vTable = &trampVTable, .vTable = &trampVTable,
.capability.bandCount = VTX_TRAMP_BAND_COUNT, .capability.bandCount = VTX_TRAMP_BAND_COUNT,
.capability.channelCount = VTX_TRAMP_CHANNEL_COUNT, .capability.channelCount = VTX_TRAMP_CHANNEL_COUNT,
.capability.powerCount = sizeof(trampPowerTable), .capability.powerCount = VTX_TRAMP_POWER_COUNT,
.bandNames = (char **)vtx58BandNames, .bandNames = (char **)vtx58BandNames,
.channelNames = (char **)vtx58ChannelNames, .channelNames = (char **)vtx58ChannelNames,
.powerNames = (char **)trampPowerNames, .powerNames = (char **)trampPowerNames,
@ -196,7 +196,7 @@ bool trampCommitChanges(void)
// return false if index out of range // return false if index out of range
static bool trampDevSetPowerByIndex(uint8_t index) static bool trampDevSetPowerByIndex(uint8_t index)
{ {
if (index > 0 && index <= sizeof(trampPowerTable)) { if (index > 0 && index <= VTX_TRAMP_POWER_COUNT) {
trampSetRFPower(trampPowerTable[index - 1]); trampSetRFPower(trampPowerTable[index - 1]);
trampCommitChanges(); trampCommitChanges();
return true; return true;

View file

@ -15,10 +15,13 @@
* along with INAV. If not, see <http://www.gnu.org/licenses/>. * along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/ */
#define MSP2_COMMON_TZ 0x1001 //out message Gets the TZ offset for the local time (returns: minutes(i16)) #define MSP2_COMMON_TZ 0x1001 //out message Gets the TZ offset for the local time (returns: minutes(i16))
#define MSP2_COMMON_SET_TZ 0x1002 //in message Sets the TZ offset for the local time (args: minutes(i16)) #define MSP2_COMMON_SET_TZ 0x1002 //in message Sets the TZ offset for the local time (args: minutes(i16))
#define MSP2_COMMON_SETTING 0x1003 //in/out message Returns the value for a setting #define MSP2_COMMON_SETTING 0x1003 //in/out message Returns the value for a setting
#define MSP2_COMMON_SET_SETTING 0x1004 //in message Sets the value for a setting #define MSP2_COMMON_SET_SETTING 0x1004 //in message Sets the value for a setting
#define MSP2_COMMON_MOTOR_MIXER 0x1005 #define MSP2_COMMON_MOTOR_MIXER 0x1005
#define MSP2_COMMON_SET_MOTOR_MIXER 0x1006 #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

View file

@ -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); PG_REGISTER_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList, PG_WAYPOINT_MISSION_STORAGE, 0);
#endif #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, PG_RESET_TEMPLATE(navConfig_t, navConfig,
.general = { .general = {
@ -92,6 +92,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.rth_tail_first = 0, .rth_tail_first = 0,
.disarm_on_landing = 0, .disarm_on_landing = 0,
.rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS, .rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS,
.auto_overrides_motor_stop = 1,
}, },
// General navigation parameters // General navigation parameters
@ -170,7 +171,7 @@ int16_t navActualVelocity[3];
int16_t navDesiredVelocity[3]; int16_t navDesiredVelocity[3];
int16_t navActualHeading; int16_t navActualHeading;
int16_t navDesiredHeading; int16_t navDesiredHeading;
int16_t navTargetPosition[3]; int32_t navTargetPosition[3];
int32_t navLatestActualPosition[3]; int32_t navLatestActualPosition[3];
int16_t navActualSurface; int16_t navActualSurface;
uint16_t navFlags; uint16_t navFlags;
@ -508,7 +509,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
[NAV_STATE_RTH_HOVER_ABOVE_HOME] = { [NAV_STATE_RTH_HOVER_ABOVE_HOME] = {
.persistentId = NAV_PERSISTENT_ID_RTH_HOVER_ABOVE_HOME, .persistentId = NAV_PERSISTENT_ID_RTH_HOVER_ABOVE_HOME,
.onEntry = navOnEnteringState_NAV_STATE_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, .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, .mapToFlightModes = NAV_RTH_MODE | NAV_ALTHOLD_MODE,
.mwState = MW_NAV_STATE_HOVER_ABOVE_HOME, .mwState = MW_NAV_STATE_HOVER_ABOVE_HOME,
@ -711,7 +712,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
.timeoutMs = 0, .timeoutMs = 0,
.stateFlags = NAV_CTL_EMERG | NAV_REQUIRE_ANGLE, .stateFlags = NAV_CTL_EMERG | NAV_REQUIRE_ANGLE,
.mapToFlightModes = 0, .mapToFlightModes = 0,
.mwState = MW_NAV_STATE_LAND_START, .mwState = MW_NAV_STATE_EMERGENCY_LANDING,
.mwError = MW_NAV_ERROR_LANDING, .mwError = MW_NAV_ERROR_LANDING,
.onEvent = { .onEvent = {
[NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS, [NAV_FSM_EVENT_SUCCESS] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS,
@ -727,7 +728,7 @@ static const navigationFSMStateDescriptor_t navFSM[NAV_STATE_COUNT] = {
.timeoutMs = 10, .timeoutMs = 10,
.stateFlags = NAV_CTL_EMERG | NAV_REQUIRE_ANGLE, .stateFlags = NAV_CTL_EMERG | NAV_REQUIRE_ANGLE,
.mapToFlightModes = 0, .mapToFlightModes = 0,
.mwState = MW_NAV_STATE_LAND_IN_PROGRESS, .mwState = MW_NAV_STATE_EMERGENCY_LANDING,
.mwError = MW_NAV_ERROR_LANDING, .mwError = MW_NAV_ERROR_LANDING,
.onEvent = { .onEvent = {
[NAV_FSM_EVENT_TIMEOUT] = NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS, // re-process the state [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 position ok OR within valid timeout - continue
if ((posControl.flags.estPosStatus >= EST_USABLE) || !checkForPositionSensorTimeout()) { 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) // Wait until target heading is reached (with 15 deg margin for error)
if (STATE(FIXED_WING)) { if (STATE(FIXED_WING)) {
resetLandingDetector(); resetLandingDetector();
updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME; return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME;
} }
else { else {
if (ABS(wrap_18000(posControl.homeWaypointAbove.yaw - posControl.actualState.yaw)) < DEGREES_TO_CENTIDEGREES(15)) { if (ABS(wrap_18000(posControl.homeWaypointAbove.yaw - posControl.actualState.yaw)) < DEGREES_TO_CENTIDEGREES(15)) {
resetLandingDetector(); resetLandingDetector();
updateClimbRateToAltitudeController(0, ROC_TO_ALT_RESET);
return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME; return navigationRTHAllowsLanding() ? NAV_FSM_EVENT_SUCCESS : NAV_FSM_EVENT_SWITCH_TO_RTH_HOVER_ABOVE_HOME;
} }
else if (!validateRTHSanityChecker()) { 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())) if (!(validateRTHSanityChecker() || (posControl.flags.estPosStatus >= EST_USABLE) || !checkForPositionSensorTimeout()))
return NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING; 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; return NAV_FSM_EVENT_NONE;
} }
@ -1824,7 +1833,7 @@ void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, flo
} }
#if defined(NAV_BLACKBOX) #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); navActualVelocity[Z] = constrain(navGetCurrentActualPositionAndVelocity()->vel.z, -32678, 32767);
#endif #endif
} }
@ -2735,9 +2744,9 @@ void applyWaypointNavigationAndAltitudeHold(void)
if (posControl.flags.isAdjustingAltitude) navFlags |= (1 << 7); if (posControl.flags.isAdjustingAltitude) navFlags |= (1 << 7);
if (posControl.flags.isAdjustingHeading) navFlags |= (1 << 8); if (posControl.flags.isAdjustingHeading) navFlags |= (1 << 8);
navTargetPosition[X] = constrain(lrintf(posControl.desiredState.pos.x), -32678, 32767); navTargetPosition[X] = lrintf(posControl.desiredState.pos.x);
navTargetPosition[Y] = constrain(lrintf(posControl.desiredState.pos.y), -32678, 32767); navTargetPosition[Y] = lrintf(posControl.desiredState.pos.y);
navTargetPosition[Z] = constrain(lrintf(posControl.desiredState.pos.z), -32678, 32767); navTargetPosition[Z] = lrintf(posControl.desiredState.pos.z);
#endif #endif
} }
@ -2803,9 +2812,9 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void)
// If we were in LAUNCH mode - force switch to IDLE only if the throttle is low // If we were in LAUNCH mode - force switch to IDLE only if the throttle is low
if (FLIGHT_MODE(NAV_LAUNCH_MODE)) { if (FLIGHT_MODE(NAV_LAUNCH_MODE)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(); throttleStatus_e throttleStatus = calculateThrottleStatus();
if (throttleStatus != THROTTLE_LOW) if (throttleStatus != THROTTLE_LOW)
return NAV_FSM_EVENT_NONE; return NAV_FSM_EVENT_NONE;
else else
return NAV_FSM_EVENT_SWITCH_TO_IDLE; return NAV_FSM_EVENT_SWITCH_TO_IDLE;
} }
} }
@ -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].I / 100.0f,
(float)pidProfile()->bank_fw.pid[PID_POS_XY].D / 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, 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 / 9.80665f, (float)pidProfile()->bank_fw.pid[PID_POS_Z].I / 10.0f,
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 9.80665f); (float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 10.0f);
} }
void navigationInit(void) void navigationInit(void)
@ -3140,6 +3149,11 @@ rthState_e getStateOfForcedRTH(void)
} }
} }
bool navigationIsExecutingAnEmergencyLanding(void)
{
return navGetCurrentStateFlags() & NAV_CTL_EMERG;
}
bool navigationIsControllingThrottle(void) bool navigationIsControllingThrottle(void)
{ {
navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();

View file

@ -126,6 +126,7 @@ typedef struct navConfig_s {
uint8_t disarm_on_landing; // uint8_t disarm_on_landing; //
uint8_t rth_allow_landing; // Enable landing as last stage of RTH. Use constants in navRTHAllowLanding_e. uint8_t rth_allow_landing; // Enable landing as last stage of RTH. Use constants in navRTHAllowLanding_e.
uint8_t rth_climb_ignore_emerg; // Option to ignore GPS loss on initial climb stage of RTH 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; } flags;
uint8_t pos_failure_timeout; // Time to wait before switching to emergency landing (0 - disable) uint8_t pos_failure_timeout; // Time to wait before switching to emergency landing (0 - disable)
@ -279,12 +280,13 @@ typedef enum {
MW_NAV_STATE_WP_ENROUTE, // WP Enroute MW_NAV_STATE_WP_ENROUTE, // WP Enroute
MW_NAV_STATE_PROCESS_NEXT, // Process next MW_NAV_STATE_PROCESS_NEXT, // Process next
MW_NAV_STATE_DO_JUMP, // Jump 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_LAND_IN_PROGRESS, // Land in Progress
MW_NAV_STATE_LANDED, // Landed MW_NAV_STATE_LANDED, // Landed
MW_NAV_STATE_LAND_SETTLE, // Settling before land MW_NAV_STATE_LAND_SETTLE, // Settling before land
MW_NAV_STATE_LAND_START_DESCENT, // Start descent 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; } navSystemStatus_State_e;
typedef enum { typedef enum {
@ -391,6 +393,7 @@ rthState_e getStateOfForcedRTH(void);
bool navigationIsControllingThrottle(void); bool navigationIsControllingThrottle(void);
bool isFixedWingAutoThrottleManuallyIncreased(void); bool isFixedWingAutoThrottleManuallyIncreased(void);
bool navigationIsFlyingAutonomousMode(void); bool navigationIsFlyingAutonomousMode(void);
bool navigationIsExecutingAnEmergencyLanding(void);
/* Returns true iff navConfig()->general.flags.rth_allow_landing is NAV_RTH_ALLOW_LANDING_ALWAYS /* 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. * 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 navCurrentState;
extern int16_t navActualVelocity[3]; extern int16_t navActualVelocity[3];
extern int16_t navDesiredVelocity[3]; extern int16_t navDesiredVelocity[3];
extern int16_t navTargetPosition[3]; extern int32_t navTargetPosition[3];
extern int32_t navLatestActualPosition[3]; extern int32_t navLatestActualPosition[3];
extern int16_t navActualSurface; extern int16_t navActualSurface;
extern uint16_t navFlags; extern uint16_t navFlags;

View file

@ -59,7 +59,7 @@ enum {
CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE 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) #define CRSF_FRAME_SIZE_MAX (CRSF_PAYLOAD_SIZE_MAX + 4)
typedef struct crsfFrameDef_s { typedef struct crsfFrameDef_s {

View file

@ -325,7 +325,7 @@ static void telemetryRX(void)
case 2: case 2:
if (sensors(SENSOR_GPS)) { if (sensors(SENSOR_GPS)) {
uint16_t gpsspeed = (gpsSol.groundSpeed*9L)/250L; 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 #ifdef USE_NAV
int32_t alt = getEstimatedActualPosition(Z); int32_t alt = getEstimatedActualPosition(Z);
#else #else

Some files were not shown because too many files have changed in this diff Show more