mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 17:55:28 +03:00
Merge branch 'development' into dzikuvx-mixer-rework
This commit is contained in:
commit
2b1a1eef1d
55 changed files with 1246 additions and 370 deletions
1
Makefile
1
Makefile
|
@ -818,6 +818,7 @@ STM32F7xx_COMMON_SRC = \
|
|||
drivers/timer_stm32f7xx.c \
|
||||
drivers/system_stm32f7xx.c \
|
||||
drivers/serial_uart_stm32f7xx.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart_hal.c
|
||||
|
||||
F7EXCLUDES = drivers/bus_spi.c \
|
||||
|
|
|
@ -84,7 +84,6 @@ Soft serial is available as an alternative to a hardware UART on RX4/TX4. By def
|
|||
* Enable soft serial
|
||||
* Do not assign any function to hardware UART 4
|
||||
* Assign the desired function to the soft-serial port
|
||||
* Enable inversion if required `set telemetry_inversion = ON` (e.g. for Frsky telemetry)
|
||||
|
||||
### USB
|
||||
|
||||
|
|
48
docs/Cli.md
48
docs/Cli.md
|
@ -93,7 +93,7 @@ Re-apply any new defaults as desired.
|
|||
|
||||
| Variable Name | Default Value | Description |
|
||||
| ------ | ------ | ------ |
|
||||
| looptime | 2000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). Default of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
|
||||
| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
|
||||
| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) |
|
||||
| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz |
|
||||
| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Use gyro_lpf and gyro_sync_denom determine the gyro refresh rate. Note that different targets have different limits. Setting too high refresh rate can mean that FC cannot keep up with the gyro and higher gyro_sync_denom is needed, |
|
||||
|
@ -164,8 +164,8 @@ Re-apply any new defaults as desired.
|
|||
| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. |
|
||||
| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
|
||||
| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
|
||||
| nav_rth_allow_landing | ON | If set to ON drone will land as a last phase of RTH. |
|
||||
| nav_rth_climb_ignore_emerg | ON | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
|
||||
| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. |
|
||||
| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
|
||||
| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details |
|
||||
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
|
||||
| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] |
|
||||
|
@ -196,24 +196,24 @@ Re-apply any new defaults as desired.
|
|||
| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees |
|
||||
| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
|
||||
| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire |
|
||||
| sbus_inversion | OFF | Standard SBUS (Futaba, FrSKY) uses an inverted signal. Some OpenLRS receivers produce a non-inverted SBUS signal. This setting is to support this type of receivers (including modified FrSKY). This only works on supported hardware (mainly F3 based flight controllers). |
|
||||
| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). |
|
||||
| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX |
|
||||
| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. |
|
||||
| telemetry_inversion | ON | Determines if the telemetry signal is inverted (Futaba, FrSKY). Only suitable on F3 uarts and Softserial on all targets |
|
||||
| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. |
|
||||
| frsky_default_latitude | 0.000 | OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
| frsky_default_longitude | 0.000 | OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
| frsky_coordinates_format | 0 | FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
|
||||
| frsky_unit | METRIC | METRIC , IMPERIAL |
|
||||
| frsky_vfas_precision | 0 | Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
|
||||
| frsky_vfas_cell_voltage | OFF | |
|
||||
| report_cell_voltage | OFF | |
|
||||
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
|
||||
| smartport_uart_unidir | OFF | Turn UART into UNIDIR for smartport telemetry for usage on F1 and F4 target. See Telemetry.md for details |
|
||||
| smartport_fuel_unit | PERCENT | Unit of the value sent with the `FUEL` ID through the S.Port telemetry. Replaces the `smartport_fuel_percent` setting in versions < 1.9 [PERCENT/MAH/MWH] |
|
||||
| smartport_fuel_unit | MAH | Unit of the value sent with the `FUEL` ID through the S.Port telemetry. Replaces the `smartport_fuel_percent` setting in versions < 1.9 [PERCENT/MAH/MWH] |
|
||||
| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. |
|
||||
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
|
||||
| battery_capacity | 0 | Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. |
|
||||
| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. |
|
||||
| vbat_max_cell_voltage | 430 | Maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 430 (4.3V) |
|
||||
| vbat_max_cell_voltage | 424 | Maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, default is 424 (4.24V) |
|
||||
| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) |
|
||||
| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) |
|
||||
| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. |
|
||||
|
@ -253,12 +253,12 @@ Re-apply any new defaults as desired.
|
|||
| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout |
|
||||
| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_stick_threshold | 0 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. |
|
||||
| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. |
|
||||
| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll |
|
||||
| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb |
|
||||
| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn |
|
||||
| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. |
|
||||
| failsafe_min_distance_procedure | SET-THR | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. |
|
||||
| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. |
|
||||
| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. |
|
||||
|
@ -329,10 +329,10 @@ Re-apply any new defaults as desired.
|
|||
| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity |
|
||||
| nav_mc_pos_xy_i | 120 | Controls deceleration time. Measured in 1/100 sec. Expected hold position is placed at a distance calculated as decelerationTime * currentVelocity |
|
||||
| nav_mc_pos_xy_d | 10 | |
|
||||
| nav_mc_vel_xy_p | 180 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
|
||||
| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
|
||||
| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
|
||||
| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
|
||||
| nav_fw_pos_xy_p | 10 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH |
|
||||
| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH |
|
||||
| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
|
||||
| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
|
||||
| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) |
|
||||
|
@ -340,7 +340,7 @@ Re-apply any new defaults as desired.
|
|||
| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
|
||||
| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
|
||||
| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. |
|
||||
| flaperon_throw_offset | 250 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
|
||||
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
|
||||
| gimbal_mode | NORMAL | When feature SERVO_TILT is enabled, this can be either NORMAL or MIXTILT |
|
||||
| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. |
|
||||
| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. |
|
||||
|
@ -362,17 +362,17 @@ Re-apply any new defaults as desired.
|
|||
| mc_p_level | 20 | Multicopter attitude stabilisation P-gain |
|
||||
| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff |
|
||||
| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point |
|
||||
| fw_p_pitch | 20 | Fixed-wing rate stabilisation P-gain for PITCH |
|
||||
| fw_i_pitch | 30 | Fixed-wing rate stabilisation I-gain for PITCH |
|
||||
| fw_ff_pitch| 10 | Fixed-wing rate stabilisation FF-gain for PITCH |
|
||||
| fw_p_roll | 25 | Fixed-wing rate stabilisation P-gain for ROLL |
|
||||
| fw_i_roll | 30 | Fixed-wing rate stabilisation I-gain for ROLL |
|
||||
| fw_ff_roll | 10 | Fixed-wing rate stabilisation FF-gain for ROLL |
|
||||
| fw_p_yaw | 50 | Fixed-wing rate stabilisation P-gain for YAW |
|
||||
| fw_i_yaw | 45 | Fixed-wing rate stabilisation I-gain for YAW |
|
||||
| fw_ff_yaw | 0 | Fixed-wing rate stabilisation FF-gain for YAW |
|
||||
| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH |
|
||||
| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH |
|
||||
| fw_ff_pitch| 50 | Fixed-wing rate stabilisation FF-gain for PITCH |
|
||||
| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL |
|
||||
| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL |
|
||||
| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL |
|
||||
| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW |
|
||||
| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW |
|
||||
| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW |
|
||||
| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain |
|
||||
| fw_i_level | 15 | Fixed-wing attitude stabilisation low-pass filter cutoff |
|
||||
| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff |
|
||||
| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point |
|
||||
| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° |
|
||||
| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° |
|
||||
|
@ -412,7 +412,7 @@ Re-apply any new defaults as desired.
|
|||
| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled |
|
||||
| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled |
|
||||
| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled |
|
||||
| airspeed_adc_channel | - | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
|
||||
| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
|
||||
| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
|
||||
| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot |
|
||||
| mixer_preset | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. |
|
||||
|
|
|
@ -36,19 +36,19 @@ Smartport uses _57600bps_ serial speed.
|
|||
|
||||
### Direct connection for F3/F7
|
||||
|
||||
Only TX serial pin has to be connected to Smartport receiver. Enable the telemetry inversion setting.
|
||||
Only TX serial pin has to be connected to Smartport receiver. Disable `telemetry_inverted`.
|
||||
|
||||
```
|
||||
set telemetry_inversion = ON
|
||||
set telemetry_inverted = OFF
|
||||
set smartport_uart_unidir = OFF
|
||||
```
|
||||
|
||||
### Receiver univerted hack
|
||||
|
||||
Some receivers (X4R, XSR and so on) can be hacked to get _uninverted_ Smartport signal. In this case connect uninverted signal to TX pad of chosen serial port
|
||||
Some receivers (X4R, XSR and so on) can be hacked to get _uninverted_ Smartport signal. In this case connect uninverted signal to TX pad of chosen serial port and enable `telemetry_inverted`.
|
||||
|
||||
```
|
||||
set telemetry_inversion = OFF
|
||||
set telemetry_inverted = ON
|
||||
set smartport_uart_unidir = OFF
|
||||
```
|
||||
|
||||
|
@ -57,7 +57,7 @@ set smartport_uart_unidir = OFF
|
|||
Software emulated serial port allows to connect to Smartport receivers without any hacks. Only `TX` has to be connected to the receiver.
|
||||
|
||||
```
|
||||
set telemetry_inversion = ON
|
||||
set telemetry_inverted = OFF
|
||||
```
|
||||
|
||||
If solution above is not working, there is an alternative RX and TX lines have to be bridged using
|
||||
|
@ -68,7 +68,7 @@ SmartPort ---> RX (CH5 pad) ---> 1kOhm resistor ---> TX (CH6 pad)
|
|||
```
|
||||
|
||||
```
|
||||
set telemetry_inversion = ON
|
||||
set telemetry_inverted = OFF
|
||||
```
|
||||
|
||||
### SmartPort (S.Port) with external hardware inverter
|
||||
|
@ -87,7 +87,7 @@ When external inverter is used, following configuration has to be applied:
|
|||
|
||||
```
|
||||
set smartport_uart_unidir = ON
|
||||
set telemetry_inversion = OFF
|
||||
set telemetry_inverted = ON
|
||||
```
|
||||
|
||||
### Available SmartPort (S.Port) sensors
|
||||
|
@ -132,15 +132,15 @@ FrSky telemetry is transmit only and just requires a single connection from the
|
|||
FrSky telemetry signals are inverted. To connect a INAV capable board to an FrSKy receiver you have some options.
|
||||
|
||||
1. A hardware inverter - Built in to some flight controllers.
|
||||
2. Use software serial and enable frsky_inversion.
|
||||
3. Use a flight controller that has software configurable hardware inversion (e.g. STM32F30x).
|
||||
2. Use software serial.
|
||||
3. Use a flight controller that has software configurable hardware inversion (e.g. F3 or F7).
|
||||
|
||||
For 1, just connect your inverter to a usart or software serial port.
|
||||
|
||||
For 2 and 3 use the CLI command as follows:
|
||||
|
||||
```
|
||||
set telemetry_inversion = ON
|
||||
set telemetry_inverted = OFF
|
||||
```
|
||||
|
||||
### Precision setting for VFAS
|
||||
|
@ -360,6 +360,8 @@ This required a receiver with new firmware that support SNR, RSSI and long frame
|
|||
|
||||
7.This same as 6, but sensor 3 is GPS_STATUS, 10 is ARMED, 16 is MODE.
|
||||
|
||||
8.This same as 7, but sensor 10 (ARMED) is reversed.
|
||||
|
||||
131.This same as 3, but sensor 16 (type SPEED) is in m/s.
|
||||
|
||||
132.This same as 4, but sensor 16 (type SPEED) is in m/s.
|
||||
|
@ -370,6 +372,8 @@ This required a receiver with new firmware that support SNR, RSSI and long frame
|
|||
|
||||
135.This same as 7, but sensor 11 (type SPEED) is in m/s.
|
||||
|
||||
136.This same as 8, but sensor 11 (type SPEED) is in m/s.
|
||||
|
||||
### RX hardware
|
||||
|
||||
These receivers are reported to work with i-bus telemetry:
|
||||
|
|
|
@ -105,7 +105,6 @@ bool mpuGyroReadScratchpad(gyroDev_t *gyro)
|
|||
gyro->gyroADCRaw[X] = (int16_t)((ctx->gyroRaw[0] << 8) | ctx->gyroRaw[1]);
|
||||
gyro->gyroADCRaw[Y] = (int16_t)((ctx->gyroRaw[2] << 8) | ctx->gyroRaw[3]);
|
||||
gyro->gyroADCRaw[Z] = (int16_t)((ctx->gyroRaw[4] << 8) | ctx->gyroRaw[5]);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -72,14 +72,14 @@ static const uint16_t spiDivisorMapFast[] = {
|
|||
SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 421.875 KBits/s
|
||||
SPI_BAUDRATEPRESCALER_128, // SPI_CLOCK_SLOW 843.75 KBits/s
|
||||
SPI_BAUDRATEPRESCALER_16, // SPI_CLOCK_STANDARD 6.75 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_4, // SPI_CLOCK_FAST 27.0 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_2 // SPI_CLOCK_ULTRAFAST 54.0 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_FAST 13.5 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_4 // SPI_CLOCK_ULTRAFAST 27.0 MBits/s
|
||||
};
|
||||
static const uint16_t spiDivisorMapSlow[] = {
|
||||
SPI_BAUDRATEPRESCALER_256, // SPI_CLOCK_INITIALIZATON 210.937 KBits/s
|
||||
SPI_BAUDRATEPRESCALER_64, // SPI_CLOCK_SLOW 843.75 KBits/s
|
||||
SPI_BAUDRATEPRESCALER_8, // SPI_CLOCK_STANDARD 6.75 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_2, // SPI_CLOCK_FAST 27.0 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_4, // SPI_CLOCK_FAST 13.5 MBits/s
|
||||
SPI_BAUDRATEPRESCALER_2 // SPI_CLOCK_ULTRAFAST 27.0 MBits/s
|
||||
};
|
||||
|
||||
|
|
|
@ -16,6 +16,7 @@
|
|||
*/
|
||||
|
||||
#pragma once
|
||||
#include "common/color.h"
|
||||
|
||||
#define WS2811_LED_STRIP_LENGTH 32
|
||||
#define WS2811_BITS_PER_LED 24
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "pitotmeter_adc.h"
|
||||
#include "adc.h"
|
||||
|
||||
#if defined(USE_PITOT_ADC)
|
||||
#if defined(USE_ADC) && defined(USE_PITOT_ADC)
|
||||
|
||||
/*
|
||||
* NXP MPXV7002DP differential pressure sensor
|
||||
|
|
|
@ -173,18 +173,28 @@ static const char * const *sensorHardwareNames[] = {
|
|||
table_acc_hardware,
|
||||
#ifdef USE_BARO
|
||||
table_baro_hardware,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_MAG
|
||||
table_mag_hardware,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_RANGEFINDER
|
||||
table_rangefinder_hardware,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_PITOT
|
||||
table_pitot_hardware,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
#ifdef USE_OPTICAL_FLOW
|
||||
table_opflow_hardware,
|
||||
#else
|
||||
NULL,
|
||||
#endif
|
||||
};
|
||||
|
||||
|
@ -2255,10 +2265,12 @@ static void cliStatus(char *cmdline)
|
|||
const uint32_t mask = (1 << i);
|
||||
if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
|
||||
const int sensorHardwareIndex = detectedSensors[i];
|
||||
if (sensorHardwareNames[i]) {
|
||||
const char *sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
|
||||
cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
|
||||
}
|
||||
}
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
|
||||
cliPrintLine("STM32 system clocks:");
|
||||
|
|
|
@ -225,12 +225,18 @@ void validateAndFixConfig(void)
|
|||
// Disable unused features
|
||||
featureClear(FEATURE_UNUSED_1 | FEATURE_UNUSED_2 | FEATURE_UNUSED_3 | FEATURE_UNUSED_4 | FEATURE_UNUSED_5 | FEATURE_UNUSED_6 | FEATURE_UNUSED_7 | FEATURE_UNUSED_8 | FEATURE_UNUSED_9 );
|
||||
|
||||
#ifdef DISABLE_RX_PWM_FEATURE
|
||||
#if defined(DISABLE_RX_PWM_FEATURE) || !defined(USE_RX_PWM)
|
||||
if (rxConfig()->receiverType == RX_TYPE_PWM) {
|
||||
rxConfigMutable()->receiverType = RX_TYPE_NONE;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !defined(USE_RX_PPM)
|
||||
if (rxConfig()->receiverType == RX_TYPE_PPM) {
|
||||
rxConfigMutable()->receiverType = RX_TYPE_NONE;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
if (rxConfig()->receiverType == RX_TYPE_PWM) {
|
||||
#if defined(STM32F10X)
|
||||
|
@ -381,6 +387,11 @@ void validateAndFixConfig(void)
|
|||
break;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if !defined(USE_MPU_DATA_READY_SIGNAL)
|
||||
gyroConfigMutable()->gyroSync = false;
|
||||
systemConfigMutable()->asyncMode = ASYNC_MODE_NONE;
|
||||
#endif
|
||||
}
|
||||
|
||||
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch)
|
||||
|
|
|
@ -492,7 +492,7 @@ void init(void)
|
|||
adc_params.adcFunctionChannel[ADC_CURRENT] = adcChannelConfig()->adcFunctionChannel[ADC_CURRENT];
|
||||
}
|
||||
|
||||
#if defined(USE_PITOT) && defined(USE_PITOT_ADC)
|
||||
#if defined(USE_PITOT) && defined(USE_ADC) && defined(USE_PITOT_ADC)
|
||||
if (pitotmeterConfig()->pitot_hardware == PITOT_ADC || pitotmeterConfig()->pitot_hardware == PITOT_AUTODETECT) {
|
||||
adc_params.adcFunctionChannel[ADC_AIRSPEED] = adcChannelConfig()->adcFunctionChannel[ADC_AIRSPEED];
|
||||
}
|
||||
|
|
|
@ -1317,7 +1317,7 @@ groups:
|
|||
members:
|
||||
- name: telemetry_switch
|
||||
type: bool
|
||||
- name: telemetry_inversion
|
||||
- name: telemetry_inverted
|
||||
type: bool
|
||||
- name: frsky_default_latitude
|
||||
field: gpsNoFixLatitude
|
||||
|
@ -1361,9 +1361,6 @@ groups:
|
|||
field: ltmUpdateRate
|
||||
condition: USE_TELEMETRY_LTM
|
||||
table: ltm_rates
|
||||
- name: telemetry_halfduplex
|
||||
field: halfDuplex
|
||||
type: bool
|
||||
|
||||
- name: PG_ELERES_CONFIG
|
||||
type: eleresConfig_t
|
||||
|
@ -1666,6 +1663,9 @@ groups:
|
|||
max: INT32_MAX
|
||||
- name: stats_total_dist
|
||||
max: INT32_MAX
|
||||
- name: stats_total_energy
|
||||
max: INT32_MAX
|
||||
condition: USE_ADC
|
||||
|
||||
- name: PG_TIME_CONFIG
|
||||
type: timeConfig_t
|
||||
|
|
|
@ -5,6 +5,8 @@
|
|||
|
||||
#include "fc/stats.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
|
@ -15,21 +17,30 @@
|
|||
#define MIN_FLIGHT_TIME_TO_RECORD_STATS_S 10 //prevent recording stats for that short "flights" [s]
|
||||
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(statsConfig_t, statsConfig, PG_STATS_CONFIG, 0);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(statsConfig_t, statsConfig, PG_STATS_CONFIG, 1);
|
||||
|
||||
PG_RESET_TEMPLATE(statsConfig_t, statsConfig,
|
||||
.stats_enabled = 0,
|
||||
.stats_total_time = 0,
|
||||
.stats_total_dist = 0,
|
||||
#ifdef USE_ADC
|
||||
.stats_total_energy = 0
|
||||
#endif
|
||||
);
|
||||
|
||||
static uint32_t arm_millis;
|
||||
static uint32_t arm_distance_cm;
|
||||
#ifdef USE_ADC
|
||||
static uint32_t arm_mWhDrawn;
|
||||
#endif
|
||||
|
||||
void statsOnArm(void)
|
||||
{
|
||||
arm_millis = millis();
|
||||
arm_distance_cm = getTotalTravelDistance();
|
||||
#ifdef USE_ADC
|
||||
arm_mWhDrawn = getMWhDrawn();
|
||||
#endif
|
||||
}
|
||||
|
||||
void statsOnDisarm(void)
|
||||
|
@ -39,6 +50,10 @@ void statsOnDisarm(void)
|
|||
if (dt >= MIN_FLIGHT_TIME_TO_RECORD_STATS_S) {
|
||||
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))
|
||||
statsConfigMutable()->stats_total_energy += getMWhDrawn() - arm_mWhDrawn;
|
||||
#endif
|
||||
writeEEPROM();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -5,6 +5,9 @@
|
|||
typedef struct statsConfig_s {
|
||||
uint32_t stats_total_time; // [s]
|
||||
uint32_t stats_total_dist; // [m]
|
||||
#ifdef USE_ADC
|
||||
uint32_t stats_total_energy; // deciWatt hour (x0.1Wh)
|
||||
#endif
|
||||
uint8_t stats_enabled;
|
||||
} statsConfig_t;
|
||||
|
||||
|
|
|
@ -386,6 +386,8 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
|
|||
quaternionInitFromVector(&deltaQ, &vTheta);
|
||||
const float thetaMagnitudeSq = vectorNormSquared(&vTheta);
|
||||
|
||||
// If calculated rotation is zero - don't update quaternion
|
||||
if (thetaMagnitudeSq >= 1e-20) {
|
||||
// Calculate quaternion delta:
|
||||
// Theta is a axis/angle rotation. Direction of a vector is axis, magnitude is angle/2.
|
||||
// Proper quaternion from axis/angle involves computing sin/cos, but the formula becomes numerically unstable as Theta approaches zero.
|
||||
|
@ -404,6 +406,7 @@ static void imuMahonyAHRSupdate(float dt, const fpVector3_t * gyroBF, const fpVe
|
|||
// Calculate final orientation and renormalize
|
||||
quaternionMultiply(&orientation, &orientation, &deltaQ);
|
||||
quaternionNormalize(&orientation, &orientation);
|
||||
}
|
||||
|
||||
// Check for invalid quaternion
|
||||
imuCheckAndResetOrientationQuaternion(accBF);
|
||||
|
|
|
@ -28,7 +28,6 @@
|
|||
#include "build/build_config.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/typeconversion.h"
|
||||
|
@ -91,23 +90,6 @@ static void ledStripDisable(void);
|
|||
# error "Led strip length must match driver"
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
COLOR_BLACK = 0,
|
||||
COLOR_WHITE,
|
||||
COLOR_RED,
|
||||
COLOR_ORANGE,
|
||||
COLOR_YELLOW,
|
||||
COLOR_LIME_GREEN,
|
||||
COLOR_GREEN,
|
||||
COLOR_MINT_GREEN,
|
||||
COLOR_CYAN,
|
||||
COLOR_LIGHT_BLUE,
|
||||
COLOR_BLUE,
|
||||
COLOR_DARK_VIOLET,
|
||||
COLOR_MAGENTA,
|
||||
COLOR_DEEP_PINK,
|
||||
} colorId_e;
|
||||
|
||||
const hsvColor_t hsv[] = {
|
||||
// H S V
|
||||
[COLOR_BLACK] = { 0, 0, 0},
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "common/color.h"
|
||||
|
||||
#define LED_MAX_STRIP_LENGTH 32
|
||||
#define LED_CONFIGURABLE_COLOR_COUNT 16
|
||||
|
@ -68,6 +69,23 @@
|
|||
#define LED_XY_MASK 0x0F
|
||||
#define CALCULATE_LED_XY(x, y) ((((x) & LED_XY_MASK) << LED_X_BIT_OFFSET) | (((y) & LED_XY_MASK) << LED_Y_BIT_OFFSET))
|
||||
|
||||
typedef enum {
|
||||
COLOR_BLACK = 0,
|
||||
COLOR_WHITE,
|
||||
COLOR_RED,
|
||||
COLOR_ORANGE,
|
||||
COLOR_YELLOW,
|
||||
COLOR_LIME_GREEN,
|
||||
COLOR_GREEN,
|
||||
COLOR_MINT_GREEN,
|
||||
COLOR_CYAN,
|
||||
COLOR_LIGHT_BLUE,
|
||||
COLOR_BLUE,
|
||||
COLOR_DARK_VIOLET,
|
||||
COLOR_MAGENTA,
|
||||
COLOR_DEEP_PINK,
|
||||
} colorId_e;
|
||||
|
||||
typedef enum {
|
||||
LED_MODE_ORIENTATION = 0,
|
||||
LED_MODE_HEADFREE,
|
||||
|
|
|
@ -99,6 +99,12 @@
|
|||
#define METERS_PER_KILOMETER 1000
|
||||
#define METERS_PER_MILE 1609
|
||||
|
||||
#define DELAYED_REFRESH_RESUME_COMMAND (checkStickPosition(THR_HI) || checkStickPosition(PIT_HI))
|
||||
|
||||
#define SPLASH_SCREEN_DISPLAY_TIME 4000 // ms
|
||||
#define ARMED_SCREEN_DISPLAY_TIME 1500 // ms
|
||||
#define STATS_SCREEN_DISPLAY_TIME 60000 // ms
|
||||
|
||||
#define EFFICIENCY_UPDATE_INTERVAL (5 * 1000)
|
||||
|
||||
// Adjust OSD_MESSAGE's default position when
|
||||
|
@ -140,8 +146,8 @@ typedef struct osd_sidebar_s {
|
|||
uint8_t idle;
|
||||
} osd_sidebar_t;
|
||||
|
||||
timeUs_t resumeRefreshAt = 0;
|
||||
#define REFRESH_1S (1000*1000)
|
||||
static timeUs_t resumeRefreshAt = 0;
|
||||
static bool refreshWaitForResumeCmdRelease;
|
||||
|
||||
static bool fullRedraw = false;
|
||||
|
||||
|
@ -1677,6 +1683,11 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
|||
osdConfig->main_voltage_decimals = 1;
|
||||
}
|
||||
|
||||
static void osdSetNextRefreshIn(uint32_t timeMs) {
|
||||
resumeRefreshAt = micros() + timeMs * 1000;
|
||||
refreshWaitForResumeCmdRelease = true;
|
||||
}
|
||||
|
||||
void osdInit(displayPort_t *osdDisplayPortToUse)
|
||||
{
|
||||
if (!osdDisplayPortToUse)
|
||||
|
@ -1705,23 +1716,49 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
|
|||
#endif
|
||||
|
||||
#ifdef USE_STATS
|
||||
#define STATS_LABEL_X_POS 4
|
||||
#define STATS_VALUE_X_POS 24
|
||||
if (statsConfig()->stats_enabled) {
|
||||
displayWrite(osdDisplayPort, 3, ++y, "ODOMETER:");
|
||||
displayWrite(osdDisplayPort, STATS_LABEL_X_POS, ++y, "ODOMETER:");
|
||||
if (osdConfig()->units == OSD_UNIT_IMPERIAL) {
|
||||
tfp_sprintf(string_buffer, "%d MI", statsConfig()->stats_total_dist / METERS_PER_MILE);
|
||||
tfp_sprintf(string_buffer, "%5d", statsConfig()->stats_total_dist / METERS_PER_MILE);
|
||||
string_buffer[5] = SYM_MI;
|
||||
} else {
|
||||
tfp_sprintf(string_buffer, "%d KM", statsConfig()->stats_total_dist / METERS_PER_KILOMETER);
|
||||
tfp_sprintf(string_buffer, "%5d", statsConfig()->stats_total_dist / METERS_PER_KILOMETER);
|
||||
string_buffer[5] = SYM_KM;
|
||||
}
|
||||
displayWrite(osdDisplayPort, 13, y++, string_buffer);
|
||||
string_buffer[6] = '\0';
|
||||
displayWrite(osdDisplayPort, STATS_VALUE_X_POS-5, y, string_buffer);
|
||||
|
||||
displayWrite(osdDisplayPort, STATS_LABEL_X_POS, ++y, "TOTAL TIME:");
|
||||
uint32_t tot_mins = statsConfig()->stats_total_time / 60;
|
||||
tfp_sprintf(string_buffer, "%d:%02d H", tot_mins / 60, tot_mins % 60);
|
||||
displayWrite(osdDisplayPort, 13, y++, string_buffer);
|
||||
tfp_sprintf(string_buffer, "%2d:%02dHM", tot_mins / 60, tot_mins % 60);
|
||||
displayWrite(osdDisplayPort, STATS_VALUE_X_POS-5, y, string_buffer);
|
||||
|
||||
#ifdef USE_ADC
|
||||
if (feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER)) {
|
||||
displayWrite(osdDisplayPort, STATS_LABEL_X_POS, ++y, "TOTAL ENERGY:");
|
||||
osdFormatCentiNumber(string_buffer, statsConfig()->stats_total_energy / 10, 0, 2, 0, 4);
|
||||
strcat(string_buffer, "\xAB"); // SYM_WH
|
||||
displayWrite(osdDisplayPort, STATS_VALUE_X_POS-4, y, string_buffer);
|
||||
|
||||
displayWrite(osdDisplayPort, STATS_LABEL_X_POS, ++y, "AVG EFFICIENCY:");
|
||||
if (statsConfig()->stats_total_dist) {
|
||||
uint32_t avg_efficiency = statsConfig()->stats_total_energy / (statsConfig()->stats_total_dist / METERS_PER_KILOMETER); // mWh/km
|
||||
osdFormatCentiNumber(string_buffer, avg_efficiency / 10, 0, 2, 0, 3);
|
||||
} else
|
||||
strcpy(string_buffer, "---");
|
||||
string_buffer[3] = SYM_WH_KM_0;
|
||||
string_buffer[4] = SYM_WH_KM_1;
|
||||
string_buffer[5] = '\0';
|
||||
displayWrite(osdDisplayPort, STATS_VALUE_X_POS-3, y, string_buffer);
|
||||
}
|
||||
#endif // USE_ADC
|
||||
}
|
||||
#endif
|
||||
|
||||
displayResync(osdDisplayPort);
|
||||
|
||||
resumeRefreshAt = micros() + (4 * REFRESH_1S);
|
||||
osdSetNextRefreshIn(SPLASH_SCREEN_DISPLAY_TIME);
|
||||
}
|
||||
|
||||
static void osdResetStats(void)
|
||||
|
@ -1901,10 +1938,10 @@ static void osdRefresh(timeUs_t currentTimeUs)
|
|||
if (ARMING_FLAG(ARMED)) {
|
||||
osdResetStats();
|
||||
osdShowArmed(); // reset statistic etc
|
||||
resumeRefreshAt = currentTimeUs + (3 * REFRESH_1S / 2);
|
||||
osdSetNextRefreshIn(ARMED_SCREEN_DISPLAY_TIME);
|
||||
} else {
|
||||
osdShowStats(); // show statistic
|
||||
resumeRefreshAt = currentTimeUs + (60 * REFRESH_1S);
|
||||
osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME);
|
||||
}
|
||||
|
||||
armState = ARMING_FLAG(ARMED);
|
||||
|
@ -1922,10 +1959,11 @@ static void osdRefresh(timeUs_t currentTimeUs)
|
|||
// or THR is high or PITCH is high, resume refreshing.
|
||||
// Clear the screen first to erase other elements which
|
||||
// might have been drawn while the OSD wasn't refreshing.
|
||||
if (currentTimeUs > resumeRefreshAt ||
|
||||
checkStickPosition(THR_HI) ||
|
||||
checkStickPosition(PIT_HI)) {
|
||||
|
||||
if (!DELAYED_REFRESH_RESUME_COMMAND)
|
||||
refreshWaitForResumeCmdRelease = false;
|
||||
|
||||
if ((currentTimeUs > resumeRefreshAt) || ((!refreshWaitForResumeCmdRelease) && DELAYED_REFRESH_RESUME_COMMAND)) {
|
||||
displayClearScreen(osdDisplayPort);
|
||||
resumeRefreshAt = 0;
|
||||
} else {
|
||||
|
|
|
@ -117,15 +117,6 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
|
|||
|
||||
serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
|
||||
|
||||
#ifdef USE_VCP
|
||||
if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
|
||||
serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1);
|
||||
if (uart1Config) {
|
||||
uart1Config->functionMask = FUNCTION_MSP;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef SERIALRX_UART
|
||||
serialPortConfig_t *serialRxUartConfig = serialFindPortConfiguration(SERIALRX_UART);
|
||||
if (serialRxUartConfig) {
|
||||
|
@ -140,6 +131,22 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef SMARTAUDIO_UART
|
||||
serialPortConfig_t *gpsUartConfig = serialFindPortConfiguration(SMARTAUDIO_UART);
|
||||
if (SMARTAUDIO_UART) {
|
||||
gpsUartConfig->functionMask = FUNCTION_VTX_SMARTAUDIO;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_VCP
|
||||
if (serialConfig->portConfigs[0].identifier == SERIAL_PORT_USB_VCP) {
|
||||
serialPortConfig_t * uart1Config = serialFindPortConfiguration(SERIAL_PORT_USART1);
|
||||
if (uart1Config && uart1Config->functionMask == 0) {
|
||||
uart1Config->functionMask = FUNCTION_MSP;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
serialConfig->reboot_character = 'R';
|
||||
}
|
||||
|
||||
|
|
|
@ -100,8 +100,7 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
static uint8_t rcSampleIndex = 0;
|
||||
|
||||
// TODO: If you increase the version number, remove _padding_0 from rxConfig_t and this line.
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 3);
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 4);
|
||||
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
|
|
|
@ -111,7 +111,6 @@ PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeCo
|
|||
typedef struct rxConfig_s {
|
||||
uint8_t receiverType; // RC receiver type (rxReceiverType_e enum)
|
||||
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
||||
uint8_t _padding_0[4]; // Added when MAX_MAPPABLE_RX_INPUTS was reduced from 8 to 4. TODO: Delete when PG version needs increasing.
|
||||
uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL
|
||||
uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers.
|
||||
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.
|
||||
|
|
|
@ -85,7 +85,7 @@ PG_RESET_TEMPLATE(batteryConfig_t, batteryConfig,
|
|||
},
|
||||
|
||||
.current = {
|
||||
.offset = 0,
|
||||
.offset = CURRENT_METER_OFFSET,
|
||||
.scale = CURRENT_METER_SCALE,
|
||||
.type = CURRENT_SENSOR_ADC
|
||||
},
|
||||
|
|
|
@ -29,6 +29,10 @@
|
|||
#define CURRENT_METER_SCALE 400 // for Allegro ACS758LCB-100U (40mV/A)
|
||||
#endif
|
||||
|
||||
#ifndef CURRENT_METER_OFFSET
|
||||
#define CURRENT_METER_OFFSET 0
|
||||
#endif
|
||||
|
||||
typedef enum {
|
||||
CURRENT_SENSOR_NONE = 0,
|
||||
CURRENT_SENSOR_ADC,
|
||||
|
|
|
@ -88,7 +88,7 @@ bool pitotDetect(pitotDev_t *dev, uint8_t pitotHardwareToUse)
|
|||
FALLTHROUGH;
|
||||
|
||||
case PITOT_ADC:
|
||||
#if defined(USE_PITOT_ADC)
|
||||
#if defined(USE_ADC) && defined(USE_PITOT_ADC)
|
||||
if (adcPitotDetect(dev)) {
|
||||
pitotHardware = PITOT_ADC;
|
||||
break;
|
||||
|
|
|
@ -37,11 +37,11 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
|
||||
{ TIM8, IO_TAG(PB6), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // PWM12 - OUT4
|
||||
|
||||
#if !defined(AIRHEROF3_QUAD)
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
|
||||
{ TIM8, IO_TAG(PB8), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
|
||||
{ TIM8, IO_TAG(PB9), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -134,4 +134,4 @@
|
|||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTF (BIT(4))
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
|
||||
|
|
|
@ -71,7 +71,6 @@ void targetConfiguration(void)
|
|||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
|
|
|
@ -73,7 +73,6 @@ void targetConfiguration(void)
|
|||
} else {
|
||||
rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
|
||||
serialConfigMutable()->portConfigs[3].functionMask = FUNCTION_TELEMETRY_FRSKY;
|
||||
telemetryConfigMutable()->telemetry_inversion = 0;
|
||||
featureConfigMutable()->enabledFeatures |= (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY);
|
||||
}
|
||||
|
||||
|
|
43
src/main/target/ASGARD32F4/config.c
Normal file
43
src/main/target/ASGARD32F4/config.c
Normal file
|
@ -0,0 +1,43 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT;
|
||||
motorConfigMutable()->motorPwmRate = 4000;
|
||||
motorConfigMutable()->minthrottle = 1075;
|
||||
motorConfigMutable()->maxthrottle = 1950;
|
||||
}
|
||||
#endif
|
53
src/main/target/ASGARD32F4/target.c
Normal file
53
src/main/target/ASGARD32F4/target.c
Normal file
|
@ -0,0 +1,53 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
#define DEF_TIM_CHNL_CH1 TIM_Channel_1
|
||||
#define DEF_TIM_CHNL_CH2 TIM_Channel_2
|
||||
#define DEF_TIM_CHNL_CH3 TIM_Channel_3
|
||||
#define DEF_TIM_CHNL_CH4 TIM_Channel_4
|
||||
|
||||
#define DEF_TIM(_tim, _ch, _pin, _usage, _flags) \
|
||||
{ _tim, IO_TAG(_pin), DEF_TIM_CHNL_##_ch, _flags, IOCFG_AF_PP, GPIO_AF_##_tim, _usage }
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PPM - timer clash with SS1_TX
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1), // M1
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR, 1), // M2
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR, 1), // M3
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 1), // M4
|
||||
|
||||
// DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0), // LED strip - timer clash with M4 output
|
||||
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0), // SS1
|
||||
};
|
177
src/main/target/ASGARD32F4/target.h
Normal file
177
src/main/target/ASGARD32F4/target.h
Normal file
|
@ -0,0 +1,177 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "ASF4"
|
||||
|
||||
#define USBD_PRODUCT_STRING "Asgard32"
|
||||
|
||||
// Status LED
|
||||
// #define LED0 PC13
|
||||
|
||||
// Beeper
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// #define USE_EXTI
|
||||
// #define GYRO_INT_EXTI PC8
|
||||
// #define USE_MPU_DATA_READY_SIGNAL // Not connected on FireworksV2
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_ACC
|
||||
|
||||
#define USE_GYRO_MPU6000
|
||||
#define USE_ACC_MPU6000
|
||||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define GYRO_MPU6000_ALIGN CW90_DEG
|
||||
#define ACC_MPU6000_ALIGN CW90_DEG
|
||||
|
||||
// #define USE_MAG
|
||||
// #define MAG_I2C_BUS BUS_I2C2
|
||||
// #define USE_MAG_HMC5883
|
||||
// #define USE_MAG_QMC5883
|
||||
// #define USE_MAG_IST8310
|
||||
// #define USE_MAG_MAG3110
|
||||
|
||||
#define USE_BARO
|
||||
|
||||
#define USE_BARO_BMP280
|
||||
#define BMP280_SPI_BUS BUS_SPI2
|
||||
#define BMP280_CS_PIN PB9
|
||||
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN NONE
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PC11
|
||||
#define UART3_TX_PIN PC10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN NONE
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_RX_PIN PD2
|
||||
#define UART5_TX_PIN PC12
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_RX_PIN NONE
|
||||
#define SOFTSERIAL_1_TX_PIN PA9 // Clash with UART1_TX, needed for S.Port
|
||||
|
||||
#define SERIAL_PORT_COUNT 8 // VCP, USART1, USART2, USART3, USART4, USART5, USART6, SOFTSERIAL1
|
||||
|
||||
// I2C
|
||||
#define USE_I2C
|
||||
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C2_SCL PB10
|
||||
#define I2C2_SDA PB11
|
||||
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PC2
|
||||
#define SPI2_MOSI_PIN PC3
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PB3
|
||||
#define SPI3_MISO_PIN PB4
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI3
|
||||
#define MAX7456_CS_PIN PA15
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_BUS BUS_SPI2
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC4
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO)
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
// Disable PWM & PPM inputs
|
||||
#undef USE_RX_PWM
|
||||
#undef USE_RX_PPM
|
||||
|
||||
// Pitot not supported
|
||||
#undef USE_PITOT
|
||||
|
||||
// Set default UARTs
|
||||
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
#define SMARTAUDIO_UART SERIAL_PORT_USART2
|
||||
|
||||
#define TARGET_CONFIG
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 4
|
||||
#define TARGET_MOTOR_COUNT 4
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 5
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
|
18
src/main/target/ASGARD32F4/target.mk
Normal file
18
src/main/target/ASGARD32F4/target.mk
Normal file
|
@ -0,0 +1,18 @@
|
|||
F405_TARGETS += $(TARGET)
|
||||
FEATURES += VCP ONBOARDFLASH
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_bmp085.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/pitotmeter_ms4525.c \
|
||||
drivers/pitotmeter_adc.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/max7456.c
|
37
src/main/target/FIREWORKSV2/config.c
Normal file
37
src/main/target/FIREWORKSV2/config.c
Normal file
|
@ -0,0 +1,37 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
#include "drivers/io.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
}
|
||||
#endif
|
53
src/main/target/FIREWORKSV2/target.c
Normal file
53
src/main/target/FIREWORKSV2/target.c
Normal file
|
@ -0,0 +1,53 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
#define DEF_TIM_CHNL_CH1 TIM_Channel_1
|
||||
#define DEF_TIM_CHNL_CH2 TIM_Channel_2
|
||||
#define DEF_TIM_CHNL_CH3 TIM_Channel_3
|
||||
#define DEF_TIM_CHNL_CH4 TIM_Channel_4
|
||||
|
||||
#define DEF_TIM(_tim, _ch, _pin, _usage, _flags) \
|
||||
{ _tim, IO_TAG(_pin), DEF_TIM_CHNL_##_ch, _flags, IOCFG_AF_PP, GPIO_AF_##_tim, _usage }
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0), // PPM
|
||||
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1), // S1_OUT
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1), // S2_OUT
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1), // S3_OUT
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1), // S4_OUT
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0), // LED strip
|
||||
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0), // SS1
|
||||
};
|
181
src/main/target/FIREWORKSV2/target.h
Normal file
181
src/main/target/FIREWORKSV2/target.h
Normal file
|
@ -0,0 +1,181 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "FWX2"
|
||||
|
||||
#define USBD_PRODUCT_STRING "OMNIBUS F4 FWX V2"
|
||||
|
||||
// Status LED
|
||||
#define LED0 PA8
|
||||
|
||||
// Beeper
|
||||
#define BEEPER PB4
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// I2C
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
#define I2C_DEVICE_2_SHARES_UART3
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC8
|
||||
// #define USE_MPU_DATA_READY_SIGNAL // Not connected on FireworksV2
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_ACC
|
||||
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_ACC_MPU6500
|
||||
#define MPU6500_CS_PIN PD2
|
||||
#define MPU6500_SPI_BUS BUS_SPI3
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C2
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
|
||||
#define USE_BARO
|
||||
|
||||
#define USE_BARO_BMP280
|
||||
#define BMP280_SPI_BUS BUS_SPI3
|
||||
#define BMP280_CS_PIN PB3
|
||||
|
||||
#define USE_PITOT_MS4525
|
||||
#define PITOT_I2C_BUS BUS_I2C2
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C2
|
||||
#define USE_RANGEFINDER_HCSR04_I2C
|
||||
|
||||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PA10
|
||||
#define UART1_TX_PIN PA9
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN NONE
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN NONE
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_RX_PIN NONE
|
||||
#define SOFTSERIAL_1_TX_PIN PA9 // Clash with UART1_TX, needed for S.Port
|
||||
|
||||
#define SERIAL_PORT_COUNT 7 // VCP, USART1, USART2, USART3, USART4, USART6, SOFTSERIAL1
|
||||
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PC12
|
||||
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI3
|
||||
#define MAX7456_CS_PIN PA15
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_BUS BUS_SPI2
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC1
|
||||
#define ADC_CHANNEL_2_PIN PC2
|
||||
#define ADC_CHANNEL_3_PIN PA0
|
||||
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO)
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PB6
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST0_HANDLER
|
||||
#define WS2811_DMA_STREAM DMA1_Stream0
|
||||
#define WS2811_DMA_CHANNEL DMA_Channel_2
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define DISABLE_RX_PWM_FEATURE
|
||||
|
||||
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
#define SMARTAUDIO_UART SERIAL_PORT_USART4
|
||||
|
||||
#define TARGET_CONFIG
|
||||
#define CURRENT_METER_SCALE 175
|
||||
#define CURRENT_METER_OFFSET 326
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 4
|
||||
#define TARGET_MOTOR_COUNT 4
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 7
|
||||
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(9) | TIM_N(10) )
|
18
src/main/target/FIREWORKSV2/target.mk
Normal file
18
src/main/target/FIREWORKSV2/target.mk
Normal file
|
@ -0,0 +1,18 @@
|
|||
F405_TARGETS += $(TARGET)
|
||||
FEATURES += VCP ONBOARDFLASH
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_bmp085.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/pitotmeter_ms4525.c \
|
||||
drivers/pitotmeter_adc.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/max7456.c
|
|
@ -36,6 +36,5 @@
|
|||
void targetConfiguration(void)
|
||||
{
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
telemetryConfigMutable()->telemetry_inversion = true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -37,5 +37,4 @@ void targetConfiguration(void)
|
|||
mixerConfigMutable()->platformType = PLATFORM_AIRPLANE; // default mixer to Airplane
|
||||
|
||||
serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
telemetryConfigMutable()->telemetry_inversion = 1;
|
||||
}
|
39
src/main/target/OMNIBUSF7NXT/config.c
Normal file
39
src/main/target/OMNIBUSF7NXT/config.c
Normal file
|
@ -0,0 +1,39 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef TARGET_CONFIG
|
||||
#include "drivers/io.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
ledStripConfigMutable()->ledConfigs[0] = DEFINE_LED(0, 0, COLOR_GREEN, 0, LED_FUNCTION_ARM_STATE, LED_FLAG_OVERLAY(LED_OVERLAY_WARNING), 0);
|
||||
// serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
}
|
||||
#endif
|
71
src/main/target/OMNIBUSF7NXT/target.c
Normal file
71
src/main/target/OMNIBUSF7NXT/target.c
Normal file
|
@ -0,0 +1,71 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
#define DEF_TIM_CHNL_CH1 TIM_CHANNEL_1
|
||||
#define DEF_TIM_CHNL_CH2 TIM_CHANNEL_2
|
||||
#define DEF_TIM_CHNL_CH3 TIM_CHANNEL_3
|
||||
#define DEF_TIM_CHNL_CH4 TIM_CHANNEL_4
|
||||
|
||||
#define GPIO_AF_PA9_TIM1 GPIO_AF1_TIM1
|
||||
#define GPIO_AF_PB0_TIM3 GPIO_AF2_TIM3
|
||||
#define GPIO_AF_PB1_TIM3 GPIO_AF2_TIM3
|
||||
#define GPIO_AF_PB4_TIM3 GPIO_AF2_TIM3
|
||||
#define GPIO_AF_PB5_TIM3 GPIO_AF2_TIM3
|
||||
#define GPIO_AF_PB6_TIM4 GPIO_AF2_TIM4
|
||||
#define GPIO_AF_PC8_TIM8 GPIO_AF3_TIM8
|
||||
#define GPIO_AF_PC9_TIM8 GPIO_AF3_TIM8
|
||||
|
||||
#define DEF_TIM(_tim, _ch, _pin, _usage, _flags) \
|
||||
{ _tim, IO_TAG(_pin), DEF_TIM_CHNL_##_ch, _flags, IOCFG_AF_PP, GPIO_AF_##_pin##_##_tim, _usage }
|
||||
|
||||
// Board hardware definitions
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, NONE, 0, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, NONE, 1, DEVFLAGS_NONE);
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
// DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0), // PPM
|
||||
|
||||
// OUTPUT 1-4
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1),
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1),
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1),
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 1),
|
||||
|
||||
// OUTPUT 5-6
|
||||
DEF_TIM(TIM8, CH3, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1),
|
||||
DEF_TIM(TIM8, CH4, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 1),
|
||||
|
||||
// AUXILARY pins
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_LED, 1), // LED
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_ANY, 0) // SS1 TX
|
||||
};
|
192
src/main/target/OMNIBUSF7NXT/target.h
Normal file
192
src/main/target/OMNIBUSF7NXT/target.h
Normal file
|
@ -0,0 +1,192 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
|
||||
* Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "ONXT"
|
||||
|
||||
#define USBD_PRODUCT_STRING "OMNIBUS NEXT"
|
||||
|
||||
#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS // Don't use common busdev descriptors for IMU
|
||||
#define TARGET_CONFIG
|
||||
|
||||
// Status LED
|
||||
#define LED0 PB2
|
||||
|
||||
// Beeper
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_GYRO
|
||||
#define USE_DUAL_GYRO
|
||||
|
||||
// OMNIBUS F7 NEXT has two IMUs - MPU6000 onboard and ICM20608 (MPU6500) in the vibration dampened box
|
||||
#define USE_GYRO_MPU6000
|
||||
#define USE_ACC_MPU6000
|
||||
#define MPU6000_CS_PIN PB12
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_ACC_MPU6500
|
||||
#define MPU6500_CS_PIN PA8
|
||||
#define MPU6500_SPI_BUS BUS_SPI1
|
||||
#define GYRO_MPU6500_ALIGN CW90_DEG
|
||||
#define ACC_MPU6500_ALIGN CW90_DEG
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_MAG3110
|
||||
|
||||
#define USE_BARO
|
||||
|
||||
#define USE_BARO_BMP280
|
||||
#define BMP280_SPI_BUS BUS_SPI2
|
||||
#define BMP280_CS_PIN PA10
|
||||
|
||||
#define USE_PITOT_MS4525
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
#define USE_RANGEFINDER_HCSR04_I2C
|
||||
#define USE_RANGEFINDER_VL53L0X
|
||||
|
||||
#define USE_VCP
|
||||
#define VBUS_SENSING_PIN PC5
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_RX_PIN PB7
|
||||
#define UART1_TX_PIN PB6
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_RX_PIN NONE
|
||||
#define UART2_TX_PIN PA2
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_RX_PIN PA1
|
||||
#define UART4_TX_PIN PA0
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_RX_PIN PC7
|
||||
#define UART6_TX_PIN PC6
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_RX_PIN NONE
|
||||
#define SOFTSERIAL_1_TX_PIN PB6 // Clash with UART1_TX, needed for S.Port
|
||||
|
||||
#define SERIAL_PORT_COUNT 7 // VCP, USART1, USART2, USART3, USART4, USART6, SOFTSERIAL1
|
||||
|
||||
// I2C
|
||||
#define USE_I2C
|
||||
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_NSS_PIN NONE
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PC3
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PC12
|
||||
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI3
|
||||
#define MAX7456_CS_PIN PA15
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN PC14
|
||||
#define M25P16_SPI_BUS BUS_SPI2
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC0
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC4
|
||||
#define ADC_CHANNEL_4_PIN PA4
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO)
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA9
|
||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA2_ST2_HANDLER
|
||||
#define WS2811_DMA_STREAM DMA2_Stream2
|
||||
#define WS2811_DMA_CHANNEL DMA_CHANNEL_6
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define DISABLE_RX_PWM_FEATURE
|
||||
|
||||
#define TELEMETRY_UART SERIAL_PORT_SOFTSERIAL1
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
// #define SMARTAUDIO_UART SERIAL_PORT_USART4
|
||||
|
||||
#define VBAT_SCALE_DEFAULT 1090
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 6
|
||||
#define TARGET_MOTOR_COUNT 6
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 8
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(8))
|
15
src/main/target/OMNIBUSF7NXT/target.mk
Normal file
15
src/main/target/OMNIBUSF7NXT/target.mk
Normal file
|
@ -0,0 +1,15 @@
|
|||
F7X2RE_TARGETS += $(TARGET)
|
||||
FEATURES += VCP ONBOARDFLASH
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/pitotmeter_ms4525.c \
|
||||
drivers/pitotmeter_adc.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_hal.c \
|
||||
drivers/max7456.c
|
|
@ -37,7 +37,6 @@ void targetConfiguration(void)
|
|||
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything.
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
|
||||
//telemetryConfigMutable()->telemetry_inversion = 1;
|
||||
//telemetryConfigMutable()->halfDuplex = 1;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -32,6 +32,5 @@ void targetConfiguration(void)
|
|||
barometerConfigMutable()->baro_hardware = BARO_BMP280;
|
||||
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So SPRacingF3OSD users don't have to change anything.
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
|
||||
telemetryConfigMutable()->telemetry_inversion = true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -21,54 +21,60 @@
|
|||
|
||||
#if !defined(USE_TARGET_HARDWARE_DESCRIPTORS)
|
||||
|
||||
#if !defined(GYRO_INT_EXTI)
|
||||
#define GYRO_INT_EXTI NONE
|
||||
#endif
|
||||
/** IMU **/
|
||||
#if !defined(USE_TARGET_IMU_HARDWARE_DESCRIPTORS)
|
||||
#if !defined(GYRO_INT_EXTI)
|
||||
#define GYRO_INT_EXTI NONE
|
||||
#endif
|
||||
|
||||
#if !defined(MPU_ADDRESS)
|
||||
#define MPU_ADDRESS 0x68
|
||||
#endif
|
||||
#if !defined(MPU_ADDRESS)
|
||||
#define MPU_ADDRESS 0x68
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_L3GD20)
|
||||
#if defined(USE_GYRO_L3GD20)
|
||||
BUSDEV_REGISTER_SPI(busdev_l3gd20, DEVHW_L3GD20, L3GD20_SPI_BUS, L3GD20_CS_PIN, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_ACC_LSM303DLHC)
|
||||
#if defined(USE_ACC_LSM303DLHC)
|
||||
BUSDEV_REGISTER_I2C(busdev_lsm303, DEVHW_LSM303DLHC, LSM303DLHC_I2C_BUS, 0x19, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU6000)
|
||||
#if defined(USE_GYRO_MPU6000)
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU6050)
|
||||
#if defined(USE_GYRO_MPU6050)
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu6050, DEVHW_MPU6050, MPU6050_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU6500)
|
||||
#if defined(USE_GYRO_MPU6500)
|
||||
#if defined(MPU6500_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#elif defined(MPU6500_I2C_BUS)
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu6500, DEVHW_MPU6500, MPU6500_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_MPU9250)
|
||||
#if defined(USE_GYRO_MPU9250)
|
||||
#if defined(MPU9250_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_mpu9250, DEVHW_MPU9250, MPU9250_SPI_BUS, MPU9250_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#elif defined(MPU9250_I2C_BUS)
|
||||
BUSDEV_REGISTER_I2C(busdev_mpu9250, DEVHW_MPU9250, MPU9250_I2C_BUS, MPU_ADDRESS, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_GYRO_BMI160)
|
||||
#if defined(USE_GYRO_BMI160)
|
||||
#if defined(BMI160_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_bmi160, DEVHW_BMI160, BMI160_SPI_BUS, BMI160_CS_PIN, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#elif defined(BMI160_I2C_BUS)
|
||||
BUSDEV_REGISTER_I2C(busdev_bmi160, DEVHW_BMI160, BMI160_I2C_BUS, 0x68, GYRO_INT_EXTI, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
/** BAROMETERS **/
|
||||
|
||||
#if defined(USE_BARO_BMP085)
|
||||
#if !defined(BMP085_I2C_BUS)
|
||||
#define BMP085_I2C_BUS BARO_I2C_BUS
|
||||
|
@ -105,6 +111,8 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
/** COMPASS SENSORS **/
|
||||
|
||||
#if defined(USE_MAG_HMC5883)
|
||||
#if !defined(HMC5883_I2C_BUS)
|
||||
#define HMC5883_I2C_BUS MAG_I2C_BUS
|
||||
|
@ -144,6 +152,9 @@
|
|||
BUSDEV_REGISTER_I2C(busdev_ist8310, DEVHW_IST8310, IST8310_I2C_BUS, 0x0C, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
||||
|
||||
/** RANGEFINDER SENSORS **/
|
||||
|
||||
#if defined(USE_RANGEFINDER_SRF10)
|
||||
#if !defined(SRF10_I2C_BUS)
|
||||
#define SRF10_I2C_BUS RANGEFINDER_I2C_BUS
|
||||
|
@ -165,6 +176,9 @@
|
|||
BUSDEV_REGISTER_I2C(busdev_vl53l0x, DEVHW_VL53L0X, VL53L0X_I2C_BUS, 0x29, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
||||
|
||||
/** AIRSPEED SENSORS **/
|
||||
|
||||
#if defined(USE_PITOT_MS4525)
|
||||
#if !defined(MS4525_I2C_BUS)
|
||||
#define MS4525_I2C_BUS PITOT_I2C_BUS
|
||||
|
@ -172,6 +186,9 @@
|
|||
BUSDEV_REGISTER_I2C(busdev_ms5425, DEVHW_MS4525, MS4525_I2C_BUS, 0x28, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
||||
|
||||
/** OTHER HARDWARE **/
|
||||
|
||||
#if defined(USE_MAX7456)
|
||||
BUSDEV_REGISTER_SPI(busdev_max7456, DEVHW_MAX7456, MAX7456_SPI_BUS, MAX7456_CS_PIN, NONE, DEVFLAGS_USE_RAW_REGISTERS);
|
||||
#endif
|
||||
|
@ -188,14 +205,3 @@
|
|||
#endif
|
||||
|
||||
#endif // USE_TARGET_HARDWARE_DESCRIPTORS
|
||||
|
||||
|
||||
|
||||
|
||||
/* This file is not compiled in and only holds example HW descriptors for supported hardware */
|
||||
#if 0
|
||||
// MS5607 / MS5611
|
||||
BUSDEV_REGISTER_I2C(busdev_ak8963, DEVHW_AK8963, MAG_I2C_BUS, 0x0C, NONE, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_I2C(busdev_ak8975, DEVHW_AK8975, MAG_I2C_BUS, 0x0C, NONE, DEVFLAGS_NONE);
|
||||
BUSDEV_REGISTER_SPI(busdev_hmc5883, DEVHW_HMC5883, MAG_SPI_BUS, HMC5883_CS_PIN, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
|
|
|
@ -17,23 +17,24 @@ _Min_Stack_Size = 0x1800;
|
|||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x08000000 to 0x08080000 512K full flash,
|
||||
0x08000000 to 0x0805FFFF 384K firmware,
|
||||
0x08060000 to 0x08080000 128K config,
|
||||
0x08000000 to 0x0807FFFF 512K full flash,
|
||||
0x08000000 to 0x08003FFF 16K isr vector, startup code,
|
||||
0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1
|
||||
0x08008000 to 0x0807FFFF 480K firmware,
|
||||
*/
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 384K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08060000, LENGTH = 128K
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
|
||||
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
|
||||
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (xrw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", CCM)
|
||||
REGION_ALIAS("FASTRAM", CCM)
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
INCLUDE "stm32_flash.ld"
|
||||
INCLUDE "stm32_flash_split.ld"
|
||||
|
|
|
@ -383,9 +383,6 @@ uint32_t hse_value = HSE_VALUE;
|
|||
#error Undefined CPU
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
|
||||
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
/* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
|
||||
#define PLL_R 7
|
||||
|
@ -395,24 +392,32 @@ uint32_t hse_value = HSE_VALUE;
|
|||
#define PLL_N 336
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 2
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
#if defined (STM32F40_41xxx)
|
||||
#define PLL_N 336
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 2
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
#endif /* STM32F40_41xxx */
|
||||
|
||||
#if defined(STM32F401xx)
|
||||
#define PLL_N 336
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 4
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
#endif /* STM32F401xx */
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F411xE)
|
||||
#define PLL_N 400
|
||||
#define PLL_N 336
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 4
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
#endif /* STM32F410xx || STM32F411xE */
|
||||
|
||||
/******************************************************************************/
|
||||
|
@ -433,21 +438,8 @@ uint32_t hse_value = HSE_VALUE;
|
|||
* @{
|
||||
*/
|
||||
|
||||
#if defined(STM32F40_41xxx)
|
||||
uint32_t SystemCoreClock = 168000000;
|
||||
#endif /* STM32F40_41xxx */
|
||||
|
||||
#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
uint32_t SystemCoreClock = 180000000;
|
||||
#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F401xx)
|
||||
uint32_t SystemCoreClock = 84000000;
|
||||
#endif /* STM32F401xx */
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F411xE)
|
||||
uint32_t SystemCoreClock = 100000000;
|
||||
#endif /* STM32F410xx || STM32F401xE */
|
||||
/* core clock is simply a mhz of PLL_N / PLL_P */
|
||||
uint32_t SystemCoreClock = 1000000 * PLL_N / PLL_P;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
|
@ -511,7 +503,7 @@ void SystemInit(void)
|
|||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
SetSysClock();
|
||||
// SetSysClock();
|
||||
|
||||
/* Configure the Vector Table location add offset address ------------------*/
|
||||
#ifdef VECT_TAB_SRAM
|
||||
|
@ -581,7 +573,6 @@ void SystemCoreClockUpdate(void)
|
|||
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
|
||||
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
if (pllsource != 0)
|
||||
{
|
||||
/* HSE used as PLL clock source */
|
||||
|
@ -592,21 +583,7 @@ void SystemCoreClockUpdate(void)
|
|||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
#elif defined(STM32F410xx) || defined(STM32F411xE)
|
||||
#if defined(USE_HSE_BYPASS)
|
||||
if (pllsource != 0)
|
||||
{
|
||||
/* HSE used as PLL clock source */
|
||||
pllvco = (HSE_BYPASS_INPUT_FREQUENCY / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
#else
|
||||
if (pllsource == 0)
|
||||
{
|
||||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
#endif /* USE_HSE_BYPASS */
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
|
||||
SystemCoreClock = pllvco/pllp;
|
||||
break;
|
||||
|
@ -653,7 +630,6 @@ void SystemCoreClockUpdate(void)
|
|||
*/
|
||||
void SetSysClock(void)
|
||||
{
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx)|| defined(STM32F469_479xx)
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
|
@ -667,7 +643,7 @@ void SetSysClock(void)
|
|||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
|
@ -703,49 +679,53 @@ void SetSysClock(void)
|
|||
RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
|
||||
#endif /* STM32F401xx */
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
|
||||
/* Configure the main PLL */
|
||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
|
||||
#endif /* STM32F40_41xxx || STM32F401xx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
|
||||
#if defined(STM32F410xx) || defined(STM32F411xE)
|
||||
/* PCLK2 = HCLK / 2*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 4*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
|
||||
#endif /* STM32F410xx || STM32F411xE */
|
||||
|
||||
#if defined(STM32F446xx)
|
||||
/* Configure the main PLL */
|
||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
|
||||
#else
|
||||
/* Configure the main PLL */
|
||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
|
||||
#endif /* STM32F446xx */
|
||||
|
||||
/* Enable the main PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till the main PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/* Enable the Over-drive to extend the clock frequency to 180 Mhz */
|
||||
PWR->CR |= PWR_CR_ODEN;
|
||||
while((PWR->CSR & PWR_CSR_ODRDY) == 0)
|
||||
while ((PWR->CSR & PWR_CSR_ODRDY) == 0)
|
||||
{
|
||||
}
|
||||
PWR->CR |= PWR_CR_ODSWEN;
|
||||
while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
|
||||
while ((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
|
||||
{
|
||||
}
|
||||
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
|
||||
#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F40_41xxx)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
|
||||
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
|
||||
#endif /* STM32F40_41xxx */
|
||||
#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
|
||||
|
||||
#if defined(STM32F401xx)
|
||||
#if defined(STM32F401xx) || defined(STM32F410xx) || defined(STM32F411xE)
|
||||
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
|
||||
#endif /* STM32F401xx */
|
||||
#endif /* STM32F401xx || STM32F410xx || STM32F411xE*/
|
||||
|
||||
/* Select the main PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
|
@ -761,113 +741,6 @@ void SetSysClock(void)
|
|||
configuration. User can add here some code to deal with this error */
|
||||
while(1) { __NOP(); }
|
||||
}
|
||||
#elif defined(STM32F410xx) || defined(STM32F411xE)
|
||||
#if defined(USE_HSE_BYPASS)
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/* Enable HSE and HSE BYPASS */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON | RCC_CR_HSEBYP);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Select regulator voltage output Scale 1 mode */
|
||||
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
|
||||
PWR->CR |= PWR_CR_VOS;
|
||||
|
||||
/* HCLK = SYSCLK / 1*/
|
||||
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 2*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 4*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
|
||||
|
||||
/* Configure the main PLL */
|
||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
|
||||
|
||||
/* Enable the main PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till the main PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
|
||||
|
||||
/* Select the main PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
{
|
||||
}
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
}
|
||||
#else /* HSI will be used as PLL clock source */
|
||||
/* Select regulator voltage output Scale 1 mode */
|
||||
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
|
||||
PWR->CR |= PWR_CR_VOS;
|
||||
|
||||
/* HCLK = SYSCLK / 1*/
|
||||
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 2*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
|
||||
|
||||
/* PCLK1 = HCLK / 4*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
|
||||
|
||||
/* Configure the main PLL */
|
||||
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | (PLL_Q << 24);
|
||||
|
||||
/* Enable the main PLL */
|
||||
RCC->CR |= RCC_CR_PLLON;
|
||||
|
||||
/* Wait till the main PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0)
|
||||
{
|
||||
}
|
||||
|
||||
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
|
||||
|
||||
/* Select the main PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
|
||||
{
|
||||
}
|
||||
#endif /* USE_HSE_BYPASS */
|
||||
#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
|
||||
|
||||
SystemCoreClockUpdate();
|
||||
}
|
||||
|
|
|
@ -447,7 +447,7 @@ void configureFrSkyTelemetryPort(void)
|
|||
return;
|
||||
}
|
||||
|
||||
frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inversion ? SERIAL_INVERTED : SERIAL_NOT_INVERTED);
|
||||
frskyPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_FRSKY, NULL, NULL, FRSKY_BAUDRATE, FRSKY_INITIAL_PORT_MODE, telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED);
|
||||
if (!frskyPort) {
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -237,12 +237,12 @@ void initIbusTelemetry(void) {
|
|||
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE1_PRES, IBUS_MEAS_VALUE_PRES);
|
||||
changeTypeIbusTelemetry(15, IBUS_MEAS_TYPE1_S85, IBUS_MEAS_VALUE_STATUS);
|
||||
}
|
||||
if (type == 7) {
|
||||
if (type == 7 || type == 8) {
|
||||
changeTypeIbusTelemetry(2, IBUS_MEAS_TYPE1_GPS_STATUS, IBUS_MEAS_VALUE_GPS_STATUS);
|
||||
changeTypeIbusTelemetry(9, IBUS_MEAS_TYPE1_ARMED, IBUS_MEAS_VALUE_ARMED);
|
||||
changeTypeIbusTelemetry(15,IBUS_MEAS_TYPE1_FLIGHT_MODE, IBUS_MEAS_VALUE_MODE);
|
||||
}
|
||||
if (type == 6 || type == 7) {
|
||||
if (type == 6 || type == 7 || type == 8) {
|
||||
if (batteryConfig()->current.type == CURRENT_SENSOR_VIRTUAL)
|
||||
changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_FUEL, IBUS_MEAS_VALUE_FUEL);
|
||||
else changeTypeIbusTelemetry(3, IBUS_MEAS_TYPE1_BAT_CURR, IBUS_MEAS_VALUE_CURRENT);
|
||||
|
|
|
@ -152,7 +152,11 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_RPM) {
|
||||
return sendIbusMeasurement2(address, (uint16_t) (rcCommand[THROTTLE]));
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE) { //VBAT
|
||||
if (telemetryConfig()->report_cell_voltage) {
|
||||
return sendIbusMeasurement2(address, getBatteryAverageCellVoltage());
|
||||
} else {
|
||||
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
|
||||
else return sendIbusMeasurement2(address, 0);
|
||||
|
@ -174,8 +178,11 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
#endif
|
||||
return sendIbusMeasurement2(address, 0);
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_ARMED) { //motorArmed
|
||||
if (ARMING_FLAG(ARMED)) return sendIbusMeasurement2(address, 0);
|
||||
else return sendIbusMeasurement2(address, 1);
|
||||
if ((telemetryConfig()->ibusTelemetryType & 0x7F) < 8) {
|
||||
return sendIbusMeasurement2(address, ARMING_FLAG(ARMED) ? 0 : 1);
|
||||
} else {
|
||||
return sendIbusMeasurement2(address, ARMING_FLAG(ARMED) ? 1 : 0);
|
||||
}
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_MODE) {
|
||||
uint16_t flightMode = flightModeToIBusTelemetryMode2[getFlightModeForTelemetry()];
|
||||
return sendIbusMeasurement2(address, flightMode);
|
||||
|
|
|
@ -400,6 +400,21 @@ void initLtmTelemetry(void)
|
|||
ltmPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_LTM);
|
||||
}
|
||||
|
||||
|
||||
|
||||
static void configureLtmScheduler(void)
|
||||
{
|
||||
|
||||
/* setup scheduler, default to 'normal' */
|
||||
if (telemetryConfig()->ltmUpdateRate == LTM_RATE_MEDIUM)
|
||||
ltm_schedule = ltm_medium_schedule;
|
||||
else if (telemetryConfig()->ltmUpdateRate == LTM_RATE_SLOW)
|
||||
ltm_schedule = ltm_slow_schedule;
|
||||
else
|
||||
ltm_schedule = ltm_normal_schedule;
|
||||
|
||||
}
|
||||
|
||||
void configureLtmTelemetryPort(void)
|
||||
{
|
||||
if (!portConfig) {
|
||||
|
@ -410,14 +425,6 @@ void configureLtmTelemetryPort(void)
|
|||
baudRateIndex = BAUD_19200;
|
||||
}
|
||||
|
||||
/* setup scheduler, default to 'normal' */
|
||||
if (telemetryConfig()->ltmUpdateRate == LTM_RATE_MEDIUM)
|
||||
ltm_schedule = ltm_medium_schedule;
|
||||
else if (telemetryConfig()->ltmUpdateRate == LTM_RATE_SLOW)
|
||||
ltm_schedule = ltm_slow_schedule;
|
||||
else
|
||||
ltm_schedule = ltm_normal_schedule;
|
||||
|
||||
/* Sanity check that we can support the scheduler */
|
||||
if (baudRateIndex == BAUD_2400 && telemetryConfig()->ltmUpdateRate == LTM_RATE_NORMAL)
|
||||
ltm_schedule = ltm_medium_schedule;
|
||||
|
@ -436,14 +443,18 @@ void checkLtmTelemetryState(void)
|
|||
if (portConfig && telemetryCheckRxPortShared(portConfig)) {
|
||||
if (!ltmEnabled && telemetrySharedPort != NULL) {
|
||||
ltmPort = telemetrySharedPort;
|
||||
configureLtmScheduler();
|
||||
ltmEnabled = true;
|
||||
}
|
||||
} else {
|
||||
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(ltmPortSharing);
|
||||
if (newTelemetryEnabledValue == ltmEnabled)
|
||||
return;
|
||||
if (newTelemetryEnabledValue)
|
||||
if (newTelemetryEnabledValue){
|
||||
configureLtmScheduler();
|
||||
configureLtmTelemetryPort();
|
||||
|
||||
}
|
||||
else
|
||||
freeLtmTelemetryPort();
|
||||
}
|
||||
|
|
|
@ -296,7 +296,7 @@ static void freeSmartPortTelemetryPort(void)
|
|||
static void configureSmartPortTelemetryPort(void)
|
||||
{
|
||||
if (portConfig) {
|
||||
portOptions_t portOptions = (telemetryConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (telemetryConfig()->telemetry_inversion ? SERIAL_NOT_INVERTED : SERIAL_INVERTED);
|
||||
portOptions_t portOptions = (telemetryConfig()->smartportUartUnidirectional ? SERIAL_UNIDIR : SERIAL_BIDIR) | (telemetryConfig()->telemetry_inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED);
|
||||
|
||||
smartPortSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions);
|
||||
}
|
||||
|
|
|
@ -49,19 +49,13 @@
|
|||
#include "telemetry/ibus.h"
|
||||
#include "telemetry/crsf.h"
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
|
||||
|
||||
#if defined(STM32F303xC)
|
||||
#define TELEMETRY_DEFAULT_INVERSION 1
|
||||
#else
|
||||
#define TELEMETRY_DEFAULT_INVERSION 0
|
||||
#endif
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 1);
|
||||
|
||||
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
|
||||
.telemetry_inversion = TELEMETRY_DEFAULT_INVERSION,
|
||||
.telemetry_switch = 0,
|
||||
.gpsNoFixLatitude = 0,
|
||||
.gpsNoFixLongitude = 0,
|
||||
.telemetry_switch = 0,
|
||||
.telemetry_inverted = 0,
|
||||
.frsky_coordinate_format = FRSKY_FORMAT_DMS,
|
||||
.frsky_unit = FRSKY_UNIT_METRICS,
|
||||
.frsky_vfas_precision = 0,
|
||||
|
@ -71,7 +65,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
|
|||
.smartportFuelUnit = SMARTPORT_FUEL_UNIT_MAH,
|
||||
.ibusTelemetryType = 0,
|
||||
.ltmUpdateRate = LTM_RATE_NORMAL,
|
||||
.halfDuplex = 1,
|
||||
);
|
||||
|
||||
void telemetryInit(void)
|
||||
|
|
|
@ -57,7 +57,7 @@ typedef struct telemetryConfig_s {
|
|||
float gpsNoFixLatitude;
|
||||
float gpsNoFixLongitude;
|
||||
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
|
||||
uint8_t telemetry_inversion; // also shared with smartport inversion
|
||||
uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry.
|
||||
frskyGpsCoordFormat_e frsky_coordinate_format;
|
||||
frskyUnit_e frsky_unit;
|
||||
uint8_t frsky_vfas_precision;
|
||||
|
@ -67,7 +67,6 @@ typedef struct telemetryConfig_s {
|
|||
smartportFuelUnit_e smartportFuelUnit;
|
||||
uint8_t ibusTelemetryType;
|
||||
uint8_t ltmUpdateRate;
|
||||
uint8_t halfDuplex;
|
||||
} telemetryConfig_t;
|
||||
|
||||
PG_DECLARE(telemetryConfig_t, telemetryConfig);
|
||||
|
|
|
@ -633,7 +633,7 @@ class Generator
|
|||
def compile_test_file(prog)
|
||||
buf = StringIO.new
|
||||
# cstddef for offsetof()
|
||||
headers = ["target.h", "platform.h", "cstddef"]
|
||||
headers = ["platform.h", "target.h", "cstddef"]
|
||||
@data["groups"].each do |group|
|
||||
gh = group["headers"]
|
||||
if gh
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue