mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 16:25:26 +03:00
Merge pull request #3 from iNavFlight/development
Sync Development Branch
This commit is contained in:
commit
2f32d56559
90 changed files with 963 additions and 508 deletions
12
README.md
12
README.md
|
@ -12,12 +12,8 @@
|
|||
* Rangefinder support (sonar and laser)
|
||||
* Oneshot and Multishot ESC support.
|
||||
* Blackbox flight recorder logging (to onboard flash or external SD card).
|
||||
* Support for more than 8 RC channels - (e.g. 16 Channels via FrSky X4RSB SBus).
|
||||
* Support for N-Position switches via flexible channel ranges - not just 3 like baseflight or 3/6 in MultiWii
|
||||
* Lux's new PID (uses float values internally, resistant to looptime variation).
|
||||
* Simultaneous Bluetooth configuration and OSD.
|
||||
* Better PWM and PPM input and failsafe detection than baseflight.
|
||||
* Better FrSky Telemetry than baseflight.
|
||||
* LTM Telemetry.
|
||||
* Smartport Telemetry.
|
||||
* RSSI via ADC - Uses ADC to read PWM RSSI signals, tested with FrSky D4R-II and X8R.
|
||||
|
@ -28,7 +24,7 @@
|
|||
* Configurable serial ports for Serial RX, Telemetry, MSP, GPS - Use most devices on any port, softserial too.
|
||||
* Multi-color RGB LED Strip support (each LED can be a different color using variable length WS2811 Addressable RGB strips - use for Orientation Indicators, Low Battery Warning, Flight Mode Status, etc)
|
||||
* PIDs from CF/BF can be used in INAV, no need to retune for INAV
|
||||
* And many more minor bug fixes.
|
||||
* And many more!
|
||||
|
||||
For a list of features, changes and some discussion please review the thread on RCGroups forums and consult the documentation.
|
||||
|
||||
|
@ -54,7 +50,9 @@ See: https://github.com/iNavFlight/inav/blob/master/docs/Installation.md
|
|||
|
||||
* [Official documentation](https://github.com/iNavFlight/inav/tree/master/docs)
|
||||
* [Official Wiki](https://github.com/iNavFlight/inav/wiki)
|
||||
* [Slack channel](https://inavflight.signup.team/)
|
||||
* [INAV Official on Telegram](https://t.me/INAVFlight)
|
||||
* [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial)
|
||||
* [INAV Official on Slack](https://publicslack.com/slacks/inavflight/invites/new)
|
||||
* [RC Groups Support](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-(navigation-rewrite)-project)
|
||||
* [Video series by Painless360](https://www.youtube.com/playlist?list=PLYsWjANuAm4qdXEGFSeUhOZ10-H8YTSnH)
|
||||
* [Video series by Paweł Spychalski](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLloACrA6f1_daCjhqY2x0fB)
|
||||
|
@ -83,4 +81,4 @@ Please refer to the development section in the [docs/development](https://github
|
|||
|
||||
|
||||
## INAV Releases
|
||||
https://github.com/iNavFlight/inav/releases
|
||||
https://github.com/iNavFlight/inav/releases
|
||||
|
|
|
@ -311,4 +311,14 @@ If `---` is displayed during flight instead of the remaining flight time/distanc
|
|||
|
||||
## Automatic throttle compensation based on battery voltage
|
||||
|
||||
Automatic throttle compensation based on battery voltage can be used by enabling the `THR_VBAT_COMP` feature. It is working like this: used_throttle = requested_throttle * battery_max_voltage / sag_compensated_voltage.
|
||||
This features aims to compensate the throttle to get constant thrust with the same throttle request despite the battery voltage going down during flight. It can be used by enabling the `THR_VBAT_COMP` feature. This feature needs the sag compensated voltage which needs a current sensor (real or virtual) to be calculated.
|
||||
|
||||
It is working like this: `used_throttle = requested_throttle * (1 + (battery_full_voltage / sag_compensated_voltage - 1) * thr_comp_weight)`.
|
||||
|
||||
The default `thr_comp_weight` of 1 should be close to idal but if you want to tune this feature you need to find the difference in throttle value to achieve the same thrust (same power) when your battery is full and when your battery is almost empty then set `thr_comp_weight` to `(empty_battery_throttle / full_battery_throttle - 1) / (battery_full_voltage / battery_empty_sag_compensated_voltage - 1)`
|
||||
|
||||
Example:
|
||||
If the drawn power is 100W when the battery is full (12.6V) with 53% throttle and the drawn power is 100W with 58% throttle when the battery is almost empty with the sag compensated voltage being 11.0V `thr_comp_weight` needs to be set to this value to compensate the throttle automatically:
|
||||
`(58 / 53 - 1) / (12.6 / 11.0 - 1) = 0.649`
|
||||
|
||||
Known limitation: it doesn't work in 3D mode (3D feature)
|
||||
|
|
|
@ -132,6 +132,8 @@ For Omnibus F4 Pro clones (Banggood, AliExpress, eBay, etc.) use **OMNIBUSF4PRO_
|
|||
|
||||
## SoftwareSerial
|
||||
|
||||
### Omnibus F4 v1/v2 SoftwareSerial Connections
|
||||
|
||||
This board allows for single **SoftwareSerial** port on small soldering pads located on the bottom side of the board.
|
||||
Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount pads CH5/CH6.
|
||||
|
||||
|
@ -148,7 +150,7 @@ Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount
|
|||
### Omnibus F4 v3/v4/v5 SoftwareSerial Connections
|
||||
|
||||
The SOFTSERIAL1 is an uni-directional port mapped to UART6-TX pin.
|
||||
When enabled, the UART6 is still available as hardware port but it's then RX-only port (good for e.g. receiving S.BUS input). TX instead is controlled in software (can be used for e.g. transmitting one-way telemetry).
|
||||
When enabled, the UART6 is still available as hardware port but it's then RX-only port (good for e.g. receiving S.BUS input). TX instead is controlled in software and can be used for transmitting one-way telemetry (e.g. LTM). Please note that UART6-TX line passes programmable inverter on those boards, so it is a pure output-only port. SmartPort/FPort telemetry requires bi-directional communication, so it is not possible on this port without hardware modification (bypassing the inverter).
|
||||
|
||||
|
||||
# Wiring diagrams for Omnibus F4 Pro
|
||||
|
|
21
docs/Cli.md
21
docs/Cli.md
|
@ -16,7 +16,7 @@ To exit the CLI without saving power off the flight controller or type in 'exit'
|
|||
|
||||
To see a list of other commands type in 'help' and press return.
|
||||
|
||||
To dump your configuration (including the current profile), use the 'dump' command.
|
||||
To dump your configuration (including the current profile), use the 'dump' or 'diff' command.
|
||||
|
||||
See the other documentation sections for details of the cli commands and settings that are available.
|
||||
|
||||
|
@ -42,23 +42,21 @@ dump profile
|
|||
|
||||
copy screen output to a file and save it.
|
||||
|
||||
Alternatively, use the `diff` command to dump only those settings that differ from their default values (those that have been changed).
|
||||
|
||||
|
||||
## Restore via CLI.
|
||||
|
||||
Use the cli `defaults` command first.
|
||||
|
||||
When restoring from a backup it is a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created you will be able to see the cli changes between firmware versions. For instance, in December 2014 the default GPS navigation PIDs changed. If you blindly restore your backup you would not benefit from these new defaults.
|
||||
When restoring from backup it's a good idea to do a dump of the latest defaults so you know what has changed - if you do this each time a firmware release is created you will be able to see the cli changes between firmware versions. If you blindly restore your backup you would not benefit from these new defaults or may even end up with completely wrong settings in case some parameters changed semantics and/or value ranges.
|
||||
|
||||
Use the CLI and send all the output from the saved backup commands.
|
||||
It may be good idea to restore settings using the `diff` output rather than complete `dump`. This way you can have more control on what is restored and the risk of mistakenly restoring bad values if the semantics changes is minimised.
|
||||
|
||||
Do not send the file too fast, if you do the FC might not be able to keep up when using USART adapters (including built in ones) since there is no hardware serial flow control.
|
||||
To perform the restore simply paste the saved commands in the Configurator CLI tab and then type `save`.
|
||||
|
||||
You may find you have to copy/paste a few lines at a time.
|
||||
After restoring it's always a good idea to `dump` or `diff` the settings once again and compare the output with previous one to verify if everything is set as it should be.
|
||||
|
||||
Repeat the backup process again!
|
||||
|
||||
Compare the two backups to make sure you are happy with your restored settings.
|
||||
|
||||
Re-apply any new defaults as desired.
|
||||
|
||||
## CLI Command Reference
|
||||
|
||||
|
@ -72,6 +70,7 @@ Re-apply any new defaults as desired.
|
|||
| `color` | configure colors |
|
||||
| `defaults` | reset to defaults and reboot |
|
||||
| `dump` | print configurable settings in a pastable form |
|
||||
| `diff` | print only settings that have been modified |
|
||||
| `exit` | |
|
||||
| `feature` | list or -val or val |
|
||||
| `get` | get variable value |
|
||||
|
@ -300,7 +299,6 @@ Re-apply any new defaults as desired.
|
|||
| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
|
||||
| osd_attitude_angle_decimals | 0 | Chose the numbers of decimals displayed by OSD attitude angle elements [0-1] |
|
||||
| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
|
@ -420,6 +418,7 @@ Re-apply any new defaults as desired.
|
|||
| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. |
|
||||
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
|
||||
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
|
||||
| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) |
|
||||
|
||||
This Markdown table is made by MarkdwonTableMaker addon for google spreadsheet.
|
||||
Original Spreadsheet used to make this table can be found here https://docs.google.com/spreadsheets/d/1ubjYdMGmZ2aAMUNYkdfe3hhIF7wRfIjcuPOi_ysmp00/edit?usp=sharing
|
||||
|
|
|
@ -156,13 +156,13 @@ MCU_COMMON_SRC = \
|
|||
drivers/adc_stm32f4xx.c \
|
||||
drivers/adc_stm32f4xx.c \
|
||||
drivers/bus_i2c_stm32f40x.c \
|
||||
drivers/inverter.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart_stm32f4xx.c \
|
||||
drivers/system_stm32f4xx.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_impl_stdperiph.c \
|
||||
drivers/timer_stm32f4xx.c \
|
||||
drivers/uart_inverter.c \
|
||||
drivers/dma_stm32f4xx.c
|
||||
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
|
|
|
@ -146,11 +146,11 @@ MCU_COMMON_SRC = \
|
|||
drivers/adc_stm32f7xx.c \
|
||||
drivers/bus_i2c_hal.c \
|
||||
drivers/dma_stm32f7xx.c \
|
||||
drivers/inverter.c \
|
||||
drivers/bus_spi_hal.c \
|
||||
drivers/timer.c \
|
||||
drivers/timer_impl_hal.c \
|
||||
drivers/timer_stm32f7xx.c \
|
||||
drivers/uart_inverter.c \
|
||||
drivers/system_stm32f7xx.c \
|
||||
drivers/serial_uart_stm32f7xx.c \
|
||||
drivers/serial_softserial.c \
|
||||
|
|
|
@ -75,6 +75,7 @@
|
|||
#include "sensors/pitotmeter.h"
|
||||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "flight/wind_estimator.h"
|
||||
|
||||
|
||||
#if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
|
||||
|
@ -193,6 +194,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"axisD", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_0)},
|
||||
{"axisD", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_1)},
|
||||
{"axisD", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_2)},
|
||||
|
||||
{"fwAltP", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwAltI", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwAltD", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
|
@ -201,6 +203,7 @@ static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
|
|||
{"fwPosI", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwPosD", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
{"fwPosOut", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(FIXED_WING_NAV)},
|
||||
|
||||
{"mcPosAxisP", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(MC_NAV)},
|
||||
{"mcPosAxisP", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(MC_NAV)},
|
||||
{"mcPosAxisP", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(MC_NAV)},
|
||||
|
@ -339,6 +342,9 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
|
|||
{"hwHealthStatus", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"powerSupplyImpedance", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"sagCompensatedVBat", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"wind", 0, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"wind", 1, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
{"wind", 2, SIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
|
||||
};
|
||||
|
||||
typedef enum BlackboxState {
|
||||
|
@ -436,6 +442,7 @@ typedef struct blackboxSlowState_s {
|
|||
int32_t hwHealthStatus;
|
||||
uint16_t powerSupplyImpedance;
|
||||
uint16_t sagCompensatedVBat;
|
||||
int16_t wind[XYZ_AXIS_COUNT];
|
||||
} __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
|
||||
|
||||
//From rc_controls.c
|
||||
|
@ -1020,6 +1027,8 @@ static void writeSlowFrame(void)
|
|||
|
||||
blackboxWriteUnsignedVB(slowHistory.powerSupplyImpedance);
|
||||
blackboxWriteUnsignedVB(slowHistory.sagCompensatedVBat);
|
||||
|
||||
blackboxWriteSigned16VBArray(slowHistory.wind, XYZ_AXIS_COUNT);
|
||||
|
||||
blackboxSlowFrameIterationTimer = 0;
|
||||
}
|
||||
|
@ -1043,6 +1052,12 @@ static void loadSlowState(blackboxSlowState_t *slow)
|
|||
(getHwPitotmeterStatus() << 2 * 6);
|
||||
slow->powerSupplyImpedance = getPowerSupplyImpedance();
|
||||
slow->sagCompensatedVBat = getBatterySagCompensatedVoltage();
|
||||
|
||||
for (int i = 0; i < XYZ_AXIS_COUNT; i++)
|
||||
{
|
||||
slow->wind[i] = getEstimatedWindSpeed(i);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -1139,7 +1154,7 @@ void blackboxStart(void)
|
|||
blackboxHistory[1] = &blackboxHistoryRing[1];
|
||||
blackboxHistory[2] = &blackboxHistoryRing[2];
|
||||
|
||||
vbatReference = getBatteryVoltageLatestADC();
|
||||
vbatReference = getBatteryRawVoltage();
|
||||
|
||||
//No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
|
||||
|
||||
|
@ -1256,25 +1271,34 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
#endif
|
||||
#ifdef USE_NAV
|
||||
if (!STATE(FIXED_WING)) {
|
||||
blackboxCurrent->mcPosAxisP[i] = lrintf(nav_pids->pos[i].output_constrained / 10);
|
||||
blackboxCurrent->mcVelAxisPID[0][i] = lrintf(nav_pids->vel[i].proportional / 10);
|
||||
blackboxCurrent->mcVelAxisPID[1][i] = lrintf(nav_pids->vel[i].integral / 10);
|
||||
blackboxCurrent->mcVelAxisPID[2][i] = lrintf(nav_pids->vel[i].derivative / 10);
|
||||
|
||||
// log requested velocity in cm/s
|
||||
blackboxCurrent->mcPosAxisP[i] = lrintf(nav_pids->pos[i].output_constrained);
|
||||
|
||||
// log requested acceleration in cm/s^2 and throttle adjustment in µs
|
||||
blackboxCurrent->mcVelAxisPID[0][i] = lrintf(nav_pids->vel[i].proportional);
|
||||
blackboxCurrent->mcVelAxisPID[1][i] = lrintf(nav_pids->vel[i].integral);
|
||||
blackboxCurrent->mcVelAxisPID[2][i] = lrintf(nav_pids->vel[i].derivative);
|
||||
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_NAV
|
||||
if (STATE(FIXED_WING)) {
|
||||
blackboxCurrent->fwAltPID[0] = lrintf(nav_pids->fw_alt.proportional / 10);
|
||||
blackboxCurrent->fwAltPID[1] = lrintf(nav_pids->fw_alt.integral / 10);
|
||||
blackboxCurrent->fwAltPID[2] = lrintf(nav_pids->fw_alt.derivative / 10);
|
||||
blackboxCurrent->fwAltPIDOutput = lrintf(nav_pids->fw_alt.output_constrained / 10);
|
||||
|
||||
// log requested pitch in decidegrees
|
||||
blackboxCurrent->fwAltPID[0] = lrintf(nav_pids->fw_alt.proportional);
|
||||
blackboxCurrent->fwAltPID[1] = lrintf(nav_pids->fw_alt.integral);
|
||||
blackboxCurrent->fwAltPID[2] = lrintf(nav_pids->fw_alt.derivative);
|
||||
blackboxCurrent->fwAltPIDOutput = lrintf(nav_pids->fw_alt.output_constrained);
|
||||
|
||||
// log requested roll in decidegrees
|
||||
blackboxCurrent->fwPosPID[0] = lrintf(nav_pids->fw_nav.proportional / 10);
|
||||
blackboxCurrent->fwPosPID[1] = lrintf(nav_pids->fw_nav.integral / 10);
|
||||
blackboxCurrent->fwPosPID[2] = lrintf(nav_pids->fw_nav.derivative / 10);
|
||||
blackboxCurrent->fwPosPIDOutput = lrintf(nav_pids->fw_nav.output_constrained / 10);
|
||||
|
||||
} else {
|
||||
blackboxCurrent->mcSurfacePID[0] = lrintf(nav_pids->surface.proportional / 10);
|
||||
blackboxCurrent->mcSurfacePID[1] = lrintf(nav_pids->surface.integral / 10);
|
||||
|
@ -1301,8 +1325,8 @@ static void loadMainState(timeUs_t currentTimeUs)
|
|||
blackboxCurrent->motor[i] = motor[i];
|
||||
}
|
||||
|
||||
blackboxCurrent->vbatLatest = getBatteryVoltageLatestADC();
|
||||
blackboxCurrent->amperageLatest = getAmperageLatestADC();
|
||||
blackboxCurrent->vbatLatest = getBatteryRawVoltage();
|
||||
blackboxCurrent->amperageLatest = getAmperage();
|
||||
|
||||
#ifdef USE_BARO
|
||||
blackboxCurrent->BaroAlt = baro.BaroAlt;
|
||||
|
@ -1461,7 +1485,7 @@ static char *blackboxGetStartDateTime(char *buf)
|
|||
// rtcGetDateTime will fill dt with 0000-01-01T00:00:00
|
||||
// when time is not known.
|
||||
rtcGetDateTime(&dt);
|
||||
dateTimeFormatUTC(buf, &dt);
|
||||
dateTimeFormatLocal(buf, &dt);
|
||||
return buf;
|
||||
}
|
||||
|
||||
|
|
|
@ -428,7 +428,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
|||
if (IS_PRINTVALUE(p, screenRow) && p->data) {
|
||||
buff[0] = '\0';
|
||||
const OSD_SETTING_t *ptr = p->data;
|
||||
const setting_t *var = &settingsTable[ptr->val];
|
||||
const setting_t *var = settingGet(ptr->val);
|
||||
int32_t value;
|
||||
const void *valuePointer = settingGetValuePointer(var);
|
||||
switch (SETTING_TYPE(var)) {
|
||||
|
@ -476,13 +476,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t
|
|||
break;
|
||||
case MODE_LOOKUP:
|
||||
{
|
||||
const char *str = NULL;
|
||||
if (var->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) {
|
||||
const lookupTableEntry_t *tableEntry = &settingLookupTables[var->config.lookup.tableIndex];
|
||||
if (value < tableEntry->valueCount) {
|
||||
str = tableEntry->values[value];
|
||||
}
|
||||
}
|
||||
const char *str = settingLookupValueName(var, value);
|
||||
strncpy(buff, str ? str : "INVALID", sizeof(buff) - 1);
|
||||
}
|
||||
break;
|
||||
|
@ -1008,7 +1002,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
|||
case OME_Setting:
|
||||
if (p->data) {
|
||||
const OSD_SETTING_t *ptr = p->data;
|
||||
const setting_t *var = &settingsTable[ptr->val];
|
||||
const setting_t *var = settingGet(ptr->val);
|
||||
setting_min_t min = settingGetMin(var);
|
||||
setting_max_t max = settingGetMax(var);
|
||||
float step = ptr->step ?: 1;
|
||||
|
|
|
@ -148,8 +148,7 @@ static const OSD_Entry menuMainEntries[] =
|
|||
OSD_SUBMENU_ENTRY("PID TUNING", &cmsx_menuImu),
|
||||
OSD_SUBMENU_ENTRY("FEATURES", &menuFeatures),
|
||||
#if defined(USE_OSD) && defined(CMS_MENU_OSD)
|
||||
OSD_SUBMENU_ENTRY("OSD LAYOUTS", &cmsx_menuOsdLayout),
|
||||
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
|
||||
OSD_SUBMENU_ENTRY("OSD", &cmsx_menuOsd),
|
||||
#endif
|
||||
OSD_SUBMENU_ENTRY("BATTERY", &cmsx_menuBattery),
|
||||
OSD_SUBMENU_ENTRY("FC&FW INFO", &menuInfo),
|
||||
|
|
|
@ -61,9 +61,9 @@ static const OSD_Entry cmsx_menuAlarmsEntries[] = {
|
|||
OSD_END_ENTRY,
|
||||
};
|
||||
|
||||
const CMS_Menu cmsx_menuAlarms = {
|
||||
static const CMS_Menu cmsx_menuAlarms = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUALARMS",
|
||||
.GUARD_text = "MENUOSDA",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
|
@ -144,7 +144,7 @@ static long osdElemActionsOnEnter(const OSD_Entry *from)
|
|||
|
||||
static const OSD_Entry menuOsdElemsEntries[] =
|
||||
{
|
||||
OSD_LABEL_ENTRY("--- OSD ---"),
|
||||
OSD_LABEL_ENTRY("--- OSD ITEMS ---"),
|
||||
|
||||
OSD_ELEMENT_ENTRY("RSSI", OSD_RSSI_VALUE),
|
||||
OSD_ELEMENT_ENTRY("MAIN BATTERY", OSD_MAIN_BATT_VOLTAGE),
|
||||
|
@ -257,7 +257,7 @@ _Static_assert(ARRAYLEN(menuOsdElemsEntries) - 3 + 1 == OSD_ITEM_COUNT, "missing
|
|||
|
||||
const CMS_Menu menuOsdElements = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUOSDELEMS",
|
||||
.GUARD_text = "MENUOSDE",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = osdElementsOnEnter,
|
||||
|
@ -290,7 +290,7 @@ static const OSD_Entry cmsx_menuOsdLayoutEntries[] =
|
|||
|
||||
const CMS_Menu cmsx_menuOsdLayout = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENULAYOUT",
|
||||
.GUARD_text = "MENUOSDL",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
|
@ -317,4 +317,53 @@ static long osdElementsOnExit(const OSD_Entry *from)
|
|||
return 0;
|
||||
}
|
||||
|
||||
static const OSD_Entry menuOsdSettingsEntries[] = {
|
||||
OSD_LABEL_ENTRY("--- OSD SETTINGS ---"),
|
||||
|
||||
OSD_SETTING_ENTRY("VOLT. DECIMALS", SETTING_OSD_MAIN_VOLTAGE_DECIMALS),
|
||||
OSD_SETTING_ENTRY("COORD. DIGITS", SETTING_OSD_COORDINATE_DIGITS),
|
||||
OSD_SETTING_ENTRY("CROSSHAIRS STYLE", SETTING_OSD_CROSSHAIRS_STYLE),
|
||||
OSD_SETTING_ENTRY("LEFT SCROLL", SETTING_OSD_LEFT_SIDEBAR_SCROLL),
|
||||
OSD_SETTING_ENTRY("RIGHT SCROLL", SETTING_OSD_RIGHT_SIDEBAR_SCROLL),
|
||||
OSD_SETTING_ENTRY("SCROLL ARROWS", SETTING_OSD_SIDEBAR_SCROLL_ARROWS),
|
||||
|
||||
|
||||
OSD_BACK_ENTRY,
|
||||
OSD_END_ENTRY,
|
||||
};
|
||||
|
||||
static const CMS_Menu cmsx_menuOsdSettings = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUOSDS",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = menuOsdSettingsEntries,
|
||||
};
|
||||
|
||||
static const OSD_Entry menuOsdEntries[] = {
|
||||
OSD_LABEL_ENTRY("--- OSD ---"),
|
||||
|
||||
OSD_SUBMENU_ENTRY("LAYOUTS", &cmsx_menuOsdLayout),
|
||||
OSD_SUBMENU_ENTRY("SETTINGS", &cmsx_menuOsdSettings),
|
||||
OSD_SUBMENU_ENTRY("ALARMS", &cmsx_menuAlarms),
|
||||
|
||||
OSD_BACK_ENTRY,
|
||||
OSD_END_ENTRY,
|
||||
};
|
||||
|
||||
|
||||
const CMS_Menu cmsx_menuOsd = {
|
||||
#ifdef CMS_MENU_DEBUG
|
||||
.GUARD_text = "MENUOSD",
|
||||
.GUARD_type = OME_MENU,
|
||||
#endif
|
||||
.onEnter = NULL,
|
||||
.onExit = NULL,
|
||||
.onGlobalExit = NULL,
|
||||
.entries = menuOsdEntries,
|
||||
};
|
||||
|
||||
#endif // CMS
|
||||
|
|
|
@ -17,5 +17,4 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
extern const CMS_Menu cmsx_menuAlarms;
|
||||
extern const CMS_Menu cmsx_menuOsdLayout;
|
||||
extern const CMS_Menu cmsx_menuOsd;
|
||||
|
|
|
@ -89,7 +89,7 @@ static const OSD_TAB_t trampCmsEntChan = { &trampCmsChan, VTX_TRAMP_CHANNEL_COUN
|
|||
|
||||
static uint8_t trampCmsPower = 1;
|
||||
|
||||
static const OSD_TAB_t trampCmsEntPower = { &trampCmsPower, sizeof(trampPowerTable), trampPowerNames };
|
||||
static const OSD_TAB_t trampCmsEntPower = { &trampCmsPower, VTX_TRAMP_POWER_COUNT, trampPowerNames };
|
||||
|
||||
static void trampCmsUpdateFreqRef(void)
|
||||
{
|
||||
|
|
|
@ -205,6 +205,13 @@ float biquadFilterApply(biquadFilter_t *filter, float input)
|
|||
return result;
|
||||
}
|
||||
|
||||
float biquadFilterReset(biquadFilter_t *filter, float value)
|
||||
{
|
||||
filter->d1 = value - (value * filter->b0);
|
||||
filter->d2 = (filter->b2 - filter->a2) * value;
|
||||
return value;
|
||||
}
|
||||
|
||||
/*
|
||||
* FIR filter
|
||||
*/
|
||||
|
|
|
@ -73,6 +73,7 @@ void biquadFilterInitNotch(biquadFilter_t *filter, uint32_t samplingIntervalUs,
|
|||
void biquadFilterInitLPF(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs);
|
||||
void biquadFilterInit(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samplingIntervalUs, float Q, biquadFilterType_e filterType);
|
||||
float biquadFilterApply(biquadFilter_t *filter, float sample);
|
||||
float biquadFilterReset(biquadFilter_t *filter, float value);
|
||||
float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff);
|
||||
|
||||
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);
|
||||
|
|
|
@ -58,7 +58,7 @@ PG_RESET_TEMPLATE(timeConfig_t, timeConfig,
|
|||
.tz_automatic_dst = TZ_AUTO_DST_OFF,
|
||||
);
|
||||
|
||||
static rtcTime_t dateTimeToRtcTime(dateTime_t *dt)
|
||||
static rtcTime_t dateTimeToRtcTime(const dateTime_t *dt)
|
||||
{
|
||||
unsigned int second = dt->seconds; // 0-59
|
||||
unsigned int minute = dt->minutes; // 0-59
|
||||
|
@ -157,6 +157,26 @@ static bool isDST(rtcTime_t t)
|
|||
switch ((tz_automatic_dst_e) timeConfig()->tz_automatic_dst) {
|
||||
case TZ_AUTO_DST_OFF:
|
||||
break;
|
||||
case TZ_AUTO_DST_EU: // begins at 1:00 a.m. on the last Sunday of March and ends at 1:00 a.m. on the last Sunday of October
|
||||
if (dateTime.month < 3 || dateTime.month > 10) {
|
||||
return false;
|
||||
}
|
||||
if (dateTime.month > 3 && dateTime.month < 10) {
|
||||
return true;
|
||||
}
|
||||
lastSunday = lastSundayOfMonth(dateTime.year, dateTime.month);
|
||||
if ((dateTime.day < lastSunday) || (dateTime.day > lastSunday)) {
|
||||
return !(dateTime.month == 3);
|
||||
}
|
||||
if (dateTime.day == lastSunday) {
|
||||
if (dateTime.month == 3) {
|
||||
return dateTime.hours >= 1;
|
||||
}
|
||||
if (dateTime.month == 10) {
|
||||
return dateTime.hours < 1;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case TZ_AUTO_DST_USA: // begins at 2:00 a.m. on the second Sunday of March and ends at 2:00 a.m. on the first Sunday of November
|
||||
if (dateTime.month < 3 || dateTime.month > 11) {
|
||||
return false;
|
||||
|
@ -180,39 +200,24 @@ static bool isDST(rtcTime_t t)
|
|||
return dateTime.day < firstSunday;
|
||||
}
|
||||
break;
|
||||
case TZ_AUTO_DST_EU: // begins at 1:00 a.m. on the last Sunday of March and ends at 1:00 a.m. on the last Sunday of October
|
||||
if (dateTime.month < 3 || dateTime.month > 10) {
|
||||
return false;
|
||||
}
|
||||
if (dateTime.month > 3 && dateTime.month < 10) {
|
||||
return true;
|
||||
}
|
||||
lastSunday = lastSundayOfMonth(dateTime.year, dateTime.month);
|
||||
if ((dateTime.day < lastSunday) || (dateTime.day > lastSunday)) {
|
||||
return !(dateTime.month == 3);
|
||||
}
|
||||
if (dateTime.day == lastSunday) {
|
||||
if (dateTime.month == 3) {
|
||||
return dateTime.hours >= 1;
|
||||
}
|
||||
if (dateTime.month == 10) {
|
||||
return dateTime.hours < 1;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void dateTimeWithOffset(dateTime_t *dateTimeOffset, dateTime_t *dateTimeInitial, int16_t minutes, bool automatic_dst)
|
||||
static void dateTimeWithOffset(dateTime_t *dateTimeOffset, const dateTime_t *dateTimeInitial, int16_t *minutes, bool automatic_dst)
|
||||
{
|
||||
rtcTime_t initialTime = dateTimeToRtcTime(dateTimeInitial);
|
||||
rtcTime_t offsetTime = rtcTimeMake(rtcTimeGetSeconds(&initialTime) + minutes * 60, rtcTimeGetMillis(&initialTime));
|
||||
rtcTime_t offsetTime = rtcTimeMake(rtcTimeGetSeconds(&initialTime) + *minutes * 60, rtcTimeGetMillis(&initialTime));
|
||||
#if defined(RTC_AUTOMATIC_DST)
|
||||
if (automatic_dst && isDST(offsetTime)) {
|
||||
offsetTime += 3600;
|
||||
// Add one hour. Tell the caller that the
|
||||
// offset has changed.
|
||||
*minutes += 60;
|
||||
offsetTime += 60 * 60 * MILLIS_PER_SECOND;
|
||||
}
|
||||
#else
|
||||
UNUSED(automatic_dst);
|
||||
#endif
|
||||
rtcTimeToDateTime(dateTimeOffset, offsetTime);
|
||||
}
|
||||
|
@ -226,10 +231,10 @@ static bool dateTimeFormat(char *buf, dateTime_t *dateTime, int16_t offset, bool
|
|||
bool retVal = true;
|
||||
|
||||
// Apply offset if necessary
|
||||
if (offset != 0) {
|
||||
if (offset != 0 || automatic_dst) {
|
||||
dateTimeWithOffset(&local, dateTime, &offset, automatic_dst);
|
||||
tz_hours = offset / 60;
|
||||
tz_minutes = ABS(offset % 60);
|
||||
dateTimeWithOffset(&local, dateTime, offset, automatic_dst);
|
||||
dateTime = &local;
|
||||
}
|
||||
|
||||
|
@ -271,12 +276,13 @@ bool dateTimeFormatUTC(char *buf, dateTime_t *dt)
|
|||
|
||||
bool dateTimeFormatLocal(char *buf, dateTime_t *dt)
|
||||
{
|
||||
return dateTimeFormat(buf, dt, timeConfig()->tz_offset, timeConfig()->tz_automatic_dst);
|
||||
return dateTimeFormat(buf, dt, timeConfig()->tz_offset, true);
|
||||
}
|
||||
|
||||
void dateTimeUTCToLocal(dateTime_t *utcDateTime, dateTime_t *localDateTime)
|
||||
void dateTimeUTCToLocal(dateTime_t *localDateTime, const dateTime_t *utcDateTime)
|
||||
{
|
||||
dateTimeWithOffset(localDateTime, utcDateTime, timeConfig()->tz_offset, timeConfig()->tz_automatic_dst);
|
||||
int16_t offset = timeConfig()->tz_offset;
|
||||
dateTimeWithOffset(localDateTime, utcDateTime, &offset, true);
|
||||
}
|
||||
|
||||
bool dateTimeSplitFormatted(char *formatted, char **date, char **time)
|
||||
|
@ -326,6 +332,15 @@ bool rtcGetDateTime(dateTime_t *dt)
|
|||
return false;
|
||||
}
|
||||
|
||||
bool rtcGetDateTimeLocal(dateTime_t *dt)
|
||||
{
|
||||
if (rtcGetDateTime(dt)) {
|
||||
dateTimeUTCToLocal(dt, dt);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
bool rtcSetDateTime(dateTime_t *dt)
|
||||
{
|
||||
rtcTime_t t = dateTimeToRtcTime(dt);
|
||||
|
|
|
@ -93,7 +93,7 @@ typedef struct _dateTime_s {
|
|||
bool dateTimeFormatUTC(char *buf, dateTime_t *dt);
|
||||
bool dateTimeFormatLocal(char *buf, dateTime_t *dt);
|
||||
|
||||
void dateTimeUTCToLocal(dateTime_t *utcDateTime, dateTime_t *localDateTime);
|
||||
void dateTimeUTCToLocal(dateTime_t *localDateTime, const dateTime_t *utcDateTime);
|
||||
// dateTimeSplitFormatted splits a formatted date into its date
|
||||
// and time parts. Note that the string pointed by formatted will
|
||||
// be modifed and will become invalid after calling this function.
|
||||
|
@ -105,4 +105,5 @@ bool rtcGet(rtcTime_t *t);
|
|||
bool rtcSet(rtcTime_t *t);
|
||||
|
||||
bool rtcGetDateTime(dateTime_t *dt);
|
||||
bool rtcGetDateTimeLocal(dateTime_t *dt);
|
||||
bool rtcSetDateTime(dateTime_t *dt);
|
||||
|
|
|
@ -113,3 +113,7 @@
|
|||
#define PG_RESERVED_FOR_TESTING_2 4094
|
||||
#define PG_RESERVED_FOR_TESTING_3 4093
|
||||
|
||||
#define PG_ID_INVALID 0
|
||||
#define PG_ID_FIRST PG_CF_START
|
||||
#define PG_ID_LAST PG_INAV_END
|
||||
|
||||
|
|
|
@ -33,6 +33,12 @@ void spiBusSetSpeed(const busDevice_t * dev, busSpeed_e speed)
|
|||
{
|
||||
const SPIClockSpeed_e spiClock[] = { SPI_CLOCK_INITIALIZATON, SPI_CLOCK_SLOW, SPI_CLOCK_STANDARD, SPI_CLOCK_FAST, SPI_CLOCK_ULTRAFAST };
|
||||
SPI_TypeDef * instance = spiInstanceByDevice(dev->busdev.spi.spiBus);
|
||||
|
||||
#ifdef BUS_SPI_SPEED_MAX
|
||||
if (speed > BUS_SPI_SPEED_MAX)
|
||||
speed = BUS_SPI_SPEED_MAX;
|
||||
#endif
|
||||
|
||||
spiSetSpeed(instance, spiClock[speed]);
|
||||
}
|
||||
|
||||
|
|
|
@ -92,6 +92,7 @@
|
|||
#define IST8310_REG_CNTRL1 0x0A
|
||||
#define IST8310_REG_CNTRL2 0x0B
|
||||
#define IST8310_REG_AVERAGE 0x41
|
||||
#define IST8310_REG_PDCNTL 0x42
|
||||
|
||||
// Parameter
|
||||
// ODR = Output Data Rate, we use single measure mode for getting more data.
|
||||
|
@ -103,7 +104,8 @@
|
|||
|
||||
// Device ID (ist8310 -> 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_DRPOL 0x04
|
||||
|
@ -117,6 +119,9 @@ static bool ist8310Init(magDev_t * mag)
|
|||
busWrite(mag->busDev, IST8310_REG_AVERAGE, IST8310_AVG_16);
|
||||
delay(5);
|
||||
|
||||
busWrite(mag->busDev, IST8310_REG_PDCNTL, IST8310_PULSE_DURATION_NORMAL);
|
||||
delay(5);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -135,10 +140,10 @@ static bool ist8310Read(magDev_t * mag)
|
|||
return false;
|
||||
}
|
||||
|
||||
// need to modify when confirming the pcb direction
|
||||
mag->magADCRaw[X] = (int16_t)(buf[1] << 8 | buf[0]) * LSB2FSV;
|
||||
mag->magADCRaw[Y] = (int16_t)(buf[3] << 8 | buf[2]) * LSB2FSV;
|
||||
mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]) * LSB2FSV;
|
||||
// Looks like datasheet is incorrect and we need to invert Y axis to conform to right hand rule
|
||||
mag->magADCRaw[X] = (int16_t)(buf[1] << 8 | buf[0]) * LSB2FSV;
|
||||
mag->magADCRaw[Y] = -(int16_t)(buf[3] << 8 | buf[2]) * LSB2FSV;
|
||||
mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]) * LSB2FSV;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -122,18 +122,22 @@ static bool qmc5883Read(magDev_t * mag)
|
|||
#define DETECTION_MAX_RETRY_COUNT 5
|
||||
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++) {
|
||||
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;
|
||||
bool ack = busRead(mag->busDev, QMC5883L_REG_ID, &sig);
|
||||
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -1,117 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "io_impl.h"
|
||||
|
||||
#include "inverter.h"
|
||||
|
||||
#ifdef USE_INVERTER
|
||||
static void inverterSet(IO_t pin, bool on)
|
||||
{
|
||||
IOWrite(pin, on);
|
||||
}
|
||||
|
||||
static void initInverter(ioTag_t ioTag)
|
||||
{
|
||||
IO_t pin = IOGetByTag(ioTag);
|
||||
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterSet(pin, false);
|
||||
}
|
||||
#endif
|
||||
|
||||
void initInverters(void)
|
||||
{
|
||||
#ifdef INVERTER_PIN_UART1
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART1));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART2
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART2));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART3
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART3));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART4
|
||||
initInverter(IO_TAG(INVERTER_PIN_USART4));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART5
|
||||
initInverter(IO_TAG(INVERTER_PIN_USART5));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART6
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART6));
|
||||
#endif
|
||||
}
|
||||
|
||||
void enableInverter(USART_TypeDef *USARTx, bool on)
|
||||
{
|
||||
#ifdef USE_INVERTER
|
||||
IO_t pin = IO_NONE;
|
||||
|
||||
#ifdef INVERTER_PIN_UART1
|
||||
if (USARTx == USART1) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART1));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART2
|
||||
if (USARTx == USART2) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART2));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART3
|
||||
if (USARTx == USART3) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART3));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART4
|
||||
if (USARTx == USART4) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_USART4));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_USART5
|
||||
if (USARTx == USART5) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_USART5));
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART6
|
||||
if (USARTx == USART6) {
|
||||
pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART6));
|
||||
}
|
||||
#endif
|
||||
|
||||
inverterSet(pin, on);
|
||||
#else
|
||||
UNUSED(USARTx);
|
||||
UNUSED(on);
|
||||
#endif
|
||||
}
|
|
@ -13,7 +13,6 @@
|
|||
#include "drivers/bus.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
|
||||
#define PCA9685_ADDR 0x40
|
||||
#define PCA9685_MODE1 0x00
|
||||
#define PCA9685_PRESCALE 0xFE
|
||||
|
||||
|
|
|
@ -28,23 +28,28 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "inverter.h"
|
||||
|
||||
#include "drivers/uart_inverter.h"
|
||||
|
||||
#include "serial.h"
|
||||
#include "serial_uart.h"
|
||||
#include "serial_uart_impl.h"
|
||||
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
|
||||
#if !defined(USE_UART_INVERTER) && !defined(STM32F303xC)
|
||||
UNUSED(uartPort);
|
||||
#else
|
||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||
|
||||
#ifdef USE_INVERTER
|
||||
if (inverted) {
|
||||
// Enable hardware inverter if available.
|
||||
enableInverter(uartPort->USARTx, true);
|
||||
#ifdef USE_UART_INVERTER
|
||||
uartInverterLine_e invertedLines = UART_INVERTER_LINE_NONE;
|
||||
if (uartPort->port.mode & MODE_RX) {
|
||||
invertedLines |= UART_INVERTER_LINE_RX;
|
||||
}
|
||||
if (uartPort->port.mode & MODE_TX) {
|
||||
invertedLines |= UART_INVERTER_LINE_TX;
|
||||
}
|
||||
uartInverterSet(uartPort->USARTx, invertedLines, inverted);
|
||||
#endif
|
||||
|
||||
#ifdef STM32F303xC
|
||||
|
|
|
@ -31,7 +31,6 @@
|
|||
#include "common/utils.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "inverter.h"
|
||||
#include "dma.h"
|
||||
|
||||
#include "serial.h"
|
||||
|
|
|
@ -51,7 +51,8 @@ void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
|
|||
// cycles per microsecond
|
||||
STATIC_UNIT_TESTED timeUs_t usTicks = 0;
|
||||
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
|
||||
STATIC_UNIT_TESTED volatile timeMs_t sysTickUptime = 0;
|
||||
STATIC_UNIT_TESTED volatile timeMs_t sysTickUptime = 0;
|
||||
STATIC_UNIT_TESTED volatile uint32_t sysTickValStamp = 0;
|
||||
// cached value of RCC->CSR
|
||||
uint32_t cachedRccCsrValue;
|
||||
|
||||
|
@ -81,6 +82,7 @@ void SysTick_Handler(void)
|
|||
{
|
||||
ATOMIC_BLOCK(NVIC_PRIO_MAX) {
|
||||
sysTickUptime++;
|
||||
sysTickValStamp = SysTick->VAL;
|
||||
sysTickPending = 0;
|
||||
(void)(SysTick->CTRL);
|
||||
}
|
||||
|
@ -148,12 +150,8 @@ timeUs_t micros(void)
|
|||
do {
|
||||
ms = sysTickUptime;
|
||||
cycle_cnt = SysTick->VAL;
|
||||
/*
|
||||
* If the SysTick timer expired during the previous instruction, we need to give it a little time for that
|
||||
* interrupt to be delivered before we can recheck sysTickUptime:
|
||||
*/
|
||||
asm volatile("\tnop\n");
|
||||
} while (ms != sysTickUptime);
|
||||
} while (ms != sysTickUptime || cycle_cnt > sysTickValStamp);
|
||||
|
||||
return ((timeUs_t)ms * 1000LL) + (usTicks * 1000LL - (timeUs_t)cycle_cnt) / usTicks;
|
||||
}
|
||||
|
||||
|
|
188
src/main/drivers/uart_inverter.c
Normal file
188
src/main/drivers/uart_inverter.c
Normal file
|
@ -0,0 +1,188 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/uart_inverter.h"
|
||||
|
||||
#if defined(USE_UART_INVERTER)
|
||||
|
||||
static void inverterPinSet(IO_t pin, bool on)
|
||||
{
|
||||
IOWrite(pin, on);
|
||||
}
|
||||
|
||||
static void initInverter(ioTag_t ioTag)
|
||||
{
|
||||
IO_t pin = IOGetByTag(ioTag);
|
||||
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||
|
||||
inverterPinSet(pin, false);
|
||||
}
|
||||
|
||||
void uartInverterInit(void)
|
||||
{
|
||||
|
||||
// UART1
|
||||
#ifdef INVERTER_PIN_UART1_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART1_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART1_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART1_TX));
|
||||
#endif
|
||||
|
||||
// UART2
|
||||
#ifdef INVERTER_PIN_UART2_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART2_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART2_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART2_TX));
|
||||
#endif
|
||||
|
||||
// UART3
|
||||
#ifdef INVERTER_PIN_UART3_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART3_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART3_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART3_TX));
|
||||
#endif
|
||||
|
||||
// UART4
|
||||
#ifdef INVERTER_PIN_UART4_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART4_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART4_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART4_TX));
|
||||
#endif
|
||||
|
||||
// UART5
|
||||
#ifdef INVERTER_PIN_UART5_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART5_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART5_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART5_TX));
|
||||
#endif
|
||||
|
||||
// UART6
|
||||
#ifdef INVERTER_PIN_UART6_RX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART6_RX));
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER_PIN_UART6_TX
|
||||
initInverter(IO_TAG(INVERTER_PIN_UART6_TX));
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void uartInverterSet(USART_TypeDef *USARTx, uartInverterLine_e line, bool enable)
|
||||
{
|
||||
IO_t rx_pin = IO_NONE;
|
||||
IO_t tx_pin = IO_NONE;
|
||||
|
||||
// UART1
|
||||
#if defined(INVERTER_PIN_UART1_RX) || defined(INVERTER_PIN_UART1_TX)
|
||||
if (USARTx == USART1) {
|
||||
#if defined(INVERTER_PIN_UART1_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART1_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART1_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART1_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART2
|
||||
#if defined(INVERTER_PIN_UART2_RX) || defined(INVERTER_PIN_UART2_TX)
|
||||
if (USARTx == USART2) {
|
||||
#if defined(INVERTER_PIN_UART2_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART2_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART2_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART2_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART3
|
||||
#if defined(INVERTER_PIN_UART3_RX) || defined(INVERTER_PIN_UART3_TX)
|
||||
if (USARTx == USART3) {
|
||||
#if defined(INVERTER_PIN_UART3_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART3_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART3_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART3_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART4
|
||||
#if defined(INVERTER_PIN_UART4_RX) || defined(INVERTER_PIN_UART4_TX)
|
||||
if (USARTx == USART4) {
|
||||
#if defined(INVERTER_PIN_UART4_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART4_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART4_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART4_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART5
|
||||
#if defined(INVERTER_PIN_UART5_RX) || defined(INVERTER_PIN_UART5_TX)
|
||||
if (USARTx == USART5) {
|
||||
#if defined(INVERTER_PIN_UART5_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART5_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART5_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART5_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// UART6
|
||||
#if defined(INVERTER_PIN_UART6_RX) || defined(INVERTER_PIN_UART6_TX)
|
||||
if (USARTx == USART6) {
|
||||
#if defined(INVERTER_PIN_UART6_RX)
|
||||
rx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART6_RX));
|
||||
#endif
|
||||
#if defined(INVERTER_PIN_UART6_TX)
|
||||
tx_pin = IOGetByTag(IO_TAG(INVERTER_PIN_UART6_TX));
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
// Now do the actual work
|
||||
if (rx_pin != IO_NONE && (line & UART_INVERTER_LINE_RX)) {
|
||||
inverterPinSet(rx_pin, enable);
|
||||
}
|
||||
if (tx_pin != IO_NONE && (line & UART_INVERTER_LINE_TX)) {
|
||||
inverterPinSet(tx_pin, enable);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -17,10 +17,12 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if defined(INVERTER_PIN_UART1) || defined(INVERTER_PIN_UART2) || defined(INVERTER_PIN_UART3) || defined(INVERTER_PIN_UART4) || defined(INVERTER_PIN_UART5) || defined(INVERTER_PIN_UART6)
|
||||
#define USE_INVERTER
|
||||
#endif
|
||||
typedef enum {
|
||||
UART_INVERTER_LINE_NONE = 0,
|
||||
UART_INVERTER_LINE_RX = 1 << 0,
|
||||
UART_INVERTER_LINE_TX = 1 << 1,
|
||||
} uartInverterLine_e;
|
||||
|
||||
void initInverters(void);
|
||||
void uartInverterInit(void);
|
||||
|
||||
void enableInverter(USART_TypeDef *USARTx, bool on);
|
||||
void uartInverterSet(USART_TypeDef *USARTx, uartInverterLine_e line, bool enable);
|
|
@ -47,7 +47,7 @@
|
|||
|
||||
#define VTX_SETTINGS_POWER_COUNT 5
|
||||
#define VTX_SETTINGS_DEFAULT_POWER 1
|
||||
#define VTX_SETTINGS_MIN_POWER 0
|
||||
#define VTX_SETTINGS_MIN_POWER 1
|
||||
#define VTX_SETTINGS_MIN_USER_FREQ 5000
|
||||
#define VTX_SETTINGS_MAX_USER_FREQ 5999
|
||||
#define VTX_SETTINGS_FREQCMD
|
||||
|
|
|
@ -352,14 +352,17 @@ static void printValuePointer(const setting_t *var, const void *valuePointer, ui
|
|||
}
|
||||
break;
|
||||
case MODE_LOOKUP:
|
||||
if (var->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) {
|
||||
cliPrintf(settingLookupTables[var->config.lookup.tableIndex].values[value]);
|
||||
{
|
||||
const char *name = settingLookupValueName(var, value);
|
||||
if (name) {
|
||||
cliPrintf(name);
|
||||
} else {
|
||||
settingGetName(var, buf);
|
||||
cliPrintLinef("VALUE %s OUT OF RANGE", buf);
|
||||
cliPrintLinef("VALUE %d OUT OF RANGE FOR %s", (int)value, buf);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool valuePtrEqualsDefault(const setting_t *value, const void *ptr, const void *ptrDefault)
|
||||
|
@ -425,8 +428,8 @@ static void dumpPgValue(const setting_t *value, uint8_t dumpMask)
|
|||
|
||||
static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask)
|
||||
{
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
const setting_t *value = &settingsTable[i];
|
||||
for (unsigned i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
const setting_t *value = settingGet(i);
|
||||
bufWriterFlush(cliWriter);
|
||||
if (SETTING_SECTION(value) == valueSection) {
|
||||
dumpPgValue(value, dumpMask);
|
||||
|
@ -453,7 +456,7 @@ static void cliPrintVarRange(const setting_t *var)
|
|||
break;
|
||||
case MODE_LOOKUP:
|
||||
{
|
||||
const lookupTableEntry_t *tableEntry = &settingLookupTables[var->config.lookup.tableIndex];
|
||||
const lookupTableEntry_t *tableEntry = settingLookupTable(var);
|
||||
cliPrint("Allowed values:");
|
||||
for (uint32_t i = 0; i < tableEntry->valueCount ; i++) {
|
||||
if (i > 0)
|
||||
|
@ -1263,7 +1266,7 @@ static void cliModeColor(char *cmdline)
|
|||
static void printServo(uint8_t dumpMask, const servoParam_t *servoParam, const servoParam_t *defaultServoParam)
|
||||
{
|
||||
// print out servo settings
|
||||
const char *format = "servo %u %d %d %d %d ";
|
||||
const char *format = "servo %u %d %d %d %d";
|
||||
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
const servoParam_t *servoConf = &servoParam[i];
|
||||
bool equalsDefault = false;
|
||||
|
@ -2256,7 +2259,7 @@ static void cliGet(char *cmdline)
|
|||
char name[SETTING_MAX_NAME_LENGTH];
|
||||
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
val = &settingsTable[i];
|
||||
val = settingGet(i);
|
||||
if (settingNameContains(val, name, cmdline)) {
|
||||
cliPrintf("%s = ", name);
|
||||
cliPrintVar(val, 0);
|
||||
|
@ -2288,7 +2291,7 @@ static void cliSet(char *cmdline)
|
|||
if (len == 0 || (len == 1 && cmdline[0] == '*')) {
|
||||
cliPrintLine("Current settings:");
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
val = &settingsTable[i];
|
||||
val = settingGet(i);
|
||||
settingGetName(val, name);
|
||||
cliPrintf("%s = ", name);
|
||||
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
|
||||
|
@ -2310,7 +2313,7 @@ static void cliSet(char *cmdline)
|
|||
}
|
||||
|
||||
for (uint32_t i = 0; i < SETTINGS_TABLE_COUNT; i++) {
|
||||
val = &settingsTable[i];
|
||||
val = settingGet(i);
|
||||
// ensure exact match when setting to prevent setting variables with shorter names
|
||||
if (settingNameIsExactMatch(val, name, cmdline, variableNameLength)) {
|
||||
const setting_type_e type = SETTING_TYPE(val);
|
||||
|
@ -2341,7 +2344,7 @@ static void cliSet(char *cmdline)
|
|||
}
|
||||
break;
|
||||
case MODE_LOOKUP: {
|
||||
const lookupTableEntry_t *tableEntry = &settingLookupTables[settingsTable[i].config.lookup.tableIndex];
|
||||
const lookupTableEntry_t *tableEntry = settingLookupTable(val);
|
||||
bool matched = false;
|
||||
for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
|
||||
matched = sl_strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
|
||||
|
|
|
@ -706,7 +706,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
cycleTime = getTaskDeltaTime(TASK_SELF);
|
||||
dT = (float)cycleTime * 0.000001f;
|
||||
|
||||
if (ARMING_FLAG(ARMED) && ((!STATE(FIXED_WING)) || (isNavLaunchEnabled() && isFixedWingLaunchDetected()))) {
|
||||
if (ARMING_FLAG(ARMED) && ((!STATE(FIXED_WING)) || (!isNavLaunchEnabled()) || (isNavLaunchEnabled() && isFixedWingLaunchDetected()))) {
|
||||
flightTime += cycleTime;
|
||||
}
|
||||
|
||||
|
|
|
@ -48,7 +48,6 @@
|
|||
#include "drivers/dma.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/inverter.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_pca9685.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
@ -69,6 +68,7 @@
|
|||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/uart_inverter.h"
|
||||
#include "drivers/vcd.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
|
@ -375,8 +375,8 @@ void init(void)
|
|||
lightsInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_INVERTER
|
||||
initInverters();
|
||||
#ifdef USE_UART_INVERTER
|
||||
uartInverterInit();
|
||||
#endif
|
||||
|
||||
// Initialize buses
|
||||
|
|
|
@ -35,6 +35,8 @@
|
|||
#include "common/time.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
@ -2549,9 +2551,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ACK;
|
||||
}
|
||||
|
||||
static const setting_t *mspReadSettingName(sbuf_t *src)
|
||||
static const setting_t *mspReadSetting(sbuf_t *src)
|
||||
{
|
||||
char name[SETTING_MAX_NAME_LENGTH];
|
||||
uint16_t id;
|
||||
uint8_t c;
|
||||
size_t s = 0;
|
||||
while (1) {
|
||||
|
@ -2560,6 +2563,14 @@ static const setting_t *mspReadSettingName(sbuf_t *src)
|
|||
}
|
||||
name[s++] = c;
|
||||
if (c == '\0') {
|
||||
if (s == 1) {
|
||||
// Payload starts with a zero, setting index
|
||||
// as uint16_t follows
|
||||
if (sbufReadU16Safe(&id, src)) {
|
||||
return settingGet(id);
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
break;
|
||||
}
|
||||
if (s == SETTING_MAX_NAME_LENGTH) {
|
||||
|
@ -2572,7 +2583,7 @@ static const setting_t *mspReadSettingName(sbuf_t *src)
|
|||
|
||||
static bool mspSettingCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
const setting_t *setting = mspReadSettingName(src);
|
||||
const setting_t *setting = mspReadSetting(src);
|
||||
if (!setting) {
|
||||
return false;
|
||||
}
|
||||
|
@ -2587,7 +2598,7 @@ static bool mspSetSettingCommand(sbuf_t *dst, sbuf_t *src)
|
|||
{
|
||||
UNUSED(dst);
|
||||
|
||||
const setting_t *setting = mspReadSettingName(src);
|
||||
const setting_t *setting = mspReadSetting(src);
|
||||
if (!setting) {
|
||||
return false;
|
||||
}
|
||||
|
@ -2679,6 +2690,94 @@ static bool mspSetSettingCommand(sbuf_t *dst, sbuf_t *src)
|
|||
return true;
|
||||
}
|
||||
|
||||
static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
const setting_t *setting = mspReadSetting(src);
|
||||
if (!setting) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Parameter Group ID
|
||||
sbufWriteU16(dst, settingGetPgn(setting));
|
||||
|
||||
// Type, section and mode
|
||||
sbufWriteU8(dst, SETTING_TYPE(setting));
|
||||
sbufWriteU8(dst, SETTING_SECTION(setting));
|
||||
sbufWriteU8(dst, SETTING_MODE(setting));
|
||||
|
||||
// Min as int32_t
|
||||
int32_t min = settingGetMin(setting);
|
||||
sbufWriteU32(dst, (uint32_t)min);
|
||||
// Max as uint32_t
|
||||
uint32_t max = settingGetMax(setting);
|
||||
sbufWriteU32(dst, max);
|
||||
|
||||
// Absolute setting index
|
||||
sbufWriteU16(dst, settingGetIndex(setting));
|
||||
|
||||
// If the setting is profile based, send the current one
|
||||
// and the count, both as uint8_t. For MASTER_VALUE, we
|
||||
// send two zeroes, so the MSP client can assume there
|
||||
// will always be two bytes.
|
||||
switch (SETTING_SECTION(setting)) {
|
||||
case MASTER_VALUE:
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU8(dst, 0);
|
||||
break;
|
||||
case PROFILE_VALUE:
|
||||
FALLTHROUGH;
|
||||
case CONTROL_RATE_VALUE:
|
||||
sbufWriteU8(dst, getConfigProfile());
|
||||
sbufWriteU8(dst, MAX_PROFILE_COUNT);
|
||||
break;
|
||||
case BATTERY_CONFIG_VALUE:
|
||||
sbufWriteU8(dst, getConfigBatteryProfile());
|
||||
sbufWriteU8(dst, MAX_BATTERY_PROFILE_COUNT);
|
||||
break;
|
||||
}
|
||||
|
||||
// If the setting uses a table, send each possible string (null terminated)
|
||||
if (SETTING_MODE(setting) == MODE_LOOKUP) {
|
||||
for (int ii = (int)min; ii <= (int)max; ii++) {
|
||||
const char *name = settingLookupValueName(setting, ii);
|
||||
sbufWriteDataSafe(dst, name, strlen(name) + 1);
|
||||
}
|
||||
}
|
||||
|
||||
// Finally, include the setting value. This way resource constrained callers
|
||||
// (e.g. a script in the radio) don't need to perform another call to retrieve
|
||||
// the value.
|
||||
const void *ptr = settingGetValuePointer(setting);
|
||||
size_t size = settingGetValueSize(setting);
|
||||
sbufWriteDataSafe(dst, ptr, size);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool mspParameterGroupsCommand(sbuf_t *dst, sbuf_t *src)
|
||||
{
|
||||
uint16_t first;
|
||||
uint16_t last;
|
||||
uint16_t start;
|
||||
uint16_t end;
|
||||
|
||||
if (sbufReadU16Safe(&first, src)) {
|
||||
last = first;
|
||||
} else {
|
||||
first = PG_ID_FIRST;
|
||||
last = PG_ID_LAST;
|
||||
}
|
||||
|
||||
for (int ii = first; ii <= last; ii++) {
|
||||
if (settingsGetParameterGroupIndexes(ii, &start, &end)) {
|
||||
sbufWriteU16(dst, ii);
|
||||
sbufWriteU16(dst, start);
|
||||
sbufWriteU16(dst, end);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResult_e *ret)
|
||||
{
|
||||
switch (cmdMSP) {
|
||||
|
@ -2705,6 +2804,14 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
|
|||
*ret = mspSetSettingCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_COMMON_SETTING_INFO:
|
||||
*ret = mspSettingInfoCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_COMMON_PG_LIST:
|
||||
*ret = mspParameterGroupsCommand(dst, src) ? MSP_RESULT_ACK : MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
#if defined(USE_OSD)
|
||||
case MSP2_INAV_OSD_LAYOUTS:
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
|
|
|
@ -101,12 +101,12 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
|
|||
static timeUs_t batMonitoringLastServiced = 0;
|
||||
timeUs_t BatMonitoringTimeSinceLastServiced = cmpTimeUs(currentTimeUs, batMonitoringLastServiced);
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER))
|
||||
if (isAmperageConfigured())
|
||||
currentMeterUpdate(BatMonitoringTimeSinceLastServiced);
|
||||
#ifdef USE_ADC
|
||||
if (feature(FEATURE_VBAT))
|
||||
batteryUpdate(BatMonitoringTimeSinceLastServiced);
|
||||
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) {
|
||||
if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
|
||||
powerMeterUpdate(BatMonitoringTimeSinceLastServiced);
|
||||
sagCompensatedVBatUpdate(currentTimeUs, BatMonitoringTimeSinceLastServiced);
|
||||
}
|
||||
|
@ -306,7 +306,7 @@ void fcTasksInit(void)
|
|||
#ifdef USE_LIGHTS
|
||||
setTaskEnabled(TASK_LIGHTS, true);
|
||||
#endif
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || feature(FEATURE_CURRENT_METER));
|
||||
setTaskEnabled(TASK_BATTERY, feature(FEATURE_VBAT) || isAmperageConfigured());
|
||||
setTaskEnabled(TASK_TEMPERATURE, true);
|
||||
setTaskEnabled(TASK_RX, true);
|
||||
#ifdef USE_GPS
|
||||
|
|
|
@ -638,12 +638,18 @@ void updateAdjustmentStates(bool canUseRxData)
|
|||
{
|
||||
for (int index = 0; index < MAX_ADJUSTMENT_RANGE_COUNT; index++) {
|
||||
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(index);
|
||||
if (adjustmentRange->adjustmentFunction == ADJUSTMENT_NONE) {
|
||||
// Range not set up
|
||||
continue;
|
||||
}
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentFunction - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
adjustmentState_t * const adjustmentState = &adjustmentStates[adjustmentRange->adjustmentIndex];
|
||||
|
||||
if (canUseRxData && isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range)) {
|
||||
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
|
||||
if (!adjustmentState->config) {
|
||||
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
|
||||
}
|
||||
} else {
|
||||
adjustmentState_t * const adjustmentState = &adjustmentStates[index];
|
||||
if (adjustmentState->config == adjustmentConfig) {
|
||||
adjustmentState->config = NULL;
|
||||
}
|
||||
|
|
|
@ -17,9 +17,12 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_curves.h"
|
||||
|
@ -31,7 +34,7 @@
|
|||
|
||||
#define PITCH_LOOKUP_LENGTH 7
|
||||
#define YAW_LOOKUP_LENGTH 7
|
||||
#define THROTTLE_LOOKUP_LENGTH 12
|
||||
#define THROTTLE_LOOKUP_LENGTH 11
|
||||
|
||||
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
|
||||
int16_t lookupThrottleRCMid; // THROTTLE curve mid point
|
||||
|
@ -55,12 +58,15 @@ void generateThrottleCurve(const controlRateConfig_t *controlRateConfig)
|
|||
int16_t rcLookup(int32_t stickDeflection, uint8_t expo)
|
||||
{
|
||||
float tmpf = stickDeflection / 100.0f;
|
||||
return (int16_t)((2500.0f + (float)expo * (tmpf * tmpf - 25.0f)) * tmpf / 25.0f);
|
||||
return lrintf((2500.0f + (float)expo * (tmpf * tmpf - 25.0f)) * tmpf / 25.0f);
|
||||
}
|
||||
|
||||
int16_t rcLookupThrottle(int32_t absoluteDeflection)
|
||||
uint16_t rcLookupThrottle(uint16_t absoluteDeflection)
|
||||
{
|
||||
const int32_t lookupStep = absoluteDeflection / 100;
|
||||
if (absoluteDeflection > 999)
|
||||
return motorConfig()->maxthrottle;
|
||||
|
||||
const uint8_t lookupStep = absoluteDeflection / 100;
|
||||
return lookupThrottleRC[lookupStep] + (absoluteDeflection - lookupStep * 100) * (lookupThrottleRC[lookupStep + 1] - lookupThrottleRC[lookupStep]) / 100;
|
||||
}
|
||||
|
||||
|
|
|
@ -21,5 +21,5 @@ struct controlRateConfig_s;
|
|||
void generateThrottleCurve(const struct controlRateConfig_s *controlRateConfig);
|
||||
|
||||
int16_t rcLookup(int32_t stickDeflection, uint8_t expo);
|
||||
int16_t rcLookupThrottle(int32_t tmp);
|
||||
uint16_t rcLookupThrottle(uint16_t tmp);
|
||||
int16_t rcLookupThrottleMid(void);
|
||||
|
|
|
@ -77,6 +77,16 @@ const setting_t *settingFind(const char *name)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
const setting_t *settingGet(unsigned index)
|
||||
{
|
||||
return index < SETTINGS_TABLE_COUNT ? &settingsTable[index] : NULL;
|
||||
}
|
||||
|
||||
unsigned settingGetIndex(const setting_t *val)
|
||||
{
|
||||
return val - settingsTable;
|
||||
}
|
||||
|
||||
size_t settingGetValueSize(const setting_t *val)
|
||||
{
|
||||
switch (SETTING_TYPE(val)) {
|
||||
|
@ -154,6 +164,23 @@ setting_max_t settingGetMax(const setting_t *val)
|
|||
return settingMinMaxTable[SETTING_INDEXES_GET_MAX(val)];
|
||||
}
|
||||
|
||||
const lookupTableEntry_t * settingLookupTable(const setting_t *val)
|
||||
{
|
||||
if (SETTING_MODE(val) == MODE_LOOKUP && val->config.lookup.tableIndex < LOOKUP_TABLE_COUNT) {
|
||||
return &settingLookupTables[val->config.lookup.tableIndex];
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const char * settingLookupValueName(const setting_t *val, unsigned v)
|
||||
{
|
||||
const lookupTableEntry_t *table = settingLookupTable(val);
|
||||
if (table && v < table->valueCount) {
|
||||
return table->values[v];
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
const char * settingGetString(const setting_t *val)
|
||||
{
|
||||
if (SETTING_TYPE(val) == VAR_STRING) {
|
||||
|
@ -180,3 +207,21 @@ setting_max_t settingGetStringMaxLength(const setting_t *val)
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool settingsGetParameterGroupIndexes(pgn_t pg, uint16_t *start, uint16_t *end)
|
||||
{
|
||||
unsigned acc = 0;
|
||||
for (int ii = 0; ii < SETTINGS_PGN_COUNT; ii++) {
|
||||
if (settingsPgn[ii] == pg) {
|
||||
if (start) {
|
||||
*start = acc;
|
||||
}
|
||||
if (end) {
|
||||
*end = acc + settingsPgnCounts[ii] - 1;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
acc += settingsPgnCounts[ii];
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -13,8 +13,6 @@ typedef struct lookupTableEntry_s {
|
|||
const uint8_t valueCount;
|
||||
} lookupTableEntry_t;
|
||||
|
||||
extern const lookupTableEntry_t settingLookupTables[];
|
||||
|
||||
#define SETTING_TYPE_OFFSET 0
|
||||
#define SETTING_SECTION_OFFSET 4
|
||||
#define SETTING_MODE_OFFSET 6
|
||||
|
@ -69,8 +67,6 @@ typedef struct {
|
|||
|
||||
} __attribute__((packed)) setting_t;
|
||||
|
||||
extern const setting_t settingsTable[];
|
||||
|
||||
static inline setting_type_e SETTING_TYPE(const setting_t *s) { return s->type & SETTING_TYPE_MASK; }
|
||||
static inline setting_section_e SETTING_SECTION(const setting_t *s) { return s->type & SETTING_SECTION_MASK; }
|
||||
static inline setting_mode_e SETTING_MODE(const setting_t *s) { return s->type & SETTING_MODE_MASK; }
|
||||
|
@ -81,6 +77,11 @@ bool settingNameIsExactMatch(const setting_t *val, char *buf, const char *cmdlin
|
|||
// Returns a setting_t with the exact name (case sensitive), or
|
||||
// NULL if no setting with that name exists.
|
||||
const setting_t *settingFind(const char *name);
|
||||
// Returns the setting at the given index, or NULL if
|
||||
// the index is greater than the total count.
|
||||
const setting_t *settingGet(unsigned index);
|
||||
// Returns the setting index for the given setting.
|
||||
unsigned settingGetIndex(const setting_t *val);
|
||||
// Returns the size in bytes of the setting value.
|
||||
size_t settingGetValueSize(const setting_t *val);
|
||||
pgn_t settingGetPgn(const setting_t *val);
|
||||
|
@ -100,6 +101,13 @@ setting_min_t settingGetMin(const setting_t *val);
|
|||
// depends on the target and build options, but will always be an unsigned
|
||||
// integer (e.g. uintxx_t,)
|
||||
setting_max_t settingGetMax(const setting_t *val);
|
||||
// Returns the lookup table for the given setting. If the setting mode
|
||||
// is not MODE_LOOKUP, it returns NULL;
|
||||
const lookupTableEntry_t * settingLookupTable(const setting_t *val);
|
||||
// Returns the string in the table which corresponds to the value v
|
||||
// for the given setting. If the setting mode is not MODE_LOOKUP or
|
||||
// if the value is out of range, it returns NULL.
|
||||
const char * settingLookupValueName(const setting_t *val, unsigned v);
|
||||
// Returns the setting value as a const char * iff the setting is of type
|
||||
// VAR_STRING. Otherwise it returns NULL.
|
||||
const char * settingGetString(const setting_t *val);
|
||||
|
@ -109,4 +117,8 @@ const char * settingGetString(const setting_t *val);
|
|||
void settingSetString(const setting_t *val, const char *s, size_t size);
|
||||
// Returns the max string length (without counting the '\0' terminator)
|
||||
// for setting of type VAR_STRING. Otherwise it returns 0.
|
||||
setting_max_t settingGetStringMaxLength(const setting_t *val);
|
||||
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);
|
|
@ -349,6 +349,10 @@ groups:
|
|||
- name: rssi_invert
|
||||
field: rssiInvert
|
||||
type: bool
|
||||
- name: sbus_sync_interval
|
||||
field: sbusSyncInterval
|
||||
min: 10000
|
||||
max: 500
|
||||
- name: rc_smoothing
|
||||
field: rcSmoothing
|
||||
type: bool
|
||||
|
@ -545,6 +549,10 @@ groups:
|
|||
- name: rth_energy_margin
|
||||
min: 0
|
||||
max: 100
|
||||
- name: thr_comp_weight
|
||||
field: throttle_compensation_weight
|
||||
min: 0
|
||||
max: 2
|
||||
|
||||
- name: PG_BATTERY_PROFILES
|
||||
type: batteryProfile_t
|
||||
|
@ -1549,10 +1557,10 @@ groups:
|
|||
field: main_voltage_decimals
|
||||
min: 1
|
||||
max: 2
|
||||
- name: osd_attitude_angle_decimals
|
||||
field: attitude_angle_decimals
|
||||
min: 0
|
||||
max: 1
|
||||
- name: osd_coordinate_digits
|
||||
field: coordinate_digits
|
||||
min: 8
|
||||
max: 11
|
||||
|
||||
- name: osd_estimations_wind_compensation
|
||||
field: estimations_wind_compensation
|
||||
|
|
|
@ -57,7 +57,7 @@ void statsOnDisarm(void)
|
|||
statsConfigMutable()->stats_total_time += dt; //[s]
|
||||
statsConfigMutable()->stats_total_dist += (getTotalTravelDistance() - arm_distance_cm) / 100; //[m]
|
||||
#ifdef USE_ADC
|
||||
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) {
|
||||
if (feature(FEATURE_VBAT) && isAmperageConfigured()) {
|
||||
const uint32_t energy = getMWhDrawn() - arm_mWhDrawn;
|
||||
statsConfigMutable()->stats_total_energy += energy;
|
||||
flyingEnergy += energy;
|
||||
|
|
|
@ -71,7 +71,7 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
|
|||
.failsafe_recovery_delay = 5, // 0.5 seconds (plus 200ms explicit delay)
|
||||
.failsafe_off_delay = 200, // 20sec
|
||||
.failsafe_throttle = 1000, // default throttle off.
|
||||
.failsafe_throttle_low_delay = 100, // default throttle low delay for "just disarm" on failsafe condition
|
||||
.failsafe_throttle_low_delay = 0, // default throttle low delay for "just disarm" on failsafe condition
|
||||
.failsafe_procedure = FAILSAFE_PROCEDURE_AUTO_LANDING, // default full failsafe procedure
|
||||
.failsafe_fw_roll_angle = -200, // 20 deg left
|
||||
.failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive)
|
||||
|
|
|
@ -312,7 +312,7 @@ void mixTable(const float dT)
|
|||
|
||||
// Throttle compensation based on battery voltage
|
||||
if (feature(FEATURE_THR_VBAT_COMP) && feature(FEATURE_VBAT) && isAmperageConfigured())
|
||||
throttleCommand = MIN(throttleCommand * calculateThrottleCompensationFactor(), throttleMax);
|
||||
throttleCommand = MIN(throttleMin + (throttleCommand - throttleMin) * calculateThrottleCompensationFactor(), throttleMax);
|
||||
}
|
||||
|
||||
throttleRange = throttleMax - throttleMin;
|
||||
|
|
|
@ -137,8 +137,8 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
.D = 0, // not used
|
||||
},
|
||||
[PID_VEL_Z] = {
|
||||
.P = 100, // NAV_VEL_Z_P * 100
|
||||
.I = 50, // NAV_VEL_Z_I * 100
|
||||
.P = 100, // NAV_VEL_Z_P * 66.7
|
||||
.I = 50, // NAV_VEL_Z_I * 20
|
||||
.D = 10, // NAV_VEL_Z_D * 100
|
||||
}
|
||||
}
|
||||
|
@ -156,14 +156,14 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
},
|
||||
[PID_HEADING] = { 60, 0, 0 },
|
||||
[PID_POS_Z] = {
|
||||
.P = 50, // FW_POS_Z_P * 100
|
||||
.I = 0, // not used
|
||||
.D = 0, // not used
|
||||
.P = 40, // FW_POS_Z_P * 10
|
||||
.I = 5, // FW_POS_Z_I * 10
|
||||
.D = 10, // FW_POS_Z_D * 10
|
||||
},
|
||||
[PID_POS_XY] = {
|
||||
.P = 75, // FW_NAV_P * 100
|
||||
.I = 5, // FW_NAV_I * 100
|
||||
.D = 8, // FW_NAV_D * 100
|
||||
.P = 75, // FW_POS_XY_P * 100
|
||||
.I = 5, // FW_POS_XY_I * 100
|
||||
.D = 8, // FW_POS_XY_D * 100
|
||||
}
|
||||
}
|
||||
},
|
||||
|
|
|
@ -177,6 +177,7 @@ static void filterServos(void)
|
|||
if (!servoFilterIsSet) {
|
||||
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
biquadFilterInitLPF(&servoFilter[i], servoConfig()->servo_lowpass_freq, gyro.targetLooptime);
|
||||
biquadFilterReset(&servoFilter[i], servo[i]);
|
||||
}
|
||||
servoFilterIsSet = true;
|
||||
}
|
||||
|
|
|
@ -2605,7 +2605,7 @@ static void afatfs_createFileContinue(afatfsFile_t *file)
|
|||
|
||||
memcpy(entry->filename, opState->filename, FAT_FILENAME_LENGTH);
|
||||
entry->attrib = file->attrib;
|
||||
if (rtcGetDateTime(&now)) {
|
||||
if (rtcGetDateTimeLocal(&now)) {
|
||||
entry->creationDate = FAT_MAKE_DATE(now.year, now.month, now.day);
|
||||
entry->creationTime = FAT_MAKE_TIME(now.hours, now.minutes, now.seconds);
|
||||
} else {
|
||||
|
|
|
@ -488,25 +488,35 @@ static uint16_t osdConvertRSSI(void)
|
|||
|
||||
static void osdFormatCoordinate(char *buff, char sym, int32_t val)
|
||||
{
|
||||
const int coordinateMaxLength = 12; // 11 for the number + 1 for the symbol
|
||||
// This should be faster than pow(10, x). Make it available this
|
||||
// via extern rather than _GNU_SOURCE, since it should be more
|
||||
// portable.
|
||||
extern float exp10f(float);
|
||||
|
||||
// up to 4 for number + 1 for the symbol + null terminator + fill the rest with decimals
|
||||
const int coordinateMaxLength = osdConfig()->coordinate_digits + 1;
|
||||
|
||||
buff[0] = sym;
|
||||
int32_t integerPart = val / GPS_DEGREES_DIVIDER;
|
||||
int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
|
||||
// Latitude maximum integer width is 3 (-90) while
|
||||
// longitude maximum integer width is 4 (-180). We always
|
||||
// show 7 decimals, so we need to use 11 spaces because
|
||||
// we're embedding the decimal separator between the
|
||||
// two numbers.
|
||||
int written = tfp_sprintf(buff + 1, "%d", integerPart);
|
||||
tfp_sprintf(buff + 1 + written, "%07d", decimalPart);
|
||||
// longitude maximum integer width is 4 (-180).
|
||||
int integerDigits = tfp_sprintf(buff + 1, (integerPart == 0 && val < 0) ? "-%d" : "%d", integerPart);
|
||||
// We can show up to 7 digits in decimalPart. Remove
|
||||
// some if needed.
|
||||
int32_t decimalPart = abs(val % GPS_DEGREES_DIVIDER);
|
||||
int trim = 7 - MAX(coordinateMaxLength - 1 - integerDigits, 0);
|
||||
if (trim > 0) {
|
||||
decimalPart /= (int32_t)exp10f(trim);
|
||||
}
|
||||
int decimalDigits = tfp_sprintf(buff + 1 + integerDigits, "%d", decimalPart);
|
||||
// Embbed the decimal separator
|
||||
buff[1+written-1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
|
||||
buff[1+written] += SYM_ZERO_HALF_LEADING_DOT - '0';
|
||||
// Pad to 11 coordinateMaxLength
|
||||
while(1 + 7 + written < coordinateMaxLength) {
|
||||
buff[1 + 7 + written] = SYM_BLANK;
|
||||
written++;
|
||||
buff[1 + integerDigits - 1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
|
||||
buff[1 + integerDigits] += SYM_ZERO_HALF_LEADING_DOT - '0';
|
||||
// Fill up to coordinateMaxLength with zeros
|
||||
int total = 1 + integerDigits + decimalDigits;
|
||||
while(total < coordinateMaxLength) {
|
||||
buff[total] = '0';
|
||||
total++;
|
||||
}
|
||||
buff[coordinateMaxLength] = '\0';
|
||||
}
|
||||
|
@ -918,7 +928,7 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
|
|||
char symUnscaled;
|
||||
char symScaled;
|
||||
int maxDecimals;
|
||||
const int scaleMultiplier = 2;
|
||||
const unsigned scaleMultiplier = 2;
|
||||
// We try to reduce the scale when the POI will be around half the distance
|
||||
// between the center and the closers map edge, to avoid too much jumping
|
||||
const int scaleReductionMultiplier = MIN(midX - hMargin, midY - vMargin) / 2;
|
||||
|
@ -961,19 +971,22 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
|
|||
float poiCos = cos_approx(poiAngle);
|
||||
|
||||
// Now start looking for a valid scale that lets us draw everything
|
||||
for (int ii = 0; ii < 50; ii++, scale *= scaleMultiplier) {
|
||||
int ii;
|
||||
for (ii = 0; ii < 50; ii++) {
|
||||
// Calculate location of the aircraft in map
|
||||
int points = poiDistance / (float)(scale / charHeight);
|
||||
int points = poiDistance / ((float)scale / charHeight);
|
||||
|
||||
float pointsX = points * poiSin;
|
||||
int poiX = midX - roundf(pointsX / charWidth);
|
||||
if (poiX < minX || poiX > maxX) {
|
||||
scale *= scaleMultiplier;
|
||||
continue;
|
||||
}
|
||||
|
||||
float pointsY = points * poiCos;
|
||||
int poiY = midY + roundf(pointsY / charHeight);
|
||||
if (poiY < minY || poiY > maxY) {
|
||||
scale *= scaleMultiplier;
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -987,9 +1000,21 @@ static void osdDrawMap(int referenceHeading, uint8_t referenceSym, uint8_t cente
|
|||
} else {
|
||||
|
||||
uint8_t c;
|
||||
if (displayReadCharWithAttr(osdDisplayPort, poiY, poiY, &c, NULL) && c != SYM_BLANK) {
|
||||
if (displayReadCharWithAttr(osdDisplayPort, poiX, poiY, &c, NULL) && c != SYM_BLANK) {
|
||||
// Something else written here, increase scale. If the display doesn't support reading
|
||||
// back characters, we assume there's nothing.
|
||||
//
|
||||
// If we're close to the center, decrease scale. Otherwise increase it.
|
||||
uint8_t centerDeltaX = (maxX - minX) / (scaleMultiplier * 2);
|
||||
uint8_t centerDeltaY = (maxY - minY) / (scaleMultiplier * 2);
|
||||
if (poiX >= midX - centerDeltaX && poiX <= midX + centerDeltaX &&
|
||||
poiY >= midY - centerDeltaY && poiY <= midY + centerDeltaY &&
|
||||
scale > scaleMultiplier) {
|
||||
|
||||
scale /= scaleMultiplier;
|
||||
} else {
|
||||
scale *= scaleMultiplier;
|
||||
}
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
@ -1036,17 +1061,17 @@ static void osdDrawRadar(uint16_t *drawn, uint32_t *usedScale)
|
|||
|
||||
#endif
|
||||
|
||||
void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController) {
|
||||
static void osdFormatPidControllerOutput(char *buff, const char *label, const pidController_t *pidController, uint8_t scale, bool showDecimal) {
|
||||
strcpy(buff, label);
|
||||
uint8_t label_len = strlen(label);
|
||||
for (uint8_t i = label_len; i < 5; ++i) buff[i] = ' ';
|
||||
osdFormatCentiNumber(buff + 5, pidController->proportional, 0, 1, 0, 4);
|
||||
for (uint8_t i = strlen(label); i < 5; ++i) buff[i] = ' ';
|
||||
uint8_t decimals = showDecimal ? 1 : 0;
|
||||
osdFormatCentiNumber(buff + 5, pidController->proportional * scale, 0, decimals, 0, 4);
|
||||
buff[9] = ' ';
|
||||
osdFormatCentiNumber(buff + 10, pidController->integrator, 0, 1, 0, 4);
|
||||
osdFormatCentiNumber(buff + 10, pidController->integrator * scale, 0, decimals, 0, 4);
|
||||
buff[14] = ' ';
|
||||
osdFormatCentiNumber(buff + 15, pidController->derivative, 0, 1, 0, 4);
|
||||
osdFormatCentiNumber(buff + 15, pidController->derivative * scale, 0, decimals, 0, 4);
|
||||
buff[19] = ' ';
|
||||
osdFormatCentiNumber(buff + 20, pidController->output_constrained, 0, 1, 0, 4);
|
||||
osdFormatCentiNumber(buff + 20, pidController->output_constrained * scale, 0, decimals, 0, 4);
|
||||
buff[24] = '\0';
|
||||
}
|
||||
|
||||
|
@ -1210,14 +1235,23 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_HOME_DIR:
|
||||
{
|
||||
// There are 16 orientations for the home direction arrow.
|
||||
// so we use 22.5deg per image, where the 1st image is used
|
||||
// for [349, 11], the 2nd for [12, 33], etc...
|
||||
int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading());
|
||||
// Add 11 to the angle, so first character maps to [349, 11]
|
||||
int homeArrowDir = osdGetHeadingAngle(homeDirection + 11);
|
||||
unsigned arrowOffset = homeArrowDir * 2 / 45;
|
||||
buff[0] = SYM_ARROW_UP + arrowOffset;
|
||||
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) {
|
||||
// There are 16 orientations for the home direction arrow.
|
||||
// so we use 22.5deg per image, where the 1st image is used
|
||||
// for [349, 11], the 2nd for [12, 33], etc...
|
||||
int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading());
|
||||
// Add 11 to the angle, so first character maps to [349, 11]
|
||||
int homeArrowDir = osdGetHeadingAngle(homeDirection + 11);
|
||||
unsigned arrowOffset = homeArrowDir * 2 / 45;
|
||||
buff[0] = SYM_ARROW_UP + arrowOffset;
|
||||
} else {
|
||||
// No home or no fix or unknown heading, blink.
|
||||
// If we're unarmed, show the arrow pointing up so users can see the arrow
|
||||
// while configuring the OSD. If we're armed, show a '-' indicating that
|
||||
// we don't know the direction to home.
|
||||
buff[0] = ARMING_FLAG(ARMED) ? '-' : SYM_ARROW_UP;
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
|
||||
}
|
||||
buff[1] = 0;
|
||||
break;
|
||||
}
|
||||
|
@ -1552,19 +1586,19 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
|
||||
case OSD_ATTITUDE_ROLL:
|
||||
buff[0] = SYM_ROLL_LEVEL;
|
||||
if (ABS(attitude.values.roll) >= (osdConfig()->attitude_angle_decimals ? 1 : 10))
|
||||
if (ABS(attitude.values.roll) >= 1)
|
||||
buff[0] += (attitude.values.roll < 0 ? -1 : 1);
|
||||
osdFormatCentiNumber(buff + 1, ABS(attitude.values.roll) * 10, 0, osdConfig()->attitude_angle_decimals, 0, 2 + osdConfig()->attitude_angle_decimals);
|
||||
osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.roll)), 0, 1, 0, 3);
|
||||
break;
|
||||
|
||||
case OSD_ATTITUDE_PITCH:
|
||||
if (ABS(attitude.values.pitch) < (osdConfig()->attitude_angle_decimals ? 1 : 10))
|
||||
if (ABS(attitude.values.pitch) < 1)
|
||||
buff[0] = 'P';
|
||||
else if (attitude.values.pitch > 0)
|
||||
buff[0] = SYM_PITCH_DOWN;
|
||||
else if (attitude.values.pitch < 0)
|
||||
buff[0] = SYM_PITCH_UP;
|
||||
osdFormatCentiNumber(buff + 1, ABS(attitude.values.pitch) * 10, 0, osdConfig()->attitude_angle_decimals, 0, 2 + osdConfig()->attitude_angle_decimals);
|
||||
osdFormatCentiNumber(buff + 1, DECIDEGREES_TO_CENTIDEGREES(ABS(attitude.values.pitch)), 0, 1, 0, 3);
|
||||
break;
|
||||
|
||||
case OSD_ARTIFICIAL_HORIZON:
|
||||
|
@ -1601,7 +1635,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
osdCrosshairsBounds(&cx, &cy, &cl);
|
||||
crosshairsX = cx - elemPosX;
|
||||
crosshairsY = cy - elemPosY;
|
||||
crosshairsXEnd = crosshairsX + cl;
|
||||
crosshairsXEnd = crosshairsX + cl - 1;
|
||||
}
|
||||
|
||||
for (int x = -4; x <= 4; x++) {
|
||||
|
@ -1618,25 +1652,32 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
int wx = x + 4; // map the -4 to the 1st element in the writtenY array
|
||||
int pwy = writtenY[wx]; // previously written Y at this X value
|
||||
int wy = (y / AH_SYMBOL_COUNT);
|
||||
// Check if we're overlapping with the crosshairs. Saves a few
|
||||
// trips to the video driver.
|
||||
|
||||
unsigned chX = elemPosX + x;
|
||||
unsigned chY = elemPosY + wy;
|
||||
uint8_t c;
|
||||
|
||||
// Check if we're overlapping with the crosshairs directly. Saves a few
|
||||
// trips to the video driver. Also, test for other arbitrary overlapping
|
||||
// elements if the display supports reading back characters.
|
||||
bool overlaps = (crosshairsVisible &&
|
||||
crosshairsY == wy &&
|
||||
x >= crosshairsX && x <= crosshairsXEnd);
|
||||
x >= crosshairsX && x <= crosshairsXEnd) ||
|
||||
(pwy != wy && displayReadCharWithAttr(osdDisplayPort, chX, chY, &c, NULL) && c != SYM_BLANK);
|
||||
|
||||
if (y >= 0 && y <= 80 && !overlaps) {
|
||||
if (pwy != -1 && pwy != wy) {
|
||||
// Erase previous character at pwy rows below elemPosY
|
||||
// iff we're writing at a different Y coordinate. Otherwise
|
||||
// we just overwrite the previous one.
|
||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + pwy, SYM_BLANK);
|
||||
displayWriteChar(osdDisplayPort, chX, elemPosY + pwy, SYM_BLANK);
|
||||
}
|
||||
uint8_t ch = SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT);
|
||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + wy, ch);
|
||||
displayWriteChar(osdDisplayPort, chX, chY, ch);
|
||||
writtenY[wx] = wy;
|
||||
} else {
|
||||
if (pwy != -1) {
|
||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + pwy, SYM_BLANK);
|
||||
displayWriteChar(osdDisplayPort, chX, elemPosY + pwy, SYM_BLANK);
|
||||
writtenY[wx] = -1;
|
||||
}
|
||||
}
|
||||
|
@ -1888,35 +1929,35 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
case OSD_FW_ALT_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt);
|
||||
osdFormatPidControllerOutput(buff, "PZO", &nav_pids->fw_alt, 10, true); // display requested pitch degrees
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_FW_POS_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav);
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers(); // display requested roll degrees
|
||||
osdFormatPidControllerOutput(buff, "PXYO", &nav_pids->fw_nav, 1, true);
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_MC_VEL_Z_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z]);
|
||||
osdFormatPidControllerOutput(buff, "VZO", &nav_pids->vel[Z], 100, false); // display throttle adjustment µs
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_MC_VEL_X_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X]);
|
||||
osdFormatPidControllerOutput(buff, "VXO", &nav_pids->vel[X], 100, false); // display requested acceleration cm/s^2
|
||||
break;
|
||||
}
|
||||
|
||||
case OSD_MC_VEL_Y_PID_OUTPUTS:
|
||||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y]);
|
||||
osdFormatPidControllerOutput(buff, "VYO", &nav_pids->vel[Y], 100, false); // display requested acceleration cm/s^2
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -1924,11 +1965,12 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
{
|
||||
const navigationPIDControllers_t *nav_pids = getNavigationPIDControllers();
|
||||
strcpy(buff, "POSO ");
|
||||
osdFormatCentiNumber(buff + 5, nav_pids->pos[X].output_constrained, 0, 1, 0, 4);
|
||||
// display requested velocity cm/s
|
||||
tfp_sprintf(buff + 5, "%4d", lrintf(nav_pids->pos[X].output_constrained * 100));
|
||||
buff[9] = ' ';
|
||||
osdFormatCentiNumber(buff + 10, nav_pids->pos[Y].output_constrained, 0, 1, 0, 4);
|
||||
tfp_sprintf(buff + 10, "%4d", lrintf(nav_pids->pos[Y].output_constrained * 100));
|
||||
buff[14] = ' ';
|
||||
osdFormatCentiNumber(buff + 15, nav_pids->pos[Z].output_constrained, 0, 1, 0, 4);
|
||||
tfp_sprintf(buff + 15, "%4d", lrintf(nav_pids->pos[Z].output_constrained * 100));
|
||||
buff[19] = '\0';
|
||||
break;
|
||||
}
|
||||
|
@ -1955,9 +1997,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
{
|
||||
// RTC not configured will show 00:00
|
||||
dateTime_t dateTime;
|
||||
if (rtcGetDateTime(&dateTime)) {
|
||||
dateTimeUTCToLocal(&dateTime, &dateTime);
|
||||
}
|
||||
rtcGetDateTimeLocal(&dateTime);
|
||||
buff[0] = SYM_CLOCK;
|
||||
tfp_sprintf(buff + 1, "%02u:%02u", dateTime.hours, dateTime.minutes);
|
||||
break;
|
||||
|
@ -2422,9 +2462,9 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
|
||||
osdConfig->units = OSD_UNIT_METRIC;
|
||||
osdConfig->main_voltage_decimals = 1;
|
||||
osdConfig->attitude_angle_decimals = 0;
|
||||
|
||||
osdConfig->estimations_wind_compensation = true;
|
||||
osdConfig->coordinate_digits = 9;
|
||||
}
|
||||
|
||||
static void osdSetNextRefreshIn(uint32_t timeMs) {
|
||||
|
@ -2652,13 +2692,21 @@ static void osdShowArmed(void)
|
|||
displayWrite(osdDisplayPort, 12, y, "ARMED");
|
||||
y += 2;
|
||||
|
||||
if (STATE(GPS_FIX)) {
|
||||
osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat);
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf);
|
||||
osdFormatCoordinate(buf, SYM_LON, gpsSol.llh.lon);
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf);
|
||||
y += 3;
|
||||
#if defined(USE_GPS)
|
||||
if (feature(FEATURE_GPS)) {
|
||||
if (STATE(GPS_FIX_HOME)) {
|
||||
osdFormatCoordinate(buf, SYM_LAT, GPS_home.lat);
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf);
|
||||
osdFormatCoordinate(buf, SYM_LON, GPS_home.lon);
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 1, buf);
|
||||
y += 3;
|
||||
} else {
|
||||
strcpy(buf, "!NO HOME POSITION!");
|
||||
displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf);
|
||||
y += 1;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
if (rtcGetDateTime(&dt)) {
|
||||
dateTimeFormatLocal(buf, &dt);
|
||||
|
|
|
@ -163,7 +163,6 @@ typedef struct osdConfig_s {
|
|||
|
||||
// Preferences
|
||||
uint8_t main_voltage_decimals;
|
||||
uint8_t attitude_angle_decimals;
|
||||
uint8_t ahi_reverse_roll;
|
||||
uint8_t crosshairs_style; // from osd_crosshairs_style_e
|
||||
uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e
|
||||
|
@ -174,6 +173,7 @@ typedef struct osdConfig_s {
|
|||
uint8_t stats_energy_unit; // from osd_stats_energy_unit_e
|
||||
|
||||
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
|
||||
uint8_t coordinate_digits;
|
||||
} osdConfig_t;
|
||||
|
||||
PG_DECLARE(osdConfig_t, osdConfig);
|
||||
|
|
|
@ -100,7 +100,7 @@ static void rcdeviceCameraUpdateTime(void)
|
|||
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_DEVICE_SETTINGS_ACCESS) &&
|
||||
!hasSynchronizedTime && retries < 3) {
|
||||
|
||||
if (rtcGetDateTime(&dt)) {
|
||||
if (rtcGetDateTimeLocal(&dt)) {
|
||||
retries++;
|
||||
tfp_sprintf(buf, "%04d%02d%02dT%02d%02d%02d.0",
|
||||
dt.year, dt.month, dt.day,
|
||||
|
|
|
@ -200,7 +200,7 @@ static void saPrintSettings(void)
|
|||
|
||||
int saDacToPowerIndex(int dac)
|
||||
{
|
||||
for (int idx = 3 ; idx >= 0 ; idx--) {
|
||||
for (int idx = VTX_SMARTAUDIO_POWER_COUNT - 1 ; idx >= 0 ; idx--) {
|
||||
if (saPowerTable[idx].valueV1 <= dac) {
|
||||
return idx;
|
||||
}
|
||||
|
|
|
@ -60,7 +60,7 @@ static vtxDevice_t vtxTramp = {
|
|||
.vTable = &trampVTable,
|
||||
.capability.bandCount = VTX_TRAMP_BAND_COUNT,
|
||||
.capability.channelCount = VTX_TRAMP_CHANNEL_COUNT,
|
||||
.capability.powerCount = sizeof(trampPowerTable),
|
||||
.capability.powerCount = VTX_TRAMP_POWER_COUNT,
|
||||
.bandNames = (char **)vtx58BandNames,
|
||||
.channelNames = (char **)vtx58ChannelNames,
|
||||
.powerNames = (char **)trampPowerNames,
|
||||
|
@ -196,7 +196,7 @@ bool trampCommitChanges(void)
|
|||
// return false if index out of range
|
||||
static bool trampDevSetPowerByIndex(uint8_t index)
|
||||
{
|
||||
if (index > 0 && index <= sizeof(trampPowerTable)) {
|
||||
if (index > 0 && index <= VTX_TRAMP_POWER_COUNT) {
|
||||
trampSetRFPower(trampPowerTable[index - 1]);
|
||||
trampCommitChanges();
|
||||
return true;
|
||||
|
|
|
@ -15,10 +15,13 @@
|
|||
* 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_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_SET_SETTING 0x1004 //in message Sets the value for a setting
|
||||
#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_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_MOTOR_MIXER 0x1005
|
||||
#define MSP2_COMMON_SET_MOTOR_MIXER 0x1006
|
||||
|
||||
#define MSP2_COMMON_SETTING_INFO 0x1007 //in/out message Returns info about a setting (PG, type, flags, min/max, etc..).
|
||||
#define MSP2_COMMON_PG_LIST 0x1008 //in/out message Returns a list of the PG ids used by the settings
|
|
@ -1816,7 +1816,7 @@ void updateActualAltitudeAndClimbRate(bool estimateValid, float newAltitude, flo
|
|||
}
|
||||
|
||||
#if defined(NAV_BLACKBOX)
|
||||
navLatestActualPosition[Z] = constrain(navGetCurrentActualPositionAndVelocity()->pos.z, -32678, 32767);
|
||||
navLatestActualPosition[Z] = navGetCurrentActualPositionAndVelocity()->pos.z;
|
||||
navActualVelocity[Z] = constrain(navGetCurrentActualPositionAndVelocity()->vel.z, -32678, 32767);
|
||||
#endif
|
||||
}
|
||||
|
@ -2969,9 +2969,9 @@ void navigationUsePIDs(void)
|
|||
(float)pidProfile()->bank_fw.pid[PID_POS_XY].I / 100.0f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_XY].D / 100.0f);
|
||||
|
||||
navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P / 9.80665f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].I / 9.80665f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 9.80665f);
|
||||
navPidInit(&posControl.pids.fw_alt, (float)pidProfile()->bank_fw.pid[PID_POS_Z].P / 10.0f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].I / 10.0f,
|
||||
(float)pidProfile()->bank_fw.pid[PID_POS_Z].D / 10.0f);
|
||||
}
|
||||
|
||||
void navigationInit(void)
|
||||
|
|
|
@ -325,7 +325,7 @@ static void telemetryRX(void)
|
|||
case 2:
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
uint16_t gpsspeed = (gpsSol.groundSpeed*9L)/250L;
|
||||
int16_t course = (gpsSol.groundCourse+360)%360;
|
||||
int16_t course = (gpsSol.groundCourse/10 + 360)%360;
|
||||
#ifdef USE_NAV
|
||||
int32_t alt = getEstimatedActualPosition(Z);
|
||||
#else
|
||||
|
|
|
@ -100,7 +100,7 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
static uint8_t rcSampleIndex = 0;
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 4);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 5);
|
||||
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
|
@ -129,6 +129,7 @@ PG_RESET_TEMPLATE(rxConfig_t, rxConfig,
|
|||
.rssi_channel = 0,
|
||||
.rssi_scale = RSSI_SCALE_DEFAULT,
|
||||
.rssiInvert = 0,
|
||||
.sbusSyncInterval = SBUS_DEFAULT_INTERFRAME_DELAY_US,
|
||||
.rcSmoothing = 1,
|
||||
);
|
||||
|
||||
|
|
|
@ -121,7 +121,7 @@ typedef struct rxConfig_s {
|
|||
uint8_t rssi_channel;
|
||||
uint8_t rssi_scale;
|
||||
uint8_t rssiInvert;
|
||||
uint16_t __reserved; // was micrd
|
||||
uint16_t sbusSyncInterval;
|
||||
uint16_t mincheck; // minimum rc end
|
||||
uint16_t maxcheck; // maximum rc end
|
||||
uint16_t rx_min_usec;
|
||||
|
|
|
@ -52,8 +52,6 @@
|
|||
* time to send frame: 3ms.
|
||||
*/
|
||||
|
||||
#define SBUS_MIN_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case
|
||||
|
||||
#define SBUS_FRAME_SIZE (SBUS_CHANNEL_DATA_LENGTH + 2)
|
||||
|
||||
#define SBUS_FRAME_BEGIN_BYTE 0x0F
|
||||
|
@ -114,7 +112,7 @@ static void sbusDataReceive(uint16_t c, void *data)
|
|||
sbusFrameData->lastActivityTimeUs = currentTimeUs;
|
||||
|
||||
// Handle inter-frame gap. We dwell in STATE_SBUS_WAIT_SYNC state ignoring all incoming bytes until we get long enough quite period on the wire
|
||||
if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= SBUS_MIN_INTERFRAME_DELAY_US) {
|
||||
if (sbusFrameData->state == STATE_SBUS_WAIT_SYNC && timeSinceLastByteUs >= rxConfig()->sbusSyncInterval) {
|
||||
DEBUG_SET(DEBUG_SBUS, DEBUG_SBUS_INTERFRAME_TIME, timeSinceLastByteUs);
|
||||
sbusFrameData->state = STATE_SBUS_SYNC;
|
||||
}
|
||||
|
|
|
@ -17,4 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define SBUS_DEFAULT_INTERFRAME_DELAY_US 3000 // According to FrSky interframe is 6.67ms, we go smaller just in case
|
||||
|
||||
bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
|
|
|
@ -56,19 +56,19 @@
|
|||
#include "io/beeper.h"
|
||||
|
||||
|
||||
#define ADCVREF 3300 // in mV (3300 = 3.3V)
|
||||
#define ADCVREF 3300 // in mV (3300 = 3.3V)
|
||||
|
||||
#define VBATT_CELL_FULL_MAX_DIFF 10 // Max difference with cell max voltage for the battery to be considered full (10mV steps)
|
||||
#define VBATT_PRESENT_THRESHOLD 100 // Minimum voltage to consider battery present
|
||||
#define VBATT_STABLE_DELAY 40 // Delay after connecting battery to begin monitoring
|
||||
#define VBATT_HYSTERESIS 10 // Batt Hysteresis of +/-100mV for changing battery state
|
||||
#define VBATT_LPF_FREQ 1 // Battery voltage filtering cutoff
|
||||
#define AMPERAGE_LPF_FREQ 1 // Battery current filtering cutoff
|
||||
#define VBATT_CELL_FULL_MAX_DIFF 10 // Max difference with cell max voltage for the battery to be considered full (10mV steps)
|
||||
#define VBATT_PRESENT_THRESHOLD 100 // Minimum voltage to consider battery present
|
||||
#define VBATT_STABLE_DELAY 40 // Delay after connecting battery to begin monitoring
|
||||
#define VBATT_HYSTERESIS 10 // Batt Hysteresis of +/-100mV for changing battery state
|
||||
#define VBATT_LPF_FREQ 1 // Battery voltage filtering cutoff
|
||||
#define AMPERAGE_LPF_FREQ 1 // Battery current filtering cutoff
|
||||
#define IMPEDANCE_STABLE_SAMPLE_COUNT_THRESH 10 // Minimum sample count to consider calculated power supply impedance as stable
|
||||
|
||||
|
||||
// Battery monitoring stuff
|
||||
static uint8_t batteryCellCount = 3; // cell count
|
||||
static uint8_t batteryCellCount; // cell count
|
||||
static uint16_t batteryFullVoltage;
|
||||
static uint16_t batteryWarningVoltage;
|
||||
static uint16_t batteryCriticalVoltage;
|
||||
|
@ -77,17 +77,15 @@ static bool batteryUseCapacityThresholds = false;
|
|||
static bool batteryFullWhenPluggedIn = false;
|
||||
static bool profileAutoswitchDisable = false;
|
||||
|
||||
static uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered)
|
||||
static uint16_t vbatLatestADC = 0; // most recent unsmoothed raw reading from vbat ADC
|
||||
static uint16_t amperageLatestADC = 0; // most recent raw reading from current ADC
|
||||
static uint16_t powerSupplyImpedance = 0; // calculated impedance in milliohm
|
||||
static uint16_t sagCompensatedVBat = 0; // calculated no load vbat
|
||||
static uint16_t vbat = 0; // battery voltage in 0.1V steps (filtered)
|
||||
static uint16_t powerSupplyImpedance = 0; // calculated impedance in milliohm
|
||||
static uint16_t sagCompensatedVBat = 0; // calculated no load vbat
|
||||
static bool powerSupplyImpedanceIsValid = false;
|
||||
|
||||
static int16_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
|
||||
static int32_t power = 0; // power draw in cW (0.01W resolution)
|
||||
static int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
|
||||
static int32_t mWhDrawn = 0; // energy (milliWatt hours) drawn from the battery since start
|
||||
static int16_t amperage = 0; // amperage read by current sensor in centiampere (1/100th A)
|
||||
static int32_t power = 0; // power draw in cW (0.01W resolution)
|
||||
static int32_t mAhDrawn = 0; // milliampere hours drawn from the battery since start
|
||||
static int32_t mWhDrawn = 0; // energy (milliWatt hours) drawn from the battery since start
|
||||
|
||||
batteryState_e batteryState;
|
||||
const batteryProfile_t *currentBatteryProfile;
|
||||
|
@ -133,23 +131,12 @@ PG_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig,
|
|||
|
||||
.cruise_power = 0,
|
||||
.idle_power = 0,
|
||||
.rth_energy_margin = 5
|
||||
.rth_energy_margin = 5,
|
||||
|
||||
.throttle_compensation_weight = 1.0f
|
||||
|
||||
);
|
||||
|
||||
uint16_t batteryAdcToVoltage(uint16_t src)
|
||||
{
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.01V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 1100 = 11:1 voltage divider (10k:1k)
|
||||
return((uint64_t)src * batteryMetersConfig()->voltage_scale * ADCVREF / (0xFFF * 1000));
|
||||
}
|
||||
|
||||
int16_t currentSensorToCentiamps(uint16_t src)
|
||||
{
|
||||
int32_t microvolts = ((uint32_t)src * ADCVREF * 100) / 0xFFF * 10 - (int32_t)batteryMetersConfig()->current.offset * 100;
|
||||
return microvolts / batteryMetersConfig()->current.scale; // current in 0.01A steps
|
||||
}
|
||||
|
||||
void batteryInit(void)
|
||||
{
|
||||
batteryState = BATTERY_NOT_PRESENT;
|
||||
|
@ -184,9 +171,8 @@ static int8_t profileDetect() {
|
|||
qsort(profile_comp_array, MAX_BATTERY_PROFILE_COUNT, sizeof(*profile_comp_array), (int (*)(const void *, const void *))profile_compare);
|
||||
|
||||
// Return index of the first profile where vbat <= profile_max_voltage
|
||||
uint16_t vbatLatest = batteryAdcToVoltage(vbatLatestADC);
|
||||
for (uint8_t i = 0; i < MAX_BATTERY_PROFILE_COUNT; ++i)
|
||||
if ((profile_comp_array[i].max_voltage > 0) && (vbatLatest <= profile_comp_array[i].max_voltage))
|
||||
if ((profile_comp_array[i].max_voltage > 0) && (vbat <= profile_comp_array[i].max_voltage))
|
||||
return profile_comp_array[i].profile_index;
|
||||
|
||||
// No matching profile found
|
||||
|
@ -203,27 +189,35 @@ void setBatteryProfile(uint8_t profileIndex)
|
|||
|
||||
void activateBatteryProfile(void)
|
||||
{
|
||||
batteryInit();
|
||||
static int8_t previous_battery_profile_index = -1;
|
||||
// Don't call batteryInit if the battery profile was not changed to prevent batteryCellCount to be reset while adjusting board alignment
|
||||
// causing the beeper to be silent when it is disabled while the board is connected through USB (beeper -ON_USB)
|
||||
if (systemConfig()->current_battery_profile_index != previous_battery_profile_index) {
|
||||
batteryInit();
|
||||
previous_battery_profile_index = systemConfig()->current_battery_profile_index;
|
||||
}
|
||||
}
|
||||
|
||||
static void updateBatteryVoltage(timeUs_t timeDelta)
|
||||
static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
|
||||
{
|
||||
uint16_t vbatSample;
|
||||
static pt1Filter_t vbatFilterState;
|
||||
|
||||
// store the battery voltage with some other recent battery voltage readings
|
||||
vbatSample = vbatLatestADC = adcGetChannel(ADC_BATTERY);
|
||||
vbatSample = pt1FilterApply4(&vbatFilterState, vbatSample, VBATT_LPF_FREQ, timeDelta * 1e-6f);
|
||||
vbat = batteryAdcToVoltage(vbatSample);
|
||||
// calculate battery voltage based on ADC reading
|
||||
// result is Vbatt in 0.01V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 1100 = 11:1 voltage divider (10k:1k)
|
||||
vbat = (uint64_t)adcGetChannel(ADC_BATTERY) * batteryMetersConfig()->voltage_scale * ADCVREF / (0xFFF * 1000);
|
||||
|
||||
if (justConnected) {
|
||||
pt1FilterReset(&vbatFilterState, vbat);
|
||||
} else {
|
||||
vbat = pt1FilterApply4(&vbatFilterState, vbat, VBATT_LPF_FREQ, timeDelta * 1e-6f);
|
||||
}
|
||||
}
|
||||
|
||||
void batteryUpdate(timeUs_t timeDelta)
|
||||
{
|
||||
updateBatteryVoltage(timeDelta);
|
||||
|
||||
/* battery has just been connected*/
|
||||
if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD)
|
||||
{
|
||||
if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD) {
|
||||
|
||||
/* Actual battery state is calculated below, this is really BATTERY_PRESENT */
|
||||
batteryState = BATTERY_OK;
|
||||
/* wait for VBatt to stabilise then we can calc number of cells
|
||||
|
@ -231,7 +225,7 @@ void batteryUpdate(timeUs_t timeDelta)
|
|||
We only do this on the ground so don't care if we do block, not
|
||||
worse than original code anyway*/
|
||||
delay(VBATT_STABLE_DELAY);
|
||||
updateBatteryVoltage(timeDelta);
|
||||
updateBatteryVoltage(timeDelta, true);
|
||||
|
||||
int8_t detectedProfileIndex = -1;
|
||||
if (feature(FEATURE_BAT_PROFILE_AUTOSWITCH) && (!profileAutoswitchDisable))
|
||||
|
@ -244,7 +238,7 @@ void batteryUpdate(timeUs_t timeDelta)
|
|||
} else if (currentBatteryProfile->cells > 0)
|
||||
batteryCellCount = currentBatteryProfile->cells;
|
||||
else {
|
||||
batteryCellCount = (batteryAdcToVoltage(vbatLatestADC) / currentBatteryProfile->voltage.cellDetect) + 1;
|
||||
batteryCellCount = (vbat / currentBatteryProfile->voltage.cellDetect) + 1;
|
||||
if (batteryCellCount > 8) batteryCellCount = 8; // something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
|
||||
}
|
||||
|
||||
|
@ -252,17 +246,20 @@ void batteryUpdate(timeUs_t timeDelta)
|
|||
batteryWarningVoltage = batteryCellCount * currentBatteryProfile->voltage.cellWarning;
|
||||
batteryCriticalVoltage = batteryCellCount * currentBatteryProfile->voltage.cellMin;
|
||||
|
||||
batteryFullWhenPluggedIn = batteryAdcToVoltage(vbatLatestADC) >= (batteryFullVoltage - batteryCellCount * VBATT_CELL_FULL_MAX_DIFF);
|
||||
batteryUseCapacityThresholds = feature(FEATURE_CURRENT_METER) && batteryFullWhenPluggedIn && (currentBatteryProfile->capacity.value > 0) &&
|
||||
batteryFullWhenPluggedIn = vbat >= (batteryFullVoltage - batteryCellCount * VBATT_CELL_FULL_MAX_DIFF);
|
||||
batteryUseCapacityThresholds = isAmperageConfigured() && batteryFullWhenPluggedIn && (currentBatteryProfile->capacity.value > 0) &&
|
||||
(currentBatteryProfile->capacity.warning > 0) && (currentBatteryProfile->capacity.critical > 0);
|
||||
|
||||
}
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD */
|
||||
else if (batteryState != BATTERY_NOT_PRESENT && vbat <= VBATT_PRESENT_THRESHOLD) {
|
||||
batteryState = BATTERY_NOT_PRESENT;
|
||||
batteryCellCount = 0;
|
||||
batteryWarningVoltage = 0;
|
||||
batteryCriticalVoltage = 0;
|
||||
} else {
|
||||
updateBatteryVoltage(timeDelta, false);
|
||||
|
||||
/* battery has been disconnected - can take a while for filter cap to disharge so we use a threshold of VBATT_PRESENT_THRESHOLD */
|
||||
if (batteryState != BATTERY_NOT_PRESENT && vbat <= VBATT_PRESENT_THRESHOLD) {
|
||||
batteryState = BATTERY_NOT_PRESENT;
|
||||
batteryCellCount = 0;
|
||||
batteryWarningVoltage = 0;
|
||||
batteryCriticalVoltage = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (batteryState != BATTERY_NOT_PRESENT) {
|
||||
|
@ -358,12 +355,7 @@ uint16_t getBatterySagCompensatedVoltage(void)
|
|||
|
||||
float calculateThrottleCompensationFactor(void)
|
||||
{
|
||||
return batteryFullVoltage / sagCompensatedVBat;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltageLatestADC(void)
|
||||
{
|
||||
return vbatLatestADC;
|
||||
return 1.0f + ((float)batteryFullVoltage / sagCompensatedVBat - 1.0f) * batteryMetersConfig()->throttle_compensation_weight;
|
||||
}
|
||||
|
||||
uint16_t getBatteryWarningVoltage(void)
|
||||
|
@ -415,11 +407,6 @@ int16_t getAmperage(void)
|
|||
return amperage;
|
||||
}
|
||||
|
||||
int16_t getAmperageLatestADC(void)
|
||||
{
|
||||
return amperageLatestADC;
|
||||
}
|
||||
|
||||
int32_t getPower(void)
|
||||
{
|
||||
return power;
|
||||
|
@ -443,10 +430,12 @@ void currentMeterUpdate(timeUs_t timeDelta)
|
|||
|
||||
switch (batteryMetersConfig()->current.type) {
|
||||
case CURRENT_SENSOR_ADC:
|
||||
amperageLatestADC = adcGetChannel(ADC_CURRENT);
|
||||
amperageLatestADC = pt1FilterApply4(&erageFilterState, amperageLatestADC, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f);
|
||||
amperage = currentSensorToCentiamps(amperageLatestADC);
|
||||
break;
|
||||
{
|
||||
int32_t microvolts = ((uint32_t)adcGetChannel(ADC_CURRENT) * ADCVREF * 100) / 0xFFF * 10 - (int32_t)batteryMetersConfig()->current.offset * 100;
|
||||
amperage = microvolts / batteryMetersConfig()->current.scale; // current in 0.01A steps
|
||||
amperage = pt1FilterApply4(&erageFilterState, amperage, AMPERAGE_LPF_FREQ, timeDelta * 1e-6f);
|
||||
break;
|
||||
}
|
||||
case CURRENT_SENSOR_VIRTUAL:
|
||||
amperage = batteryMetersConfig()->current.offset;
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
|
@ -559,7 +548,7 @@ uint8_t calculateBatteryPercentage(void)
|
|||
if (batteryState == BATTERY_NOT_PRESENT)
|
||||
return 0;
|
||||
|
||||
if (batteryFullWhenPluggedIn && feature(FEATURE_CURRENT_METER) && (currentBatteryProfile->capacity.value > 0) && (currentBatteryProfile->capacity.critical > 0)) {
|
||||
if (batteryFullWhenPluggedIn && isAmperageConfigured() && (currentBatteryProfile->capacity.value > 0) && (currentBatteryProfile->capacity.critical > 0)) {
|
||||
uint32_t capacityDiffBetweenFullAndEmpty = currentBatteryProfile->capacity.value - currentBatteryProfile->capacity.critical;
|
||||
return constrain(batteryRemainingCapacity * 100 / capacityDiffBetweenFullAndEmpty, 0, 100);
|
||||
} else
|
||||
|
|
|
@ -76,6 +76,8 @@ typedef struct batteryMetersConfig_s {
|
|||
uint16_t idle_power; // power drawn by the system when the motor(s) are stopped (cW)
|
||||
uint8_t rth_energy_margin; // Energy that should be left after RTH (%), used for remaining time/distance before RTH
|
||||
|
||||
float throttle_compensation_weight;
|
||||
|
||||
} batteryMetersConfig_t;
|
||||
|
||||
typedef struct batteryProfile_s {
|
||||
|
@ -125,7 +127,6 @@ bool isPowerSupplyImpedanceValid(void);
|
|||
uint16_t getBatteryVoltage(void);
|
||||
uint16_t getBatteryRawVoltage(void);
|
||||
uint16_t getBatterySagCompensatedVoltage(void);
|
||||
uint16_t getBatteryVoltageLatestADC(void);
|
||||
uint16_t getBatteryWarningVoltage(void);
|
||||
uint8_t getBatteryCellCount(void);
|
||||
uint16_t getBatteryRawAverageCellVoltage(void);
|
||||
|
@ -136,7 +137,6 @@ uint16_t getPowerSupplyImpedance(void);
|
|||
|
||||
bool isAmperageConfigured(void);
|
||||
int16_t getAmperage(void);
|
||||
int16_t getAmperageLatestADC(void);
|
||||
int32_t getPower(void);
|
||||
int32_t getMAhDrawn(void);
|
||||
int32_t getMWhDrawn(void);
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE_2_SHARES_UART3
|
||||
|
@ -85,10 +83,13 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define INVERTER_PIN_UART1_RX PC0 // PC0 used as inverter select GPIO
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
|
|
@ -27,8 +27,6 @@
|
|||
#define BEEPER PB2
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART1 PC3
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
@ -69,9 +67,12 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PA8
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define INVERTER_PIN_UART1_RX PC3
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
|
|
@ -81,6 +81,8 @@
|
|||
#define VBUS_SENSING_ENABLED
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -90,15 +92,13 @@
|
|||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3 //Shared with PPM
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define INVERTER_PIN_UART2 PC15
|
||||
#define INVERTER_PIN_UART2_RX PC15
|
||||
|
||||
//Telemetry
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define INVERTER_PIN_UART3 PC14
|
||||
#define INVERTER_PIN_UART3_RX PC14
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
|
|
|
@ -27,9 +27,6 @@
|
|||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// PC13 used as inverter select GPIO for UART2
|
||||
#define INVERTER_PIN_UART2 PC13
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
@ -71,6 +68,7 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
|
@ -80,7 +78,8 @@
|
|||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
// PC13 used as inverter select GPIO for UART2
|
||||
#define INVERTER_PIN_UART2_RX PC13
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
|
|
@ -35,9 +35,6 @@
|
|||
#define BEEPER_OPT PB7
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART6 PB15
|
||||
//#define INVERTER_PIN_UART1 PC9
|
||||
|
||||
// MPU6500 interrupt
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define GYRO_INT_EXTI PC5
|
||||
|
@ -92,9 +89,12 @@
|
|||
//#define VBUS_SENSING_PIN PA8
|
||||
//#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
//#define INVERTER_PIN_UART1_TX PC9
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
@ -103,6 +103,7 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
#define INVERTER_PIN_UART6_RX PB15
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
|
|
@ -32,7 +32,6 @@
|
|||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_3
|
||||
|
@ -78,10 +77,14 @@
|
|||
#define WS2811_DMA_CHANNEL DMA_Channel_2
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#define INVERTER_PIN_UART1_RX PC0 // PC0 used as inverter select GPIO
|
||||
|
||||
#if defined( CLRACINGF4AIRV2) || defined(CLRACINGF4AIRV3)
|
||||
#define USE_UART2
|
||||
|
|
|
@ -36,8 +36,6 @@
|
|||
|
||||
#define BEEPER PC5
|
||||
|
||||
#define INVERTER_PIN_UART2 PB2 // PB2 used as inverter select GPIO
|
||||
|
||||
#define MPU6000_CS_PIN PC4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
@ -83,6 +81,8 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PA9
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PB7
|
||||
#define UART1_TX_PIN PB6
|
||||
|
@ -91,6 +91,7 @@
|
|||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
#define INVERTER_PIN_UART2_RX PB2 // PB2 used as inverter select GPIO
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
|
|
@ -27,9 +27,6 @@
|
|||
#define BEEPER PE5
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART6 PD3
|
||||
|
||||
|
||||
|
||||
// MPU6000 interrupts
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
@ -74,6 +71,8 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PA9
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PB7
|
||||
#define UART1_TX_PIN PB6
|
||||
|
@ -95,6 +94,7 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
#define INVERTER_PIN_UART6_RX PD3
|
||||
|
||||
#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART6
|
||||
|
||||
|
|
|
@ -93,7 +93,6 @@ void targetConfiguration(void)
|
|||
failsafeConfigMutable()->failsafe_recovery_delay = 5;
|
||||
failsafeConfigMutable()->failsafe_off_delay = 200;
|
||||
failsafeConfigMutable()->failsafe_throttle = 1200;
|
||||
failsafeConfigMutable()->failsafe_throttle_low_delay = 100;
|
||||
failsafeConfigMutable()->failsafe_procedure = FAILSAFE_PROCEDURE_RTH;
|
||||
|
||||
boardAlignmentMutable()->rollDeciDegrees = 0;
|
||||
|
|
|
@ -61,6 +61,8 @@
|
|||
#define USE_VCP
|
||||
// #define VBUS_SENSING_PIN PA9
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -69,11 +71,10 @@
|
|||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define INVERTER_PIN_UART3 PA8
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define INVERTER_PIN_UART3_RX PA8
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PC11
|
||||
|
|
|
@ -78,6 +78,8 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -85,7 +87,7 @@
|
|||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define INVERTER_PIN_UART3 PC15
|
||||
#define INVERTER_PIN_UART3_RX PC15
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PA0
|
||||
|
|
|
@ -105,6 +105,8 @@
|
|||
//#define VBUS_SENSING_PIN PA8
|
||||
//#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -113,9 +115,9 @@
|
|||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
#if defined(FF_PIKOF4OSD)
|
||||
#define INVERTER_PIN_UART3 PC3
|
||||
#define INVERTER_PIN_UART3_RX PC3
|
||||
#else
|
||||
#define INVERTER_PIN_UART3 PC8
|
||||
#define INVERTER_PIN_UART3_RX PC8
|
||||
#endif
|
||||
|
||||
#define USE_UART4
|
||||
|
|
|
@ -28,9 +28,6 @@
|
|||
// *************** BEEPER *****************************
|
||||
#define BEEPER PC15
|
||||
|
||||
// *************** INVERTER *****************************
|
||||
#define INVERTER_PIN_UART2 PB2
|
||||
|
||||
// *************** SPI *****************************
|
||||
#define USE_SPI
|
||||
|
||||
|
@ -114,6 +111,8 @@
|
|||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
// provide for Telemetry module
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
|
@ -123,6 +122,7 @@
|
|||
#define USE_UART2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define UART2_TX_PIN PA2
|
||||
#define INVERTER_PIN_UART2_RX PB2
|
||||
|
||||
// provide for GPS module
|
||||
#define USE_UART5
|
||||
|
|
|
@ -23,8 +23,6 @@
|
|||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART6 PC8
|
||||
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
@ -61,6 +59,8 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -72,6 +72,7 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
#define INVERTER_PIN_UART6_RX PC8
|
||||
|
||||
#define SERIAL_PORT_COUNT 4 // VCP, UART1, UART3, UART6
|
||||
|
||||
|
|
|
@ -40,8 +40,6 @@
|
|||
#define BEEPER PC9
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART3 PB15
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC5
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
@ -94,6 +92,8 @@
|
|||
#define VBUS_SENSING_PIN PA8
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -101,6 +101,7 @@
|
|||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
#define INVERTER_PIN_UART3_RX PB15
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
|
|
@ -33,8 +33,8 @@ const timerHardware_t timerHardware[] =
|
|||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 1, IOCFG_IPD, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM6
|
||||
{ TIM2, IO_TAG(PB10), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM7
|
||||
{ TIM2, IO_TAG(PB11), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM8
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_MC_SERVO | TIM_USE_ANY | TIM_USE_LED }, // S1_out
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_IPD, GPIO_AF_1, TIM_USE_MC_SERVO | TIM_USE_ANY }, // S2_out
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_ANY | TIM_USE_LED }, // S1_out
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_IPD, GPIO_AF_1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO |TIM_USE_ANY }, // S2_out
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
||||
|
|
|
@ -34,6 +34,8 @@
|
|||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
||||
#define BUS_SPI_SPEED_MAX BUS_SPEED_SLOW
|
||||
|
||||
#define MPU6000_CS_PIN PB5
|
||||
#define MPU6000_SPI_BUS BUS_SPI2
|
||||
|
||||
|
|
|
@ -28,9 +28,6 @@
|
|||
#define BEEPER PC1
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART1 PB13
|
||||
#define INVERTER_PIN_UART6 PB12
|
||||
|
||||
#define MPU6000_CS_PIN PB2
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
|
@ -93,9 +90,12 @@
|
|||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define INVERTER_PIN_UART1_RX PB13
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
@ -112,6 +112,7 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
#define INVERTER_PIN_UART6_RX PB12
|
||||
|
||||
#define SERIAL_PORT_COUNT 6
|
||||
|
||||
|
|
|
@ -41,12 +41,6 @@
|
|||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#if defined(OMNIBUSF4V3)
|
||||
#define INVERTER_PIN_UART6 PC8
|
||||
#else
|
||||
#define INVERTER_PIN_UART1 PC0 // PC0 has never been used as inverter control on genuine OMNIBUS F4 variants, but leave it as is since some clones actually implement it.
|
||||
#endif
|
||||
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE_2_SHARES_UART3
|
||||
|
@ -132,10 +126,15 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
#if !defined(OMNIBUSF4V3)
|
||||
#define INVERTER_PIN_UART1_RX PC0 // PC0 has never been used as inverter control on genuine OMNIBUS F4 variants, but leave it as is since some clones actually implement it.
|
||||
#endif
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
|
@ -144,6 +143,10 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
#if defined(OMNIBUSF4V3)
|
||||
#define INVERTER_PIN_UART6_RX PC8
|
||||
#define INVERTER_PIN_UART6_TX PC9
|
||||
#endif
|
||||
|
||||
#if defined(OMNIBUSF4V3)
|
||||
#define USE_SOFTSERIAL1
|
||||
|
|
|
@ -32,9 +32,6 @@
|
|||
|
||||
#define BEEPER PB4
|
||||
|
||||
// PC0 used as inverter select GPIO
|
||||
#define INVERTER_PIN_UART1 PC0
|
||||
|
||||
// MPU6000 interrupts
|
||||
#define USE_EXTI
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
|
@ -89,10 +86,14 @@
|
|||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
|
||||
// PC0 used as inverter select GPIO
|
||||
#define INVERTER_PIN_UART1_RX PC0
|
||||
|
||||
#define USE_UART3
|
||||
#define I2C_DEVICE_2_SHARES_UART3
|
||||
|
|
|
@ -29,8 +29,6 @@
|
|||
|
||||
#define BEEPER PC9
|
||||
|
||||
#define INVERTER_PIN_UART6 PC6
|
||||
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||
|
@ -77,6 +75,8 @@
|
|||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PA8
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -88,6 +88,7 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6 //inverter
|
||||
#define INVERTER_PIN_UART6_RX PC6
|
||||
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
|
|
|
@ -31,8 +31,6 @@
|
|||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define INVERTER_PIN_UART2 PB2
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
@ -69,6 +67,9 @@
|
|||
#define USE_MAG_MAG3110
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
|
@ -81,6 +82,7 @@
|
|||
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
#define INVERTER_PIN_UART2_RX PB2
|
||||
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
|
|
@ -47,8 +47,6 @@
|
|||
#define BEEPER_PWM_FREQUENCY 3150
|
||||
#endif
|
||||
|
||||
#define INVERTER_PIN_UART6 PB15
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
@ -109,6 +107,8 @@
|
|||
#define USB_IO
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
@ -124,6 +124,7 @@
|
|||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
#define INVERTER_PIN_UART6_RX PB15
|
||||
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
|
||||
|
|
|
@ -228,4 +228,13 @@
|
|||
BUSDEV_REGISTER_I2C(busdev_ug2864, DEVHW_UG2864, UG2864_I2C_BUS, 0x3C, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
||||
#if defined(USE_PMW_SERVO_DRIVER)
|
||||
#if defined(USE_PWM_DRIVER_PCA9685) && defined(USE_I2C)
|
||||
#if !defined(PCA9685_I2C_BUS)
|
||||
#define PCA9685_I2C_BUS BUS_I2C1
|
||||
#endif
|
||||
BUSDEV_REGISTER_I2C(busdev_pca9685, DEVHW_PCA9685, PCA9685_I2C_BUS, 0x40, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif // USE_TARGET_HARDWARE_DESCRIPTORS
|
||||
|
|
|
@ -70,8 +70,8 @@ uint16_t frskyGetGPSState(void)
|
|||
// ones and tens columns (# of satellites 0 - 99)
|
||||
tmpi += constrain(gpsSol.numSat, 0, 99);
|
||||
|
||||
// hundreds column (satellite accuracy HDOP: 0 = worst [HDOP 6.5], 9 = best [HDOP 2.0])
|
||||
tmpi += (9 - constrain((gpsSol.hdop - 151) / 50, 0, 9)) * 100;
|
||||
// hundreds column (satellite accuracy HDOP: 0 = worst [HDOP > 5.5], 9 = best [HDOP <= 1.0])
|
||||
tmpi += (9 - constrain((gpsSol.hdop - 51) / 50, 0, 9)) * 100;
|
||||
|
||||
// thousands column (GPS fix status)
|
||||
if (STATE(GPS_FIX))
|
||||
|
|
|
@ -158,10 +158,10 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
return sendIbusMeasurement2(address, getBatteryVoltage());
|
||||
}
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_CURRENT) { //CURR in 10*mA, 1 = 10 mA
|
||||
if (feature(FEATURE_CURRENT_METER)) return sendIbusMeasurement2(address, (uint16_t) getAmperage()); //int32_t
|
||||
if (isAmperageConfigured()) return sendIbusMeasurement2(address, (uint16_t) getAmperage()); //int32_t
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_FUEL) { //capacity in mAh
|
||||
if (feature(FEATURE_CURRENT_METER)) return sendIbusMeasurement2(address, (uint16_t) getMAhDrawn()); //int32_t
|
||||
if (isAmperageConfigured()) return sendIbusMeasurement2(address, (uint16_t) getMAhDrawn()); //int32_t
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_CLIMB) {
|
||||
return sendIbusMeasurement2(address, (int16_t) (getEstimatedActualVelocity(Z))); //
|
||||
|
|
|
@ -226,7 +226,7 @@ void mavlinkSendSystemStatus(void)
|
|||
// voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
|
||||
feature(FEATURE_VBAT) ? getBatteryVoltage() * 10 : 0,
|
||||
// current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
|
||||
feature(FEATURE_CURRENT_METER) ? getAmperage() : -1,
|
||||
isAmperageConfigured() ? getAmperage() : -1,
|
||||
// battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
|
||||
feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
|
||||
// drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
|
||||
|
|
|
@ -153,7 +153,7 @@ static smartPortWriteFrameFn *smartPortWriteFrame;
|
|||
static bool smartPortMspReplyPending = false;
|
||||
#endif
|
||||
|
||||
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool useChecksum)
|
||||
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, timeUs_t *clearToSendAt, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool useChecksum)
|
||||
{
|
||||
static uint8_t rxBuffer[sizeof(smartPortPayload_t)];
|
||||
static uint8_t smartPortRxBytes = 0;
|
||||
|
@ -178,6 +178,7 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
|
|||
if ((c == FSSP_SENSOR_ID1) && checkQueueEmpty()) {
|
||||
// our slot is starting, no need to decode more
|
||||
*clearToSend = true;
|
||||
*clearToSendAt = micros() + SMARTPORT_MIN_TELEMETRY_RESPONSE_DELAY_US;
|
||||
skipUntilStart = true;
|
||||
} else if (c == FSSP_SENSOR_ID2) {
|
||||
checksum = 0;
|
||||
|
@ -199,6 +200,7 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
|
|||
checksum += c;
|
||||
|
||||
if (!useChecksum && (smartPortRxBytes == sizeof(smartPortPayload_t))) {
|
||||
*clearToSendAt = micros() + SMARTPORT_MIN_TELEMETRY_RESPONSE_DELAY_US;
|
||||
skipUntilStart = true;
|
||||
|
||||
return (smartPortPayload_t *)&rxBuffer;
|
||||
|
@ -209,6 +211,7 @@ smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPor
|
|||
checksum += c;
|
||||
checksum = (checksum & 0xFF) + (checksum >> 8);
|
||||
if (checksum == 0xFF) {
|
||||
*clearToSendAt = micros() + SMARTPORT_MIN_TELEMETRY_RESPONSE_DELAY_US;
|
||||
return (smartPortPayload_t *)&rxBuffer;
|
||||
}
|
||||
}
|
||||
|
@ -524,7 +527,7 @@ static bool serialCheckQueueEmpty(void)
|
|||
void handleSmartPortTelemetry(void)
|
||||
{
|
||||
static bool clearToSend = false;
|
||||
static volatile timeUs_t lastTelemetryFrameReceivedUs;
|
||||
static timeUs_t clearToSendAt;
|
||||
static smartPortPayload_t *payload = NULL;
|
||||
|
||||
const uint32_t requestTimeout = millis() + SMARTPORT_SERVICE_TIMEOUT_MS;
|
||||
|
@ -532,13 +535,10 @@ void handleSmartPortTelemetry(void)
|
|||
if (telemetryState == TELEMETRY_STATE_INITIALIZED_SERIAL && smartPortSerialPort) {
|
||||
while (serialRxBytesWaiting(smartPortSerialPort) > 0 && !payload) {
|
||||
uint8_t c = serialRead(smartPortSerialPort);
|
||||
payload = smartPortDataReceive(c, &clearToSend, serialCheckQueueEmpty, true);
|
||||
if (payload) {
|
||||
lastTelemetryFrameReceivedUs = micros();
|
||||
}
|
||||
payload = smartPortDataReceive(c, &clearToSend, &clearToSendAt, serialCheckQueueEmpty, true);
|
||||
}
|
||||
|
||||
if (cmpTimeUs(micros(), lastTelemetryFrameReceivedUs) >= SMARTPORT_MIN_TELEMETRY_RESPONSE_DELAY_US) {
|
||||
if (clearToSendAt > 0 && micros() >= clearToSendAt) {
|
||||
processSmartPortTelemetry(payload, &clearToSend, &requestTimeout);
|
||||
payload = NULL;
|
||||
}
|
||||
|
|
|
@ -10,6 +10,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "common/time.h"
|
||||
|
||||
#define SMARTPORT_MSP_TX_BUF_SIZE 256
|
||||
#define SMARTPORT_MSP_RX_BUF_SIZE 64
|
||||
|
||||
|
@ -50,7 +52,7 @@ bool initSmartPortTelemetryExternal(smartPortWriteFrameFn *smartPortWriteFrameEx
|
|||
void handleSmartPortTelemetry(void);
|
||||
void processSmartPortTelemetry(smartPortPayload_t *payload, volatile bool *hasRequest, const uint32_t *requestTimeout);
|
||||
|
||||
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool withChecksum);
|
||||
smartPortPayload_t *smartPortDataReceive(uint16_t c, bool *clearToSend, timeUs_t *clearToSendAt, smartPortCheckQueueEmptyFn *checkQueueEmpty, bool withChecksum);
|
||||
|
||||
struct serialPort_s;
|
||||
void smartPortWriteFrameSerial(const smartPortPayload_t *payload, struct serialPort_s *port, uint16_t checksum);
|
||||
|
|
|
@ -25,6 +25,7 @@ extern "C" {
|
|||
#include "drivers/time.h"
|
||||
extern timeUs_t usTicks;
|
||||
extern volatile timeMs_t sysTickUptime;
|
||||
extern volatile timeMs_t sysTickValStamp;
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
|
@ -44,7 +45,7 @@ TEST(TimeUnittest, TestMillis)
|
|||
TEST(TimeUnittest, TestMicros)
|
||||
{
|
||||
usTicks = 168;
|
||||
SysTick->VAL = 1000 * usTicks;
|
||||
sysTickValStamp = SysTick->VAL = 1000 * usTicks;
|
||||
sysTickUptime = 0;
|
||||
EXPECT_EQ(0, micros());
|
||||
sysTickUptime = 1;
|
||||
|
@ -58,7 +59,7 @@ TEST(TimeUnittest, TestMicros)
|
|||
EXPECT_EQ(500000000, micros());
|
||||
|
||||
sysTickUptime = 0;
|
||||
SysTick->VAL = 0;
|
||||
sysTickValStamp = SysTick->VAL = 0;
|
||||
EXPECT_EQ(1000, micros());
|
||||
sysTickUptime = 1;
|
||||
EXPECT_EQ(2000, micros());
|
||||
|
|
|
@ -468,7 +468,7 @@ class Generator
|
|||
buf << "};\n"
|
||||
end
|
||||
|
||||
buf << "const lookupTableEntry_t settingLookupTables[] = {\n"
|
||||
buf << "static const lookupTableEntry_t settingLookupTables[] = {\n"
|
||||
table_names.each do |name|
|
||||
vn = table_variable_name(name)
|
||||
buf << "\t{ #{vn}, sizeof(#{vn}) / sizeof(char*) },\n"
|
||||
|
@ -476,7 +476,7 @@ class Generator
|
|||
buf << "};\n"
|
||||
|
||||
# Write min/max values table
|
||||
buf << "const uint32_t settingMinMaxTable[] = {\n"
|
||||
buf << "static const uint32_t settingMinMaxTable[] = {\n"
|
||||
@value_encoder.values.each do |v|
|
||||
buf << "\t#{v},\n"
|
||||
end
|
||||
|
@ -492,7 +492,7 @@ class Generator
|
|||
end
|
||||
|
||||
# Write setting_t values
|
||||
buf << "const setting_t settingsTable[] = {\n"
|
||||
buf << "static const setting_t settingsTable[] = {\n"
|
||||
|
||||
last_group = nil
|
||||
foreach_enabled_member do |group, member|
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue