Compare commits
4 commits
Author | SHA1 | Date | |
---|---|---|---|
52c28161f8 | |||
2082ecbb06 | |||
c5a5844297 | |||
d8f2ce9f79 |
64 changed files with 504 additions and 811 deletions
1
Makefile
1
Makefile
|
@ -444,7 +444,6 @@ CC3D_SRC = \
|
|||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/sonar_hcsr04.c \
|
||||
drivers/sound_beeper_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer.c \
|
||||
|
|
|
@ -203,9 +203,9 @@ flight problems like vibration or PID setting issues.
|
|||
|
||||
The Blackbox starts recording data as soon as you arm your craft, and stops when you disarm.
|
||||
|
||||
If your craft has a buzzer attached, you can use Cleanflight's arming beep to synchronize your Blackbox log with your
|
||||
flight video. Cleanflight's arming beep is a "long, short" pattern. The beginning of the first long beep will be shown
|
||||
as a blue line in the flight data log, which you can sync against your recorded audio track.
|
||||
If your craft has a buzzer attached, a short beep will be played when you arm and recording begins. You can later use
|
||||
this beep to synchronize your recorded flight video with the rendered flight data log (the beep is shown as a blue line
|
||||
in the flight data log, which you can sync against the beep in your recorded audio track).
|
||||
|
||||
You should wait a few seconds after disarming your craft to allow the Blackbox to finish saving its data.
|
||||
|
||||
|
@ -224,9 +224,8 @@ minutes.
|
|||
![Dataflash tab in Configurator](Screenshots/blackbox-dataflash.png)
|
||||
|
||||
After downloading the log, be sure to erase the chip to make it ready for reuse by clicking the "erase flash" button.
|
||||
|
||||
If you try to start recording a new flight when the dataflash is already full, Blackbox logging will be disabled and
|
||||
nothing will be recorded.
|
||||
If you try to start recording a new flight when the dataflash is already full, the Blackbox will not make its regular
|
||||
arming beep and nothing will be recorded.
|
||||
|
||||
## Converting logs to CSV or PNG
|
||||
After your flights, you'll have a series of flight log files with a .TXT extension. You'll need to decode these with
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
# Board - AlienWii32 (ALIENWIIF1 and ALIENWIIF3 target)
|
||||
|
||||
The AlienWii32 is actually in prototype stage and few samples exist. There are some different variants and field testing with some users is ongoing. The information below is preliminary and will be updated as needed.
|
||||
The AlienWii32 is actually in prototype stage and only a few samples exist. There are two different variants and some more field testing with some users is ongoing. The information below is preliminary and will be updated as needed.
|
||||
|
||||
Here are the hardware specifications:
|
||||
|
||||
- STM32F103CBT6 MCU (ALIENWIIF1)
|
||||
- STM32F303CCT6 MCU (ALIENWIIF3)
|
||||
- MPU6050 accelerometer/gyro sensor unit
|
||||
- 4-8 x 4.2A brushed ESCs, integrated, to run the strongest micro motors
|
||||
- 8x 4.2A brushed ESCs, integrated, to run the strongest micro motors
|
||||
- extra-wide traces on the PCB, for maximum power throughput
|
||||
- USB port, integrated
|
||||
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31)
|
||||
|
@ -16,16 +16,11 @@ Here are the hardware specifications:
|
|||
- motor connections are at the corners for a clean look with reduced wiring
|
||||
- dimensions: 29x33mm
|
||||
- direct operation from an single cell lipoly battery
|
||||
- 3.3V LDO power regulator (older prototypes)
|
||||
- 3.3V buck-boost power converter (newer prototypes and production versions)
|
||||
- battery monitoring with an LED for buzzer functionality (actualy for an ALIENWIIF3 variant)
|
||||
- 3.3V LDO power regulator (ALIENWIIF1 only)
|
||||
- 3.3V buck-boost power converter (ALIENWIIF3 only)
|
||||
- battery monitoring with an white LED for buzzer functionality (ALIENWIIF3 only)
|
||||
|
||||
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset). This is chosen for maximum compatibility. For optimal connection it is recommended to adjust settings to match the capabilities of your transmitter and satellite receiver. If possible it is recommended to use the DSMX protocol since it is known as more reliable. Also to make use of additional channels you should adjust the following two parameters with the Cleanflight Configurator.
|
||||
|
||||
set serialrx_provider = 1 (0 for 1024bit, 1 for 2048bit)
|
||||
set spektrum_sat_bind = 5
|
||||
|
||||
For more detail of the different bind modes please refer the [Spektrum Bind](Spektrum bind.md) document
|
||||
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset).
|
||||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
|
@ -35,4 +30,4 @@ The pin layout for the ALIENWIIF1 is very similar to NAZE32 or the related clone
|
|||
|
||||
The AlienWii32 F1 board can be flashed like the Naze board or the related clones. All the different methods will work in the same way.
|
||||
|
||||
The AlienWii32 F3 board needs to be flashed via the USB port in DFU mode. Flashing via the Cleanflight GUI is not possible yet. The DFU mode can be activated via setting the BOOT0 jumper during power on of the board. The second method is to connect with an terminal program (i.e. Putty) to the board and enter the character "R" immediately after connecting. Details about the flashing process can be found in the related section of the [Sparky](Board - Sparky.md) documentation. The BOOT0 jumper should be removed and the board needs to be repowerd after firmware flashing. Please be aware, during reboot of the AlienWii F3 board, the GUI will disconnect and an manual reconnect is required.
|
||||
The AlienWii32 F3 board needs to be flashed via the USB port in DFU mode. Flashing via the Cleanflight GUI is not possible yet. The DFU mode can be activated via setting the BOOT0 jumper during power on of the board. The second method is to connect with an terminal program (i.e. Putty) to the board and enter the character "R" immediately after connecting. Details about the flashing process can be found in the related section of the Sparky documentation. The BOOT0 jumper should be removed and the board needs to be repowerd after firmware flashing. Please be aware, during reboot of the AlienWii F3 board, the GUI will disconnect and an manual reconnect is required.
|
|
@ -23,8 +23,8 @@ The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SE
|
|||
| 1 | Ground | |
|
||||
| 2 | +5V | |
|
||||
| 3 | PPM Input | Enable `feature RX_PPM` |
|
||||
| 4 | SoftSerial1 TX / Sonar trigger | |
|
||||
| 5 | SoftSerial1 RX / Sonar Echo | |
|
||||
| 4 | SoftSerial1 TX | Enable `feature SOFTSERIAL` |
|
||||
| 5 | SoftSerial1 RX | Enable `feature SOFTSERIAL` |
|
||||
| 6 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
|
||||
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
|
||||
| 8 | RSSI | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
|
||||
|
|
|
@ -1,22 +1,22 @@
|
|||
# Board - Naze32
|
||||
|
||||
The Naze32 target supports all Naze hardware revisions. Revision 4 and 5 are used and
|
||||
The Naze32 target supports all Naze hardware revisions. Revison 4 and Revision 5 are used and
|
||||
frequently flown by the primary maintainer. Previous Naze hardware revisions may have issues,
|
||||
if found please report via the [github issue tracker](https://github.com/cleanflight/cleanflight/issues).
|
||||
|
||||
## Serial Ports
|
||||
# Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | Notes |
|
||||
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | RX / PA10 | TX / PA9 / TELEM | TELEM output is always inverted (for FrSky). Internally connected to USB port via CP2102 IC |
|
||||
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
|
||||
| 4 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | |
|
||||
| 5 | SOFTSERIAL2 | RC7 / PB0 | RC8 / PB1 | |
|
||||
| 3 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | |
|
||||
| 4 | SOFTSERIAL2 | RC7 / PB0 | RC8 / PB1 | |
|
||||
|
||||
* You cannot use USART1/TX/TELEM pins at the same time.
|
||||
* You may encounter flashing problems if you have something connected to the RX/TX pins. Try disconnecting RX/TX.
|
||||
|
||||
## Pinouts
|
||||
# Pinouts
|
||||
|
||||
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
|
||||
|
||||
|
@ -42,14 +42,14 @@ When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two
|
|||
| 9 | 7 | SOFTSERIAL2 RX | |
|
||||
| 10 | 8 | SOFTSERIAL2 TX | |
|
||||
|
||||
## Recovery
|
||||
# Recovery
|
||||
|
||||
### Board
|
||||
## Board
|
||||
+ Short the two pads labelled 'Boot' **taking extra care not to touch the 5V pad**
|
||||
+ Apply power to the board
|
||||
+ Remove the short on the board
|
||||
|
||||
### Cleanflight configurator
|
||||
## Cleanflight configurator
|
||||
+ Select the correct hardware and the desired release of the Clearflight firmware
|
||||
+ Put a check in the "No reboot sequence"
|
||||
+ Flash firmware
|
||||
|
|
|
@ -1,48 +0,0 @@
|
|||
# Board - Paris Air Hero 32 / Acro Naze 32 Mini
|
||||
|
||||
This board uses the same firmware as the Naze32 board.
|
||||
|
||||
## Sensors
|
||||
|
||||
MPU6500 via SPI interface.
|
||||
|
||||
## Ports
|
||||
|
||||
6 x 3pin ESC / Servo outputs
|
||||
1 x 8pin JST connector (PPM/PWM/UART2)
|
||||
1 x 4pin JST connector (UART3/I2C)
|
||||
|
||||
## Pinouts
|
||||
|
||||
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
|
||||
|
||||
From right to left when looking at the socket from the edge of the board.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | +5V | |
|
||||
| 3 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | RSSI_ADC | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
|
||||
| 5 | USART2 TX | |
|
||||
| 6 | USART2 RX | Built-in inverter |
|
||||
| 7 | LED_STRIP | Enable `feature LED_STRIP` |
|
||||
| 8 | unused | |
|
||||
|
||||
When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but one SoftSerial port is made available to use instead.
|
||||
|
||||
| Pin | Function | Notes |
|
||||
| --- | -------------- | -------------------------------- |
|
||||
| 7 | SOFTSERIAL1 RX | Enable `feature SOFTSERIAL` |
|
||||
| 8 | SOFTSERIAL1 TX | |
|
||||
|
||||
|
||||
## Serial Ports
|
||||
|
||||
| Value | Identifier | RX | TX | Notes |
|
||||
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
|
||||
| 1 | USART1 | RX / PA10 | TX / PA9 / TELEM | TELEM output is always inverted (for FrSky). Internally connected to USB port via CP2102 IC |
|
||||
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
|
||||
| 3 | USART3 | F3 / PB11 | F2 / PB10 | Flex port is configured as UART3 when port is configured |
|
||||
| 4 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | |
|
||||
|
|
@ -13,11 +13,11 @@ a dedicated USB to UART adapter. VCP does not 'use' a physical UART port.
|
|||
* UART - A pair of dedicated hardware transmit and receive pins with signal detection and generation done in hardware.
|
||||
* SoftSerial - A pair of hardware transmit and receive pins with signal detection and generation done in software.
|
||||
|
||||
UART is the most efficient in terms of CPU usage.
|
||||
SoftSerial is the least efficient and slowest, SoftSerial should only be used for low-bandwidth usages, such as telemetry transmission.
|
||||
UART is the most efficent in terms of CPU usage.
|
||||
SoftSerial is the least efficient and slowest, SoftSerial should only be used for low-bandwith usages, such as telemetry transmission.
|
||||
|
||||
UART ports are sometimes exposed via on-board USB to UART converters, such as the CP2102 as found on the Naze and Flip32 boards.
|
||||
If the flight controller does not have an on-board USB to UART converter and doesn't support VCP then an external USB to UART board is required.
|
||||
If the flight controller does not have an onboard USB to UART converter and doesn't support VCP then an external USB to UART board is required.
|
||||
These are sometimes referred to as FTDI boards. FTDI is just a common manufacturer of a chip (the FT232RL) used on USB to UART boards.
|
||||
|
||||
When selecting a USB to UART converter choose one that has DTR exposed as well as a selector for 3.3v and 5v since they are more useful.
|
||||
|
@ -31,9 +31,9 @@ Both SoftSerial and UART ports can be connected to your computer via USB to UART
|
|||
|
||||
## Serial Configuration
|
||||
|
||||
Serial port configuration is best done via the configurator.
|
||||
Serial port configuration is best done via the configurator. You can use the CLI too but the commands are reserved for developers and advanced users.
|
||||
|
||||
Configure serial ports first, then enable/disable features that use the ports. To configure SoftSerial ports the SOFTSERIAL feature must be also be enabled.
|
||||
Configure serial ports first, then enable/disable features that use the ports.
|
||||
|
||||
### Constraints
|
||||
|
||||
|
@ -52,23 +52,9 @@ e.g. after configuring a port for GPS enable the GPS feature.
|
|||
* You can use as many different telemetry systems as you like at the same time.
|
||||
* You can only use each telemetry system once. e.g. FrSky telemetry cannot be used on two port, but MSP Telemetry + FrSky on different ports is fine.
|
||||
|
||||
### Configuration via CLI
|
||||
|
||||
You can use the CLI for configuration but the commands are reserved for developers and advanced users.
|
||||
|
||||
The `serial` CLI command takes 6 arguments.
|
||||
|
||||
1. Identifier
|
||||
1. Function bitmask (see serialPortFunction_e in the source)
|
||||
1. MSP baud rate
|
||||
1. GPS baud rate
|
||||
1. Telemetry baud rate (auto baud allowed)
|
||||
1. Blackbox baud rate
|
||||
|
||||
|
||||
### Baud Rates
|
||||
|
||||
The allowable baud rates are as follows:
|
||||
Each baud rate is assigned an identifier, they are as follows:
|
||||
|
||||
| Identifier | Baud rate |
|
||||
| ---------- | --------- |
|
||||
|
@ -80,4 +66,3 @@ The allowable baud rates are as follows:
|
|||
| 5 | 115200 |
|
||||
| 6 | 230400 |
|
||||
| 7 | 250000 |
|
||||
|
||||
|
|
|
@ -19,8 +19,6 @@ Currently the only supported sensor is the HCSR04 sensor.
|
|||
| Parallel PWM/ADC current sensor | PB8 / Motor 5 | PB9 / Motor 6 | NO (5v tolerant) |
|
||||
| PPM/Serial RX | PB0 / RC7 | PB1 / RC8 | YES (3.3v input) |
|
||||
|
||||
#### Constraints
|
||||
|
||||
Current meter cannot be used in conjunction with Parallel PWM and Sonar.
|
||||
|
||||
### Olimexino
|
||||
|
@ -29,18 +27,4 @@ Current meter cannot be used in conjunction with Parallel PWM and Sonar.
|
|||
| ------------- | ------------- | ------------------- |
|
||||
| PB0 / RC7 | PB1 / RC8 | YES (3.3v input) |
|
||||
|
||||
#### Constraints
|
||||
|
||||
Current meter cannot be used in conjunction with Sonar.
|
||||
|
||||
### CC3D
|
||||
|
||||
| Trigger | Echo | Inline 1k resistors |
|
||||
| ------------- | ------------- | ------------------- |
|
||||
| PB5 | PB0 | YES (3.3v input) |
|
||||
|
||||
Sonar support is not available when using the OpenPilot bootloader (OPBL).
|
||||
|
||||
#### Constraints
|
||||
|
||||
Sonar cannot be used in conjuction with SoftSerial or Parallel PWM.
|
||||
Current meter cannot be used in conjunction with sonar.
|
||||
|
|
|
@ -34,12 +34,12 @@ Please refer to the satellite receiver documentation for more details of the spe
|
|||
|
||||
## Table with spektrum_sat_bind parameter value
|
||||
|
||||
| Value | Receiver mode | Notes |
|
||||
| ----- | ------------------| -------------------|
|
||||
| 3 | DSM2 1024bit/22ms | |
|
||||
| 5 | DSM2 2048bit/11ms | default AlienWii32 |
|
||||
| 7 | DSMX 1024bit/22ms | |
|
||||
| 9 | DSMX 2048bit/11ms | |
|
||||
| Value | Receiver mode | Notes |
|
||||
| ----- | ---------------| -------------------|
|
||||
| 3 | DSM2 1024/22ms | |
|
||||
| 5 | DSM2 2048/11ms | default AlienWii32 |
|
||||
| 7 | DSMX 22ms | |
|
||||
| 9 | DSMX 11ms | |
|
||||
|
||||
More detailed information regarding the satellite binding process can be found here:
|
||||
http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
|
||||
|
@ -50,15 +50,15 @@ NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets and ALIENWIIF1, ALIE
|
|||
|
||||
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller
|
||||
|
||||
The Flip32/Flip32+ is wired in a rather strange way, i.e. the dedicated connector for the satellite module uses the same UART pins as the USB adapter. This means that you can't use that connector as it maps to UART1 which you really shouldn't assign to SERIAL_RX as that will break USB functionality. (Looks this problem is fixed in later versions of the Flip32/Flip32+)
|
||||
The Flip32+ is wired in a rather strange way, i.e. the dedicated connector for the satellite module uses the same UART pins as the USB adapter. This means that you can't use that connector as it maps to UART1 which you really shouldn't assign to SERIAL_RX as that will break USB functionality.
|
||||
|
||||
In order to connect the satellite to a Flip32+, you have to wire the serial data pin to RC_CH4. This is the fourth pin from the top in the left column of the 3x6 header on the right side of the board. GND and +3.3V may either be obtained from the dedicated SAT connector or from any ground pin and pin 1 of the BOOT connector which also provides 3.3V.
|
||||
|
||||
#### Tested satellite transmitter combinations
|
||||
|
||||
| Satellite | Remote | Remark |
|
||||
| -------------------- | -------------- | -------------------------------------------------------- |
|
||||
| Orange R100 | Spektrum DX6i | Bind value 3 |
|
||||
| Lemon RX DSM2/DSMX | Spektrum DX8 | Bind value 5 |
|
||||
| Lemon RX DSMX | Walkera Devo10 | Bind value 9, Deviation firmware 4.01 up to 12 channels |
|
||||
| Lemon RX DSM2 | Walkera Devo7 | Bind value 9, Deviation firmware |
|
||||
| Satellite | Remote | Remark |
|
||||
| -------------------- | -------------- | ------------------------------------------ |
|
||||
| Orange R100 | Spektrum DX6i | Bind value 3 |
|
||||
| Lemon RX DSM2/DSMX | Spektrum DX8 | |
|
||||
| Lemon RX DSMX | Walkera Devo10 | Deviation firmware 4.01 up to 12 channels |
|
||||
| Lemon RX DSM2 | Walkera Devo7 | Deviation firmware |
|
||||
|
|
|
@ -61,8 +61,6 @@ You can also step-debug the tests in eclipse and you can use the GoogleTest test
|
|||
|
||||
The tests are currently always compiled with debugging information enabled, there may be additional warnings, if you see any warnings please attempt to fix them and submit pull requests with the fixes.
|
||||
|
||||
Tests are verified and working with GCC 4.9.2.
|
||||
|
||||
## Using git and github
|
||||
|
||||
Ensure you understand the github workflow: https://guides.github.com/introduction/flow/index.html
|
||||
|
|
|
@ -1,8 +1,8 @@
|
|||
### IO variables
|
||||
|
||||
`gyroADC/8192*2000 = deg/s`
|
||||
`gyroData/8192*2000 = deg/s`
|
||||
|
||||
`gyroADC/4 ~ deg/s`
|
||||
`gyroData/4 ~ deg/s`
|
||||
|
||||
`rcCommand` - `<-500 - 500>` nominal, but is scaled with `rcRate/100`, max +-1250
|
||||
|
||||
|
@ -23,7 +23,7 @@ Iacc = intergrate(error, limit +-10000) * I8[PIDLEVEL] / 4096
|
|||
#### Gyro term
|
||||
```
|
||||
Pgyro = rcCommand[axis];
|
||||
error = rcCommand[axis] * 10 * 8 / pidProfile->P8[axis] - gyroADC[axis] / 4; (conversion so that error is in deg/s ?)
|
||||
error = rcCommand[axis] * 10 * 8 / pidProfile->P8[axis] - gyroData[axis] / 4; (conversion so that error is in deg/s ?)
|
||||
Igyro = integrate(error, limit +-16000) / 10 / 8 * I8[axis] / 100 (conversion back to mixer units ?)
|
||||
```
|
||||
|
||||
|
@ -52,12 +52,12 @@ reset I term if
|
|||
#### Gyro stabilization
|
||||
|
||||
```
|
||||
P -= gyroADC[axis] / 4 * dynP8 / 10 / 8
|
||||
D = -mean(diff(gyroADC[axis] / 4), over 3 samples) * 3 * dynD8 / 32
|
||||
P -= gyroData[axis] / 4 * dynP8 / 10 / 8
|
||||
D = -mean(diff(gyroData[axis] / 4), over 3 samples) * 3 * dynD8 / 32
|
||||
[equivalent to :]
|
||||
D = - (gyroADC[axis]/4 - (<3 loops old>gyroADC[axis]/4)) * dynD8 / 32
|
||||
D = - (gyroData[axis]/4 - (<3 loops old>gyroData[axis]/4)) * dynD8 / 32
|
||||
```
|
||||
|
||||
This can be seen as sum of
|
||||
- PI controller (handles rcCommand, HORIZON/ANGLE); `Igyro` is only output based on gyroADC
|
||||
- PD controller(parameters dynP8/dynD8) with zero setpoint acting on gyroADC
|
||||
- PI controller (handles rcCommand, HORIZON/ANGLE); `Igyro` is only output based on gyroData
|
||||
- PD controller(parameters dynP8/dynD8) with zero setpoint acting on gyroData
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
|
||||
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */
|
||||
|
||||
static const uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9 };
|
||||
__I uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9 };
|
||||
|
||||
uint32_t hse_value = 8000000;
|
||||
|
||||
|
|
|
@ -190,8 +190,8 @@
|
|||
* @{
|
||||
*/
|
||||
|
||||
static const uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
static const uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
|
||||
static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8};
|
||||
extern uint32_t hse_value;
|
||||
|
||||
/**
|
||||
|
|
|
@ -202,9 +202,9 @@ static const blackboxMainFieldDefinition_t blackboxMainFields[] = {
|
|||
#endif
|
||||
|
||||
/* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */
|
||||
{"gyroADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroData", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroData", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"gyroData", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
{"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
|
||||
|
@ -250,6 +250,7 @@ typedef enum BlackboxState {
|
|||
BLACKBOX_STATE_SEND_GPS_H_HEADERS,
|
||||
BLACKBOX_STATE_SEND_GPS_G_HEADERS,
|
||||
BLACKBOX_STATE_SEND_SYSINFO,
|
||||
BLACKBOX_STATE_PRERUN,
|
||||
BLACKBOX_STATE_RUNNING,
|
||||
BLACKBOX_STATE_SHUTTING_DOWN
|
||||
} BlackboxState;
|
||||
|
@ -267,8 +268,6 @@ extern uint32_t currentTime;
|
|||
|
||||
static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
|
||||
|
||||
static uint32_t blackboxLastArmingBeep = 0;
|
||||
|
||||
static struct {
|
||||
uint32_t headerIndex;
|
||||
|
||||
|
@ -486,7 +485,7 @@ static void writeIntraframe(void)
|
|||
#endif
|
||||
|
||||
for (x = 0; x < XYZ_AXIS_COUNT; x++) {
|
||||
blackboxWriteSignedVB(blackboxCurrent->gyroADC[x]);
|
||||
blackboxWriteSignedVB(blackboxCurrent->gyroData[x]);
|
||||
}
|
||||
|
||||
for (x = 0; x < XYZ_AXIS_COUNT; x++) {
|
||||
|
@ -602,7 +601,7 @@ static void writeInterframe(void)
|
|||
|
||||
//Since gyros, accs and motors are noisy, base the prediction on the average of the history:
|
||||
for (x = 0; x < XYZ_AXIS_COUNT; x++) {
|
||||
blackboxWriteSignedVB(blackboxHistory[0]->gyroADC[x] - (blackboxHistory[1]->gyroADC[x] + blackboxHistory[2]->gyroADC[x]) / 2);
|
||||
blackboxWriteSignedVB(blackboxHistory[0]->gyroData[x] - (blackboxHistory[1]->gyroData[x] + blackboxHistory[2]->gyroData[x]) / 2);
|
||||
}
|
||||
|
||||
for (x = 0; x < XYZ_AXIS_COUNT; x++) {
|
||||
|
@ -685,12 +684,6 @@ void startBlackbox(void)
|
|||
*/
|
||||
blackboxBuildConditionCache();
|
||||
|
||||
/*
|
||||
* Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
|
||||
* it finally plays the beep for this arming event.
|
||||
*/
|
||||
blackboxLastArmingBeep = getArmingBeepTimeMicros();
|
||||
|
||||
blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
|
||||
}
|
||||
}
|
||||
|
@ -781,7 +774,7 @@ static void loadBlackboxState(void)
|
|||
}
|
||||
|
||||
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
|
||||
blackboxCurrent->gyroADC[i] = gyroADC[i];
|
||||
blackboxCurrent->gyroData[i] = gyroData[i];
|
||||
}
|
||||
|
||||
for (i = 0; i < XYZ_AXIS_COUNT; i++) {
|
||||
|
@ -1019,19 +1012,16 @@ void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
|
|||
}
|
||||
}
|
||||
|
||||
/* If an arming beep has played since it was last logged, write the time of the arming beep to the log as a synchronization point */
|
||||
static void blackboxCheckAndLogArmingBeep()
|
||||
// Write the time of the last arming beep to the log as a synchronization point
|
||||
static void blackboxLogArmingBeep()
|
||||
{
|
||||
flightLogEvent_syncBeep_t eventData;
|
||||
|
||||
// Use != so that we can still detect a change if the counter wraps
|
||||
if (getArmingBeepTimeMicros() != blackboxLastArmingBeep) {
|
||||
blackboxLastArmingBeep = getArmingBeepTimeMicros();
|
||||
// Get time of last arming beep (in system-uptime microseconds)
|
||||
eventData.time = getArmingBeepTimeMicros();
|
||||
|
||||
eventData.time = blackboxLastArmingBeep;
|
||||
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP, (flightLogEventData_t *) &eventData);
|
||||
}
|
||||
// Write the time to the log
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP, (flightLogEventData_t *) &eventData);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -1092,9 +1082,14 @@ void handleBlackbox(void)
|
|||
|
||||
//Keep writing chunks of the system info headers until it returns true to signal completion
|
||||
if (blackboxWriteSysinfo()) {
|
||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||
blackboxSetState(BLACKBOX_STATE_PRERUN);
|
||||
}
|
||||
break;
|
||||
case BLACKBOX_STATE_PRERUN:
|
||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||
|
||||
blackboxLogArmingBeep();
|
||||
break;
|
||||
case BLACKBOX_STATE_RUNNING:
|
||||
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
||||
|
||||
|
@ -1104,8 +1099,6 @@ void handleBlackbox(void)
|
|||
loadBlackboxState();
|
||||
writeIntraframe();
|
||||
} else {
|
||||
blackboxCheckAndLogArmingBeep();
|
||||
|
||||
/* Adding a magic shift of "masterConfig.blackbox_rate_num - 1" in here creates a better spread of
|
||||
* recorded / skipped frames when the I frame's position is considered:
|
||||
*/
|
||||
|
|
|
@ -29,7 +29,7 @@ typedef struct blackboxValues_t {
|
|||
int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
|
||||
|
||||
int16_t rcCommand[4];
|
||||
int16_t gyroADC[XYZ_AXIS_COUNT];
|
||||
int16_t gyroData[XYZ_AXIS_COUNT];
|
||||
int16_t accSmooth[XYZ_AXIS_COUNT];
|
||||
int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
|
|
|
@ -44,7 +44,7 @@
|
|||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/statusindicator.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
|
@ -73,6 +73,17 @@
|
|||
#define BRUSHED_MOTORS_PWM_RATE 16000
|
||||
#define BRUSHLESS_MOTORS_PWM_RATE 400
|
||||
|
||||
void mixerUseConfigs(
|
||||
#ifdef USE_SERVOS
|
||||
servoParam_t *servoConfToUse,
|
||||
gimbalConfig_t *gimbalConfigToUse,
|
||||
#endif
|
||||
flight3DConfig_t *flight3DConfigToUse,
|
||||
escAndServoConfig_t *escAndServoConfigToUse,
|
||||
mixerConfig_t *mixerConfigToUse,
|
||||
airplaneConfig_t *airplaneConfigToUse,
|
||||
rxConfig_t *rxConfig
|
||||
);
|
||||
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
|
||||
|
||||
#define FLASH_TO_RESERVE_FOR_CONFIG 0x800
|
||||
|
@ -123,12 +134,11 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
|||
|
||||
master_t masterConfig; // master config struct with data independent from profiles
|
||||
profile_t *currentProfile;
|
||||
static uint32_t activeFeaturesLatch = 0;
|
||||
|
||||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 101;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 100;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -524,7 +534,6 @@ static void resetConf(void)
|
|||
#else
|
||||
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
|
||||
#endif
|
||||
masterConfig.rxConfig.serialrx_provider = 1;
|
||||
masterConfig.rxConfig.spektrum_sat_bind = 5;
|
||||
masterConfig.escAndServoConfig.minthrottle = 1000;
|
||||
masterConfig.escAndServoConfig.maxthrottle = 2000;
|
||||
|
@ -715,26 +724,26 @@ void activateConfig(void)
|
|||
|
||||
void validateAndFixConfig(void)
|
||||
{
|
||||
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
|
||||
if (!(feature(FEATURE_RX_PARALLEL_PWM) || feature(FEATURE_RX_PPM) || feature(FEATURE_RX_SERIAL) || feature(FEATURE_RX_MSP))) {
|
||||
featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_PPM)) {
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_MSP)) {
|
||||
if (feature(FEATURE_RX_MSP)) {
|
||||
featureClear(FEATURE_RX_SERIAL);
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
featureClear(FEATURE_RX_PPM);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||
if (feature(FEATURE_RX_SERIAL)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM);
|
||||
featureClear(FEATURE_RX_PPM);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
#if defined(STM32F10X)
|
||||
// rssi adc needs the same ports
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
|
@ -755,7 +764,7 @@ void validateAndFixConfig(void)
|
|||
|
||||
|
||||
#if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||
if (featureConfigured(FEATURE_SOFTSERIAL) && (
|
||||
if (feature(FEATURE_SOFTSERIAL) && (
|
||||
0
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
|| (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
|
||||
|
@ -770,7 +779,7 @@ void validateAndFixConfig(void)
|
|||
#endif
|
||||
|
||||
#if defined(NAZE) && defined(SONAR)
|
||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM) && feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
}
|
||||
#endif
|
||||
|
@ -795,12 +804,6 @@ void validateAndFixConfig(void)
|
|||
masterConfig.mixerConfig.pid_at_min_throttle = 0;
|
||||
}
|
||||
|
||||
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1)
|
||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||
featureClear(FEATURE_SONAR);
|
||||
}
|
||||
#endif
|
||||
|
||||
useRxConfig(&masterConfig.rxConfig);
|
||||
|
||||
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
||||
|
@ -841,7 +844,7 @@ void readEEPROMAndNotify(void)
|
|||
{
|
||||
// re-read written data
|
||||
readEEPROM();
|
||||
beeperConfirmationBeeps(1);
|
||||
blinkLedAndSoundBeeper(15, 20, 1);
|
||||
}
|
||||
|
||||
void writeEEPROM(void)
|
||||
|
@ -922,7 +925,7 @@ void changeProfile(uint8_t profileIndex)
|
|||
masterConfig.current_profile_index = profileIndex;
|
||||
writeEEPROM();
|
||||
readEEPROM();
|
||||
beeperConfirmationBeeps(profileIndex + 1);
|
||||
blinkLedAndSoundBeeper(2, 40, profileIndex + 1);
|
||||
}
|
||||
|
||||
void changeControlRateProfile(uint8_t profileIndex)
|
||||
|
@ -934,30 +937,9 @@ void changeControlRateProfile(uint8_t profileIndex)
|
|||
activateControlRateConfig();
|
||||
}
|
||||
|
||||
void handleOneshotFeatureChangeOnRestart(void)
|
||||
{
|
||||
// Shutdown PWM on all motors prior to soft restart
|
||||
StopPwmAllMotors();
|
||||
delay(50);
|
||||
// Apply additional delay when OneShot125 feature changed from on to off state
|
||||
if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
|
||||
delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
|
||||
}
|
||||
}
|
||||
|
||||
void latchActiveFeatures()
|
||||
{
|
||||
activeFeaturesLatch = masterConfig.enabledFeatures;
|
||||
}
|
||||
|
||||
bool featureConfigured(uint32_t mask)
|
||||
{
|
||||
return masterConfig.enabledFeatures & mask;
|
||||
}
|
||||
|
||||
bool feature(uint32_t mask)
|
||||
{
|
||||
return activeFeaturesLatch & mask;
|
||||
return masterConfig.enabledFeatures & mask;
|
||||
}
|
||||
|
||||
void featureSet(uint32_t mask)
|
||||
|
|
|
@ -19,7 +19,6 @@
|
|||
|
||||
#define MAX_PROFILE_COUNT 3
|
||||
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
|
||||
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
||||
|
||||
|
||||
typedef enum {
|
||||
|
@ -45,9 +44,6 @@ typedef enum {
|
|||
FEATURE_BLACKBOX = 1 << 19
|
||||
} features_e;
|
||||
|
||||
void handleOneshotFeatureChangeOnRestart(void);
|
||||
void latchActiveFeatures(void);
|
||||
bool featureConfigured(uint32_t mask);
|
||||
bool feature(uint32_t mask);
|
||||
void featureSet(uint32_t mask);
|
||||
void featureClear(uint32_t mask);
|
||||
|
|
|
@ -57,7 +57,7 @@
|
|||
static uint8_t mpuLowPassFilter = L3G4200D_DLPF_32HZ;
|
||||
|
||||
static void l3g4200dInit(void);
|
||||
static void l3g4200dRead(int16_t *gyroADC);
|
||||
static void l3g4200dRead(int16_t *gyroData);
|
||||
|
||||
bool l3g4200dDetect(gyro_t *gyro, uint16_t lpf)
|
||||
{
|
||||
|
@ -110,13 +110,13 @@ static void l3g4200dInit(void)
|
|||
}
|
||||
|
||||
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
||||
static void l3g4200dRead(int16_t *gyroADC)
|
||||
static void l3g4200dRead(int16_t *gyroData)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
i2cRead(L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf);
|
||||
|
||||
gyroADC[X] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroADC[Y] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroADC[Z] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
gyroData[X] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroData[Y] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroData[Z] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
}
|
||||
|
|
|
@ -120,7 +120,7 @@ void l3gd20GyroInit(void)
|
|||
delay(100);
|
||||
}
|
||||
|
||||
static void l3gd20GyroRead(int16_t *gyroADC)
|
||||
static void l3gd20GyroRead(int16_t *gyroData)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
|
@ -134,9 +134,9 @@ static void l3gd20GyroRead(int16_t *gyroADC)
|
|||
|
||||
GPIO_SetBits(L3GD20_CS_GPIO, L3GD20_CS_PIN);
|
||||
|
||||
gyroADC[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroADC[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroADC[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
|
||||
#if 0
|
||||
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
|
||||
|
|
|
@ -106,7 +106,7 @@ void lsm303dlhcAccInit(void)
|
|||
}
|
||||
|
||||
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
||||
static void lsm303dlhcAccRead(int16_t *gyroADC)
|
||||
static void lsm303dlhcAccRead(int16_t *gyroData)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
|
@ -116,9 +116,9 @@ static void lsm303dlhcAccRead(int16_t *gyroADC)
|
|||
return;
|
||||
|
||||
// the values range from -8192 to +8191
|
||||
gyroADC[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2;
|
||||
gyroADC[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2;
|
||||
gyroADC[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2;
|
||||
gyroData[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2;
|
||||
gyroData[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2;
|
||||
gyroData[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2;
|
||||
|
||||
#if 0
|
||||
debug[0] = (int16_t)((buf[1] << 8) | buf[0]);
|
||||
|
|
|
@ -58,7 +58,7 @@
|
|||
static uint8_t mpuLowPassFilter = MPU3050_DLPF_42HZ;
|
||||
|
||||
static void mpu3050Init(void);
|
||||
static void mpu3050Read(int16_t *gyroADC);
|
||||
static void mpu3050Read(int16_t *gyroData);
|
||||
static void mpu3050ReadTemp(int16_t *tempData);
|
||||
|
||||
bool mpu3050Detect(gyro_t *gyro, uint16_t lpf)
|
||||
|
@ -121,15 +121,15 @@ static void mpu3050Init(void)
|
|||
}
|
||||
|
||||
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
|
||||
static void mpu3050Read(int16_t *gyroADC)
|
||||
static void mpu3050Read(int16_t *gyroData)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
i2cRead(MPU3050_ADDRESS, MPU3050_GYRO_OUT, 6, buf);
|
||||
|
||||
gyroADC[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroADC[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroADC[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
}
|
||||
|
||||
static void mpu3050ReadTemp(int16_t *tempData)
|
||||
|
|
|
@ -175,7 +175,7 @@ static uint8_t mpuLowPassFilter = INV_FILTER_42HZ;
|
|||
static void mpu6050AccInit(void);
|
||||
static void mpu6050AccRead(int16_t *accData);
|
||||
static void mpu6050GyroInit(void);
|
||||
static void mpu6050GyroRead(int16_t *gyroADC);
|
||||
static void mpu6050GyroRead(int16_t *gyroData);
|
||||
|
||||
typedef enum {
|
||||
MPU_6050_HALF_RESOLUTION,
|
||||
|
@ -439,7 +439,7 @@ static void mpu6050GyroInit(void)
|
|||
#endif
|
||||
}
|
||||
|
||||
static void mpu6050GyroRead(int16_t *gyroADC)
|
||||
static void mpu6050GyroRead(int16_t *gyroData)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
|
@ -447,7 +447,7 @@ static void mpu6050GyroRead(int16_t *gyroADC)
|
|||
return;
|
||||
}
|
||||
|
||||
gyroADC[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroADC[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroADC[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
}
|
||||
|
|
|
@ -125,8 +125,8 @@ static bool mpuSpi6000InitDone = false;
|
|||
#define DISABLE_MPU6000 GPIO_SetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
|
||||
#define ENABLE_MPU6000 GPIO_ResetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
|
||||
|
||||
void mpu6000SpiGyroRead(int16_t *gyroADC);
|
||||
void mpu6000SpiAccRead(int16_t *gyroADC);
|
||||
void mpu6000SpiGyroRead(int16_t *gyroData);
|
||||
void mpu6000SpiAccRead(int16_t *gyroData);
|
||||
|
||||
static void mpu6000WriteRegister(uint8_t reg, uint8_t data)
|
||||
{
|
||||
|
|
|
@ -16,5 +16,5 @@
|
|||
bool mpu6000SpiAccDetect(acc_t *acc);
|
||||
bool mpu6000SpiGyroDetect(gyro_t *gyro, uint16_t lpf);
|
||||
|
||||
void mpu6000SpiGyroRead(int16_t *gyroADC);
|
||||
void mpu6000SpiAccRead(int16_t *gyroADC);
|
||||
void mpu6000SpiGyroRead(int16_t *gyroData);
|
||||
void mpu6000SpiAccRead(int16_t *gyroData);
|
||||
|
|
|
@ -74,7 +74,7 @@ static uint8_t mpuLowPassFilter = INV_FILTER_42HZ;
|
|||
static void mpu6500AccInit(void);
|
||||
static void mpu6500AccRead(int16_t *accData);
|
||||
static void mpu6500GyroInit(void);
|
||||
static void mpu6500GyroRead(int16_t *gyroADC);
|
||||
static void mpu6500GyroRead(int16_t *gyroData);
|
||||
|
||||
extern uint16_t acc_1G;
|
||||
|
||||
|
@ -188,13 +188,13 @@ static void mpu6500GyroInit(void)
|
|||
mpu6500WriteRegister(MPU6500_RA_RATE_DIV, 0); // 1kHz S/R
|
||||
}
|
||||
|
||||
static void mpu6500GyroRead(int16_t *gyroADC)
|
||||
static void mpu6500GyroRead(int16_t *gyroData)
|
||||
{
|
||||
uint8_t buf[6];
|
||||
|
||||
mpu6500ReadRegister(MPU6500_RA_GYRO_XOUT_H, buf, 6);
|
||||
|
||||
gyroADC[X] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroADC[Y] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroADC[Z] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
gyroData[X] = (int16_t)((buf[0] << 8) | buf[1]);
|
||||
gyroData[Y] = (int16_t)((buf[2] << 8) | buf[3]);
|
||||
gyroData[Z] = (int16_t)((buf[4] << 8) | buf[5]);
|
||||
}
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
|
||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex);
|
||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t idlePulse);
|
||||
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
||||
|
||||
/*
|
||||
|
@ -408,6 +408,29 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
continue;
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
// skip Sonar pins
|
||||
// FIXME - Hack - See sonar.c sonarInit() and sonarHardware_t
|
||||
if (init->useSonar && timerHardwarePtr->gpio == GPIOB) {
|
||||
#if defined(SPRACINGF3) || defined(OLIMEXINO)
|
||||
if (timerHardwarePtr->pin == GPIO_Pin_0 || timerHardwarePtr->pin == GPIO_Pin_1) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
#if defined(NAZE)
|
||||
if (init->useParallelPWM) {
|
||||
if (timerHardwarePtr->pin == GPIO_Pin_8 || timerHardwarePtr->pin == GPIO_Pin_9) {
|
||||
continue;
|
||||
}
|
||||
} else {
|
||||
if (timerHardwarePtr->pin == GPIO_Pin_0 || timerHardwarePtr->pin == GPIO_Pin_1) {
|
||||
continue;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef SOFTSERIAL_1_TIMER
|
||||
if (init->useSoftSerial && timerHardwarePtr->tim == SOFTSERIAL_1_TIMER)
|
||||
continue;
|
||||
|
@ -448,17 +471,6 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef SONAR
|
||||
if (init->sonarGPIOConfig && timerHardwarePtr->gpio == init->sonarGPIOConfig->gpio &&
|
||||
(
|
||||
timerHardwarePtr->pin == init->sonarGPIOConfig->triggerPin ||
|
||||
timerHardwarePtr->pin == init->sonarGPIOConfig->echoPin
|
||||
)
|
||||
) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
// hacks to allow current functionality
|
||||
if (type == MAP_TO_PWM_INPUT && !init->useParallelPWM)
|
||||
continue;
|
||||
|
@ -543,7 +555,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
channelIndex++;
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
if (init->useOneshot) {
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount);
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->idlePulse);
|
||||
} else if (init->motorPwmRate > 500) {
|
||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||
} else {
|
||||
|
|
|
@ -36,12 +36,6 @@
|
|||
#define PWM_TIMER_MHZ 1
|
||||
#define ONESHOT125_TIMER_MHZ 8
|
||||
|
||||
typedef struct sonarGPIOConfig_s {
|
||||
GPIO_TypeDef *gpio;
|
||||
uint16_t triggerPin;
|
||||
uint16_t echoPin;
|
||||
} sonarGPIOConfig_t;
|
||||
|
||||
typedef struct drv_pwm_config_t {
|
||||
bool useParallelPWM;
|
||||
bool usePPM;
|
||||
|
@ -71,7 +65,6 @@ typedef struct drv_pwm_config_t {
|
|||
uint16_t motorPwmRate;
|
||||
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
|
||||
// some higher value (used by 3d mode), or 0, for brushed pwm drivers.
|
||||
sonarGPIOConfig_t *sonarGPIOConfig;
|
||||
} drv_pwm_config_t;
|
||||
|
||||
|
||||
|
|
|
@ -142,16 +142,6 @@ void pwmWriteMotor(uint8_t index, uint16_t value)
|
|||
motors[index]->pwmWritePtr(index, value);
|
||||
}
|
||||
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
||||
for(index = 0; index < motorCount; index++){
|
||||
// Set the compare register to 0, which stops the output pulsing if the timer overflows
|
||||
*motors[index]->ccr = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
@ -186,9 +176,9 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor
|
|||
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
||||
}
|
||||
|
||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex)
|
||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t idlePulse)
|
||||
{
|
||||
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, 0);
|
||||
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, idlePulse);
|
||||
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
||||
}
|
||||
|
||||
|
|
|
@ -18,7 +18,6 @@
|
|||
#pragma once
|
||||
|
||||
void pwmWriteMotor(uint8_t index, uint16_t value);
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);
|
||||
|
||||
void pwmWriteServo(uint8_t index, uint16_t value);
|
||||
|
|
|
@ -58,11 +58,6 @@ static void ECHO_EXTI_IRQHandler(void)
|
|||
EXTI_ClearITPendingBit(sonarHardware->exti_line);
|
||||
}
|
||||
|
||||
void EXTI0_IRQHandler(void)
|
||||
{
|
||||
ECHO_EXTI_IRQHandler();
|
||||
}
|
||||
|
||||
void EXTI1_IRQHandler(void)
|
||||
{
|
||||
ECHO_EXTI_IRQHandler();
|
||||
|
|
|
@ -25,8 +25,6 @@ typedef struct sonarHardware_s {
|
|||
IRQn_Type exti_irqn;
|
||||
} sonarHardware_t;
|
||||
|
||||
#define SONAR_GPIO GPIOB
|
||||
|
||||
void hcsr04_init(const sonarHardware_t *sonarHardware);
|
||||
|
||||
void hcsr04_start_reading(void);
|
||||
|
|
|
@ -60,7 +60,7 @@ typedef struct timerOvrHandlerRec_s {
|
|||
typedef struct {
|
||||
TIM_TypeDef *tim;
|
||||
GPIO_TypeDef *gpio;
|
||||
uint16_t pin;
|
||||
uint32_t pin;
|
||||
uint8_t channel;
|
||||
uint8_t irq;
|
||||
uint8_t outputEnable;
|
||||
|
|
|
@ -184,10 +184,10 @@ static void autotuneLogAngleTargets(float currentAngle)
|
|||
eventData.targetAngleAtPeak = (int) targetAngleAtPeak;
|
||||
|
||||
// currentAngle is integer decidegrees divided by 10, so just reverse that process to get an integer again:
|
||||
eventData.currentAngle = round(currentAngle * 10);
|
||||
eventData.currentAngle = roundf(currentAngle * 10);
|
||||
// the peak angles are only ever set to currentAngle, so they get the same treatment:
|
||||
eventData.firstPeakAngle = round(firstPeakAngle * 10);
|
||||
eventData.secondPeakAngle = round(secondPeakAngle * 10);
|
||||
eventData.firstPeakAngle = roundf(firstPeakAngle * 10);
|
||||
eventData.secondPeakAngle = roundf(secondPeakAngle * 10);
|
||||
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_AUTOTUNE_TARGETS, (flightLogEventData_t*)&eventData);
|
||||
}
|
||||
|
|
|
@ -48,6 +48,7 @@
|
|||
|
||||
int16_t accSmooth[XYZ_AXIS_COUNT];
|
||||
int32_t accSum[XYZ_AXIS_COUNT];
|
||||
int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT] = { 0, 0, 0 };
|
||||
|
||||
uint32_t accTimeSum = 0; // keep track for integration of acc
|
||||
int accSumCount = 0;
|
||||
|
@ -297,10 +298,11 @@ static void imuCalculateEstimatedAttitude(void)
|
|||
imuCalculateAcceleration(deltaT); // rotate acc vector into earth frame
|
||||
}
|
||||
|
||||
void imuUpdate(rollAndPitchTrims_t *accelerometerTrims)
|
||||
void imuUpdate(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerMode)
|
||||
{
|
||||
gyroUpdate();
|
||||
static int16_t gyroYawSmooth = 0;
|
||||
|
||||
gyroUpdate();
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
updateAccelerationReadings(accelerometerTrims); // TODO rename to accelerometerUpdate and rename many other 'Acceleration' references to be 'Accelerometer'
|
||||
imuCalculateEstimatedAttitude();
|
||||
|
@ -309,6 +311,16 @@ void imuUpdate(rollAndPitchTrims_t *accelerometerTrims)
|
|||
accADC[Y] = 0;
|
||||
accADC[Z] = 0;
|
||||
}
|
||||
|
||||
gyroData[FD_ROLL] = gyroADC[FD_ROLL];
|
||||
gyroData[FD_PITCH] = gyroADC[FD_PITCH];
|
||||
|
||||
if (mixerMode == MIXER_TRI) {
|
||||
gyroData[FD_YAW] = (gyroYawSmooth * 2 + gyroADC[FD_YAW]) / 3;
|
||||
gyroYawSmooth = gyroData[FD_YAW];
|
||||
} else {
|
||||
gyroData[FD_YAW] = gyroADC[FD_YAW];
|
||||
}
|
||||
}
|
||||
|
||||
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value)
|
||||
|
|
|
@ -24,6 +24,7 @@ extern float accVelScale;
|
|||
extern t_fp_vector EstG;
|
||||
extern int16_t accSmooth[XYZ_AXIS_COUNT];
|
||||
extern int32_t accSum[XYZ_AXIS_COUNT];
|
||||
extern int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||
extern int16_t smallAngle;
|
||||
|
||||
typedef struct rollAndPitchInclination_s {
|
||||
|
@ -61,7 +62,7 @@ void imuConfigure(
|
|||
);
|
||||
|
||||
void calculateEstimatedAltitude(uint32_t currentTime);
|
||||
void imuUpdate(rollAndPitchTrims_t *accelerometerTrims);
|
||||
void imuUpdate(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerMode);
|
||||
float calculateThrottleAngleScale(uint16_t throttle_correction_angle);
|
||||
int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value);
|
||||
float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff);
|
||||
|
|
|
@ -513,11 +513,6 @@ void stopMotors(void)
|
|||
delay(50); // give the timers and ESCs a chance to react.
|
||||
}
|
||||
|
||||
void StopPwmAllMotors()
|
||||
{
|
||||
pwmShutdownPulsesForAllMotors(motorCount);
|
||||
}
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
static void airplaneMixer(void)
|
||||
{
|
||||
|
|
|
@ -100,10 +100,6 @@ typedef struct servoParam_t {
|
|||
int8_t forwardFromChannel; // RX channel index, 0 based. See CHANNEL_FORWARDING_DISABLED
|
||||
} servoParam_t;
|
||||
|
||||
struct gimbalConfig_s;
|
||||
struct escAndServoConfig_s;
|
||||
struct rxConfig_s;
|
||||
|
||||
extern int16_t servo[MAX_SUPPORTED_SERVOS];
|
||||
bool isMixerUsingServos(void);
|
||||
void writeServos(void);
|
||||
|
@ -113,21 +109,9 @@ void filterServos(void);
|
|||
extern int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
void mixerUseConfigs(
|
||||
#ifdef USE_SERVOS
|
||||
servoParam_t *servoConfToUse,
|
||||
struct gimbalConfig_s *gimbalConfigToUse,
|
||||
#endif
|
||||
flight3DConfig_t *flight3DConfigToUse,
|
||||
struct escAndServoConfig_s *escAndServoConfigToUse,
|
||||
mixerConfig_t *mixerConfigToUse,
|
||||
airplaneConfig_t *airplaneConfigToUse,
|
||||
struct rxConfig_s *rxConfigToUse);
|
||||
|
||||
void writeAllMotors(int16_t mc);
|
||||
void mixerLoadMix(int index, motorMixer_t *customMixers);
|
||||
void mixerResetMotors(void);
|
||||
void mixTable(void);
|
||||
void writeMotors(void);
|
||||
void stopMotors(void);
|
||||
void StopPwmAllMotors(void);
|
||||
|
|
|
@ -174,7 +174,7 @@ static void pidLuxFloat(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
}
|
||||
|
||||
gyroRate = gyroADC[axis] * gyro.scale; // gyro output scaled to dps
|
||||
gyroRate = gyroData[axis] * gyro.scale; // gyro output scaled to dps
|
||||
|
||||
// --------low-level gyro-based PID. ----------
|
||||
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
|
||||
|
@ -258,12 +258,12 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
if (!FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE) || axis == FD_YAW) { // MODE relying on GYRO or YAW axis
|
||||
error = (int32_t) rcCommand[axis] * 10 * 8 / pidProfile->P8[axis];
|
||||
error -= gyroADC[axis] / 4;
|
||||
error -= gyroData[axis] / 4;
|
||||
|
||||
PTermGYRO = rcCommand[axis];
|
||||
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp
|
||||
if ((ABS(gyroADC[axis]) > (640 * 4)) || (axis == FD_YAW && ABS(rcCommand[axis]) > 100))
|
||||
if ((ABS(gyroData[axis]) > (640 * 4)) || (axis == FD_YAW && ABS(rcCommand[axis]) > 100))
|
||||
errorGyroI[axis] = 0;
|
||||
|
||||
ITermGYRO = (errorGyroI[axis] / 125 * pidProfile->I8[axis]) / 64;
|
||||
|
@ -281,9 +281,9 @@ static void pidMultiWii(pidProfile_t *pidProfile, controlRateConfig_t *controlRa
|
|||
}
|
||||
}
|
||||
|
||||
PTerm -= ((int32_t)gyroADC[axis] / 4) * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation
|
||||
delta = (gyroADC[axis] - lastGyro[axis]) / 4;
|
||||
lastGyro[axis] = gyroADC[axis];
|
||||
PTerm -= ((int32_t)gyroData[axis] / 4) * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation
|
||||
delta = (gyroData[axis] - lastGyro[axis]) / 4;
|
||||
lastGyro[axis] = gyroData[axis];
|
||||
deltaSum = delta1[axis] + delta2[axis] + delta;
|
||||
delta2[axis] = delta1[axis];
|
||||
delta1[axis] = delta;
|
||||
|
@ -319,10 +319,10 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
|
||||
rc = rcCommand[axis] << 1;
|
||||
|
||||
error = rc - (gyroADC[axis] / 4);
|
||||
error = rc - (gyroData[axis] / 4);
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp 16 bits is ok here
|
||||
|
||||
if (ABS(gyroADC[axis]) > (640 * 4)) {
|
||||
if (ABS(gyroData[axis]) > (640 * 4)) {
|
||||
errorGyroI[axis] = 0;
|
||||
}
|
||||
|
||||
|
@ -359,10 +359,10 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
PTerm = PTermACC + ((PTerm - PTermACC) * prop >> 9);
|
||||
}
|
||||
|
||||
PTerm -= ((int32_t)(gyroADC[axis] / 4) * dynP8[axis]) >> 6; // 32 bits is needed for calculation
|
||||
PTerm -= ((int32_t)(gyroData[axis] / 4) * dynP8[axis]) >> 6; // 32 bits is needed for calculation
|
||||
|
||||
delta = (gyroADC[axis] - lastGyro[axis]) / 4; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
|
||||
lastGyro[axis] = gyroADC[axis];
|
||||
delta = (gyroData[axis] - lastGyro[axis]) / 4; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800
|
||||
lastGyro[axis] = gyroData[axis];
|
||||
DTerm = delta1[axis] + delta2[axis] + delta;
|
||||
delta2[axis] = delta1[axis];
|
||||
delta1[axis] = delta;
|
||||
|
@ -381,9 +381,9 @@ static void pidMultiWii23(pidProfile_t *pidProfile, controlRateConfig_t *control
|
|||
//YAW
|
||||
rc = (int32_t)rcCommand[FD_YAW] * (2 * controlRateConfig->rates[FD_YAW] + 30) >> 5;
|
||||
#ifdef ALIENWII32
|
||||
error = rc - gyroADC[FD_YAW];
|
||||
error = rc - gyroData[FD_YAW];
|
||||
#else
|
||||
error = rc - (gyroADC[FD_YAW] / 4);
|
||||
error = rc - (gyroData[FD_YAW] / 4);
|
||||
#endif
|
||||
errorGyroI[FD_YAW] += (int32_t)error * pidProfile->I8[FD_YAW];
|
||||
errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW], 2 - ((int32_t)1 << 28), -2 + ((int32_t)1 << 28));
|
||||
|
@ -450,12 +450,12 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con
|
|||
}
|
||||
if (!FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { // MODE relying on GYRO
|
||||
error = (int32_t) rcCommand[axis] * 10 * 8 / pidProfile->P8[axis];
|
||||
error -= gyroADC[axis] / 4;
|
||||
error -= gyroData[axis] / 4;
|
||||
|
||||
PTermGYRO = rcCommand[axis];
|
||||
|
||||
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp
|
||||
if (ABS(gyroADC[axis]) > (640 * 4))
|
||||
if (ABS(gyroData[axis]) > (640 * 4))
|
||||
errorGyroI[axis] = 0;
|
||||
|
||||
ITermGYRO = (errorGyroI[axis] / 125 * pidProfile->I8[axis]) / 64;
|
||||
|
@ -473,9 +473,9 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con
|
|||
}
|
||||
}
|
||||
|
||||
PTerm -= ((int32_t)gyroADC[axis] / 4) * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation
|
||||
delta = (gyroADC[axis] - lastGyro[axis]) / 4;
|
||||
lastGyro[axis] = gyroADC[axis];
|
||||
PTerm -= ((int32_t)gyroData[axis] / 4) * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation
|
||||
delta = (gyroData[axis] - lastGyro[axis]) / 4;
|
||||
lastGyro[axis] = gyroData[axis];
|
||||
deltaSum = delta1[axis] + delta2[axis] + delta;
|
||||
delta2[axis] = delta1[axis];
|
||||
delta1[axis] = delta;
|
||||
|
@ -491,9 +491,9 @@ static void pidMultiWiiHybrid(pidProfile_t *pidProfile, controlRateConfig_t *con
|
|||
//YAW
|
||||
rc = (int32_t)rcCommand[FD_YAW] * (2 * controlRateConfig->rates[FD_YAW] + 30) >> 5;
|
||||
#ifdef ALIENWII32
|
||||
error = rc - gyroADC[FD_YAW];
|
||||
error = rc - gyroData[FD_YAW];
|
||||
#else
|
||||
error = rc - (gyroADC[FD_YAW] / 4);
|
||||
error = rc - (gyroData[FD_YAW] / 4);
|
||||
#endif
|
||||
errorGyroI[FD_YAW] += (int32_t)error * pidProfile->I8[FD_YAW];
|
||||
errorGyroI[FD_YAW] = constrain(errorGyroI[FD_YAW], 2 - ((int32_t)1 << 28), -2 + ((int32_t)1 << 28));
|
||||
|
@ -523,7 +523,7 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
{
|
||||
UNUSED(rxConfig);
|
||||
|
||||
float delta, RCfactor, rcCommandAxis, MainDptCut, gyroADCQuant;
|
||||
float delta, RCfactor, rcCommandAxis, MainDptCut, gyroDataQuant;
|
||||
float PTerm, ITerm, DTerm, PTermACC = 0.0f, ITermACC = 0.0f, ITermGYRO, error, prop = 0.0f;
|
||||
static float lastGyro[2] = { 0.0f, 0.0f }, lastDTerm[2] = { 0.0f, 0.0f };
|
||||
uint8_t axis;
|
||||
|
@ -540,8 +540,8 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
}
|
||||
|
||||
for (axis = 0; axis < 2; axis++) {
|
||||
int32_t tmp = (int32_t)((float)gyroADC[axis] * 0.3125f); // Multiwii masks out the last 2 bits, this has the same idea
|
||||
gyroADCQuant = (float)tmp * 3.2f; // but delivers more accuracy and also reduces jittery flight
|
||||
int32_t tmp = (int32_t)((float)gyroData[axis] * 0.3125f); // Multiwii masks out the last 2 bits, this has the same idea
|
||||
gyroDataQuant = (float)tmp * 3.2f; // but delivers more accuracy and also reduces jittery flight
|
||||
rcCommandAxis = (float)rcCommand[axis]; // Calculate common values for pid controllers
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
||||
#ifdef GPS
|
||||
|
@ -563,10 +563,10 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
}
|
||||
|
||||
if (!FLIGHT_MODE(ANGLE_MODE)) {
|
||||
if (ABS((int16_t)gyroADC[axis]) > 2560) {
|
||||
if (ABS((int16_t)gyroData[axis]) > 2560) {
|
||||
errorGyroIf[axis] = 0.0f;
|
||||
} else {
|
||||
error = (rcCommandAxis * 320.0f / (float)pidProfile->P8[axis]) - gyroADCQuant;
|
||||
error = (rcCommandAxis * 320.0f / (float)pidProfile->P8[axis]) - gyroDataQuant;
|
||||
errorGyroIf[axis] = constrainf(errorGyroIf[axis] + error * ACCDeltaTimeINS, -192.0f, +192.0f);
|
||||
}
|
||||
|
||||
|
@ -584,10 +584,10 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
ITerm = ITermACC;
|
||||
}
|
||||
|
||||
PTerm -= gyroADCQuant * dynP8[axis] * 0.003f;
|
||||
delta = (gyroADCQuant - lastGyro[axis]) / ACCDeltaTimeINS;
|
||||
PTerm -= gyroDataQuant * dynP8[axis] * 0.003f;
|
||||
delta = (gyroDataQuant - lastGyro[axis]) / ACCDeltaTimeINS;
|
||||
|
||||
lastGyro[axis] = gyroADCQuant;
|
||||
lastGyro[axis] = gyroDataQuant;
|
||||
lastDTerm[axis] += RCfactor * (delta - lastDTerm[axis]);
|
||||
DTerm = lastDTerm[axis] * dynD8[axis] * 0.00007f;
|
||||
|
||||
|
@ -605,7 +605,7 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
|
||||
if (OLD_YAW) { // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw. hardcoded for now
|
||||
PTerm = ((int32_t)pidProfile->P8[FD_YAW] * (100 - (int32_t)controlRateConfig->rates[FD_YAW] * (int32_t)ABS(rcCommand[FD_YAW]) / 500)) / 100;
|
||||
int32_t tmp = lrintf(gyroADC[FD_YAW] * 0.25f);
|
||||
int32_t tmp = lrintf(gyroData[FD_YAW] * 0.25f);
|
||||
PTerm = rcCommand[FD_YAW] - tmp * PTerm / 80;
|
||||
if ((ABS(tmp) > 640) || (ABS(rcCommand[FD_YAW]) > 100)) {
|
||||
errorGyroI[FD_YAW] = 0;
|
||||
|
@ -616,7 +616,7 @@ rollAndPitchTrims_t *angleTrim, rxConfig_t *rxConfig)
|
|||
}
|
||||
} else {
|
||||
int32_t tmp = ((int32_t)rcCommand[FD_YAW] * (((int32_t)controlRateConfig->rates[FD_YAW] << 1) + 40)) >> 5;
|
||||
error = tmp - lrintf(gyroADC[FD_YAW] * 0.25f); // Less Gyrojitter works actually better
|
||||
error = tmp - lrintf(gyroData[FD_YAW] * 0.25f); // Less Gyrojitter works actually better
|
||||
|
||||
if (ABS(tmp) > 50) {
|
||||
errorGyroI[FD_YAW] = 0;
|
||||
|
@ -716,7 +716,7 @@ static void pidRewrite(pidProfile_t *pidProfile, controlRateConfig_t *controlRat
|
|||
// Used in stand-alone mode for ACRO, controlled by higher level regulators in other modes
|
||||
// -----calculate scaled error.AngleRates
|
||||
// multiplication of rcCommand corresponds to changing the sticks scaling here
|
||||
RateError = AngleRateTmp - (gyroADC[axis] / 4);
|
||||
RateError = AngleRateTmp - (gyroData[axis] / 4);
|
||||
|
||||
// -----calculate P component
|
||||
PTerm = (RateError * pidProfile->P8[axis] * PIDweight[axis] / 100) >> 7;
|
||||
|
|
|
@ -30,7 +30,6 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#ifdef GPS
|
||||
#include "io/gps.h"
|
||||
|
@ -39,7 +38,6 @@
|
|||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
|
||||
#include "io/beeper.h"
|
||||
|
||||
#if FLASH_SIZE > 64
|
||||
|
@ -77,7 +75,7 @@ static const uint8_t beep_disarmBeep[] = {
|
|||
};
|
||||
// beeps while stick held in disarm position (after pause)
|
||||
static const uint8_t beep_disarmRepeatBeep[] = {
|
||||
0, 100, 10, BEEPER_COMMAND_STOP
|
||||
0, 35, 40, 5, BEEPER_COMMAND_STOP
|
||||
};
|
||||
// Long beep and pause after that
|
||||
static const uint8_t beep_lowBatteryBeep[] = {
|
||||
|
@ -112,11 +110,6 @@ static const uint8_t beep_2shortBeeps[] = {
|
|||
static const uint8_t beep_2longerBeeps[] = {
|
||||
20, 15, 35, 5, BEEPER_COMMAND_STOP
|
||||
};
|
||||
// 3 beeps
|
||||
static const uint8_t beep_gyroCalibrated[] = {
|
||||
20, 10, 20, 10, 20, 10, BEEPER_COMMAND_STOP
|
||||
};
|
||||
|
||||
// array used for variable # of beeps (reporting GPS sat count, etc)
|
||||
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2];
|
||||
|
||||
|
@ -152,22 +145,21 @@ typedef struct beeperTableEntry_s {
|
|||
#endif
|
||||
|
||||
static const beeperTableEntry_t const beeperTable[] = {
|
||||
{ BEEPER_ENTRY(BEEPER_GYRO_CALIBRATED, 0, beep_gyroCalibrated, "GYRO_CALIBRATED") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 1, beep_sos, "RX_LOST_LANDING") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST, 2, beep_txLostBeep, "RX_LOST") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARMING, 3, beep_disarmBeep, "DISARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING, 4, beep_armingBeep, "ARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 5, beep_armedGpsFix, "ARMING_GPS_FIX") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 6, beep_critBatteryBeep, "BAT_CRIT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_LOW, 7, beep_lowBatteryBeep, "BAT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_GPS_STATUS, 8, beep_multiBeeps, NULL) },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_SET, 9, beep_shortBeep, "RX_SET") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST_LANDING, 0, beep_sos, "RX_LOST_LANDING") },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_LOST, 1, beep_txLostBeep, "RX_LOST") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARMING, 2, beep_disarmBeep, "DISARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING, 3, beep_armingBeep, "ARMING") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMING_GPS_FIX, 4, beep_armedGpsFix, "ARMING_GPS_FIX") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_CRIT_LOW, 5, beep_critBatteryBeep, "BAT_CRIT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_BAT_LOW, 6, beep_lowBatteryBeep, "BAT_LOW") },
|
||||
{ BEEPER_ENTRY(BEEPER_GPS_STATUS, 7, beep_multiBeeps, NULL) },
|
||||
{ BEEPER_ENTRY(BEEPER_RX_SET, 8, beep_shortBeep, "RX_SET") },
|
||||
{ BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 9, beep_disarmRepeatBeep, "DISARM_REPEAT") },
|
||||
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION, 10, beep_2shortBeeps, "ACC_CALIBRATION") },
|
||||
{ BEEPER_ENTRY(BEEPER_ACC_CALIBRATION_FAIL, 11, beep_2longerBeeps, "ACC_CALIBRATION_FAIL") },
|
||||
{ BEEPER_ENTRY(BEEPER_READY_BEEP, 12, beep_readyBeep, "READY_BEEP") },
|
||||
{ BEEPER_ENTRY(BEEPER_MULTI_BEEPS, 13, beep_multiBeeps, NULL) }, // FIXME having this listed makes no sense since the beep array will not be initialised.
|
||||
{ BEEPER_ENTRY(BEEPER_DISARM_REPEAT, 14, beep_disarmRepeatBeep, "DISARM_REPEAT") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMED, 15, beep_armedBeep, "ARMED") },
|
||||
{ BEEPER_ENTRY(BEEPER_ARMED, 14, beep_armedBeep, "ARMED") },
|
||||
};
|
||||
|
||||
static const beeperTableEntry_t *currentBeeperEntry = NULL;
|
||||
|
@ -217,10 +209,6 @@ void beeper(beeperMode_e mode)
|
|||
void beeperSilence(void)
|
||||
{
|
||||
BEEP_OFF;
|
||||
warningLedDisable();
|
||||
warningLedRefresh();
|
||||
|
||||
|
||||
beeperIsOn = 0;
|
||||
|
||||
beeperNextToggleTime = 0;
|
||||
|
@ -303,9 +291,7 @@ void beeperUpdate(void)
|
|||
beeperIsOn = 1;
|
||||
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
||||
BEEP_ON;
|
||||
warningLedEnable();
|
||||
warningLedRefresh();
|
||||
// if this was arming beep then mark time (for blackbox)
|
||||
//if this was arming beep then mark time (for blackbox)
|
||||
if (
|
||||
beeperPos == 0
|
||||
&& (currentBeeperEntry->mode == BEEPER_ARMING || currentBeeperEntry->mode == BEEPER_ARMING_GPS_FIX)
|
||||
|
@ -317,8 +303,6 @@ void beeperUpdate(void)
|
|||
beeperIsOn = 0;
|
||||
if (currentBeeperEntry->sequence[beeperPos] != 0) {
|
||||
BEEP_OFF;
|
||||
warningLedDisable();
|
||||
warningLedRefresh();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -364,7 +348,7 @@ beeperMode_e beeperModeForTableIndex(int idx)
|
|||
*/
|
||||
const char *beeperNameForTableIndex(int idx)
|
||||
{
|
||||
#ifndef BEEPER_NAMES
|
||||
#ifndef BEEPER_NAME
|
||||
UNUSED(idx);
|
||||
return NULL;
|
||||
#else
|
||||
|
|
|
@ -21,7 +21,6 @@ typedef enum {
|
|||
// IMPORTANT: these are in priority order, 0 = Highest
|
||||
BEEPER_SILENCE = 0, // Silence, see beeperSilence()
|
||||
|
||||
BEEPER_GYRO_CALIBRATED,
|
||||
BEEPER_RX_LOST_LANDING, // Beeps SOS when armed and TX is turned off or signal lost (autolanding/autodisarm)
|
||||
BEEPER_RX_LOST, // Beeps when TX is turned off or signal lost (repeat until TX is okay)
|
||||
BEEPER_DISARMING, // Beep when disarming the board
|
||||
|
|
|
@ -83,7 +83,7 @@ static char lineBuffer[SCREEN_CHARACTER_COLUMN_COUNT + 1];
|
|||
#define HALF_SCREEN_CHARACTER_COLUMN_COUNT (SCREEN_CHARACTER_COLUMN_COUNT / 2)
|
||||
#define IS_SCREEN_CHARACTER_COLUMN_COUNT_ODD (SCREEN_CHARACTER_COLUMN_COUNT & 1)
|
||||
|
||||
static const char* const pageTitles[] = {
|
||||
const char* pageTitles[] = {
|
||||
"CLEANFLIGHT",
|
||||
"ARMED",
|
||||
"BATTERY",
|
||||
|
|
|
@ -140,23 +140,23 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
|
|||
return;
|
||||
}
|
||||
|
||||
if (isUsingSticksToArm) {
|
||||
// Disarm on throttle down + yaw
|
||||
if (isUsingSticksToArm) {
|
||||
// Disarm on throttle down + yaw
|
||||
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE) {
|
||||
if (ARMING_FLAG(ARMED))
|
||||
if (ARMING_FLAG(ARMED)) //board was armed
|
||||
mwDisarm();
|
||||
else {
|
||||
beeper(BEEPER_DISARM_REPEAT); // sound tone while stick held
|
||||
rcDelayCommand = 0; // reset so disarm tone will repeat
|
||||
else { //board was not armed
|
||||
beeper(BEEPER_DISARM_REPEAT); //sound tone while stick held
|
||||
rcDelayCommand = 0; //reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
// Disarm on roll (only when retarded_arm is enabled)
|
||||
if (retarded_arm && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO)) {
|
||||
if (ARMING_FLAG(ARMED))
|
||||
if (ARMING_FLAG(ARMED)) //board was armed
|
||||
mwDisarm();
|
||||
else {
|
||||
beeper(BEEPER_DISARM_REPEAT); // sound tone while stick held
|
||||
rcDelayCommand = 0; // reset so disarm tone will repeat
|
||||
else { //board was not armed
|
||||
beeper(BEEPER_DISARM_REPEAT); //sound tone while stick held
|
||||
rcDelayCommand = 0; //reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -84,7 +84,12 @@ typedef enum {
|
|||
#define THR_CE (3 << (2 * THROTTLE))
|
||||
#define THR_HI (2 << (2 * THROTTLE))
|
||||
|
||||
#define MAX_MODE_ACTIVATION_CONDITION_COUNT 20
|
||||
#define MAX_MODE_ACTIVATION_CONDITION_COUNT 40
|
||||
// 40 is enough for 1 mode for each position of 11 * 3 position switches and a 6 pos switch.
|
||||
// however, that is unlikely because you don't define the 'off' positions, so for a 3 position
|
||||
// switch it's normal that only 2 values would be configured.
|
||||
// this leaves plenty of 'slots' free for cases where you enable multiple modes for a switch
|
||||
// position (like gps rth + horizon + baro + beeper)
|
||||
|
||||
#define CHANNEL_RANGE_MIN 900
|
||||
#define CHANNEL_RANGE_MAX 2100
|
||||
|
|
|
@ -53,7 +53,7 @@
|
|||
static serialConfig_t *serialConfig;
|
||||
static serialPortUsage_t serialPortUsageList[SERIAL_PORT_COUNT];
|
||||
|
||||
const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
||||
serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
||||
#ifdef USE_VCP
|
||||
SERIAL_PORT_USB_VCP,
|
||||
#endif
|
||||
|
@ -74,9 +74,7 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
|
|||
#endif
|
||||
};
|
||||
|
||||
static uint8_t serialPortCount;
|
||||
|
||||
const uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000}; // see baudRate_e
|
||||
uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000}; // see baudRate_e
|
||||
|
||||
#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))
|
||||
|
||||
|
@ -89,7 +87,7 @@ baudRate_e lookupBaudRateIndex(uint32_t baudRate)
|
|||
return index;
|
||||
}
|
||||
}
|
||||
return BAUD_AUTO;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier)
|
||||
|
@ -228,22 +226,16 @@ bool isSerialConfigValid(serialConfig_t *serialConfigToCheck)
|
|||
return true;
|
||||
}
|
||||
|
||||
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier)
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
|
||||
{
|
||||
uint8_t index;
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
serialPortConfig_t *candidate = &serialConfig->portConfigs[index];
|
||||
if (candidate->identifier == identifier) {
|
||||
return candidate;
|
||||
if (candidate->identifier == identifier && candidate->functionMask) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e identifier)
|
||||
{
|
||||
serialPortConfig_t *candidate = serialFindPortConfiguration(identifier);
|
||||
return candidate != NULL && candidate->functionMask;
|
||||
return false;
|
||||
}
|
||||
|
||||
serialPort_t *openSerialPort(
|
||||
|
@ -254,13 +246,6 @@ serialPort_t *openSerialPort(
|
|||
portMode_t mode,
|
||||
portOptions_t options)
|
||||
{
|
||||
#if (!defined(USE_VCP) && !defined(USE_USART1) && !defined(USE_USART2) && !defined(USE_USART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1))
|
||||
UNUSED(callback);
|
||||
UNUSED(baudRate);
|
||||
UNUSED(mode);
|
||||
UNUSED(options);
|
||||
#endif
|
||||
|
||||
serialPortUsage_t *serialPortUsage = findSerialPortUsageByIdentifier(identifier);
|
||||
if (!serialPortUsage || serialPortUsage->function != FUNCTION_NONE) {
|
||||
// not available / already in use
|
||||
|
@ -339,7 +324,6 @@ void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled)
|
|||
|
||||
serialConfig = initialSerialConfig;
|
||||
|
||||
serialPortCount = SERIAL_PORT_COUNT;
|
||||
memset(&serialPortUsageList, 0, sizeof(serialPortUsageList));
|
||||
|
||||
for (index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
|
@ -355,37 +339,11 @@ void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled)
|
|||
#endif
|
||||
) {
|
||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||
serialPortCount--;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void serialRemovePort(serialPortIdentifier_e identifier)
|
||||
{
|
||||
for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
if (serialPortUsageList[index].identifier == identifier) {
|
||||
serialPortUsageList[index].identifier = SERIAL_PORT_NONE;
|
||||
serialPortCount--;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t serialGetAvailablePortCount(void)
|
||||
{
|
||||
return serialPortCount;
|
||||
}
|
||||
|
||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier)
|
||||
{
|
||||
for (uint8_t index = 0; index < SERIAL_PORT_COUNT; index++) {
|
||||
if (serialPortUsageList[index].identifier == identifier) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void handleSerial(void)
|
||||
{
|
||||
#ifdef USE_CLI
|
||||
|
|
|
@ -46,7 +46,7 @@ typedef enum {
|
|||
BAUD_250000,
|
||||
} baudRate_e;
|
||||
|
||||
extern const uint32_t baudRates[];
|
||||
extern uint32_t baudRates[];
|
||||
|
||||
// serial port identifiers are now fixed, these values are used by MSP commands.
|
||||
typedef enum {
|
||||
|
@ -61,7 +61,7 @@ typedef enum {
|
|||
SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
|
||||
} serialPortIdentifier_e;
|
||||
|
||||
extern const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
|
||||
extern serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT];
|
||||
|
||||
//
|
||||
// runtime
|
||||
|
@ -96,11 +96,7 @@ typedef struct serialConfig_s {
|
|||
//
|
||||
// configuration
|
||||
//
|
||||
void serialRemovePort(serialPortIdentifier_e identifier);
|
||||
uint8_t serialGetAvailablePortCount(void);
|
||||
bool serialIsPortAvailable(serialPortIdentifier_e identifier);
|
||||
bool isSerialConfigValid(serialConfig_t *serialConfig);
|
||||
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e identifier);
|
||||
bool doesConfigurationUsePort(serialPortIdentifier_e portIdentifier);
|
||||
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
|
||||
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
|
||||
|
@ -127,7 +123,6 @@ void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort);
|
|||
|
||||
baudRate_e lookupBaudRateIndex(uint32_t baudRate);
|
||||
|
||||
|
||||
//
|
||||
// msp/cli/bootloader
|
||||
//
|
||||
|
|
|
@ -109,7 +109,6 @@ static void cliProfile(char *cmdline);
|
|||
static void cliRateProfile(char *cmdline);
|
||||
static void cliReboot(void);
|
||||
static void cliSave(char *cmdline);
|
||||
static void cliSerial(char *cmdline);
|
||||
static void cliServo(char *cmdline);
|
||||
static void cliSet(char *cmdline);
|
||||
static void cliGet(char *cmdline);
|
||||
|
@ -221,7 +220,6 @@ const clicmd_t cmdTable[] = {
|
|||
{ "profile", "index (0 to 2)", cliProfile },
|
||||
{ "rateprofile", "index (0 to 2)", cliRateProfile },
|
||||
{ "save", "save and reboot", cliSave },
|
||||
{ "serial", "show/set serial settings", cliSerial },
|
||||
#ifdef USE_SERVOS
|
||||
{ "servo", "servo config", cliServo },
|
||||
#endif
|
||||
|
@ -289,6 +287,40 @@ const clivalue_t valueTable[] = {
|
|||
|
||||
{ "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, -1, 1 },
|
||||
|
||||
{ "serial_port_1_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_1_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].msp_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_1_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 },
|
||||
{ "serial_port_1_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_1_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[0].gps_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 2)
|
||||
{ "serial_port_2_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_2_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].msp_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_2_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 },
|
||||
{ "serial_port_2_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_2_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[1].gps_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 3)
|
||||
{ "serial_port_3_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].functionMask, 0, 0xFFFF},
|
||||
{ "serial_port_3_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].msp_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_3_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 },
|
||||
{ "serial_port_3_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_3_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[2].gps_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 4)
|
||||
{ "serial_port_4_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_4_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].msp_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_4_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 },
|
||||
{ "serial_port_4_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_4_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[3].gps_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
#if (SERIAL_PORT_COUNT >= 5)
|
||||
{ "serial_port_5_functions", VAR_UINT16 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].functionMask, 0, 0xFFFF },
|
||||
{ "serial_port_5_msp_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].msp_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_5_telemetry_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].telemetry_baudrateIndex, BAUD_AUTO, BAUD_115200 },
|
||||
{ "serial_port_5_blackbox_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].blackbox_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
{ "serial_port_5_gps_baudrate", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.portConfigs[4].gps_baudrateIndex, BAUD_9600, BAUD_115200 },
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
|
||||
{ "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, 48, 126 },
|
||||
|
||||
#ifdef GPS
|
||||
|
@ -559,102 +591,6 @@ static void cliAux(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
static void cliSerial(char *cmdline)
|
||||
{
|
||||
int i, val;
|
||||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
|
||||
continue;
|
||||
};
|
||||
printf("serial %d %d %ld %ld %ld %ld\r\n" ,
|
||||
masterConfig.serialConfig.portConfigs[i].identifier,
|
||||
masterConfig.serialConfig.portConfigs[i].functionMask,
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
|
||||
baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
|
||||
);
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
serialPortConfig_t portConfig;
|
||||
memset(&portConfig, 0 , sizeof(portConfig));
|
||||
|
||||
serialPortConfig_t *currentConfig;
|
||||
|
||||
uint8_t validArgumentCount = 0;
|
||||
|
||||
ptr = cmdline;
|
||||
|
||||
val = atoi(ptr++);
|
||||
currentConfig = serialFindPortConfiguration(val);
|
||||
if (currentConfig) {
|
||||
portConfig.identifier = val;
|
||||
validArgumentCount++;
|
||||
}
|
||||
|
||||
ptr = strchr(ptr, ' ');
|
||||
if (ptr) {
|
||||
val = atoi(++ptr);
|
||||
portConfig.functionMask = val & 0xFFFF;
|
||||
validArgumentCount++;
|
||||
}
|
||||
|
||||
for (i = 0; i < 4; i ++) {
|
||||
ptr = strchr(ptr, ' ');
|
||||
if (!ptr) {
|
||||
break;
|
||||
}
|
||||
|
||||
val = atoi(++ptr);
|
||||
|
||||
uint8_t baudRateIndex = lookupBaudRateIndex(val);
|
||||
if (baudRates[baudRateIndex] != (uint32_t) val) {
|
||||
break;
|
||||
}
|
||||
|
||||
switch(i) {
|
||||
case 0:
|
||||
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
|
||||
continue;
|
||||
}
|
||||
portConfig.msp_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
case 1:
|
||||
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
|
||||
continue;
|
||||
}
|
||||
portConfig.gps_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
case 2:
|
||||
if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
|
||||
continue;
|
||||
}
|
||||
portConfig.telemetry_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
case 3:
|
||||
if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
|
||||
continue;
|
||||
}
|
||||
portConfig.blackbox_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
}
|
||||
|
||||
validArgumentCount++;
|
||||
}
|
||||
|
||||
if (validArgumentCount < 6) {
|
||||
cliPrint("Parse error\r\n");
|
||||
return;
|
||||
}
|
||||
|
||||
memcpy(currentConfig, &portConfig, sizeof(portConfig));
|
||||
|
||||
}
|
||||
|
||||
static void cliAdjustmentRange(char *cmdline)
|
||||
{
|
||||
|
@ -1130,9 +1066,6 @@ static void cliDump(char *cmdline)
|
|||
buf[i] = '\0';
|
||||
printf("map %s\r\n", buf);
|
||||
|
||||
cliPrint("\r\n\r\n# serial\r\n");
|
||||
cliSerial("");
|
||||
|
||||
#ifdef LED_STRIP
|
||||
cliPrint("\r\n\r\n# led\r\n");
|
||||
cliLed("");
|
||||
|
@ -1363,13 +1296,14 @@ static void cliMotor(char *cmdline)
|
|||
int motor_value = 0;
|
||||
int index = 0;
|
||||
char *pch = NULL;
|
||||
char *saveptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
cliPrint("Usage:\r\nmotor index [value] - show [or set] motor value\r\n");
|
||||
return;
|
||||
}
|
||||
|
||||
pch = strtok(cmdline, " ");
|
||||
pch = strtok_r(cmdline, " ", &saveptr);
|
||||
while (pch != NULL) {
|
||||
switch (index) {
|
||||
case 0:
|
||||
|
@ -1380,7 +1314,7 @@ static void cliMotor(char *cmdline)
|
|||
break;
|
||||
}
|
||||
index++;
|
||||
pch = strtok(NULL, " ");
|
||||
pch = strtok_r(NULL, " ", &saveptr);
|
||||
}
|
||||
|
||||
if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
|
||||
|
@ -1477,7 +1411,6 @@ static void cliReboot(void) {
|
|||
cliPrint("\r\nRebooting");
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
|
||||
|
|
|
@ -140,12 +140,12 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
|||
#define BASEFLIGHT_IDENTIFIER "BAFL";
|
||||
|
||||
#define FLIGHT_CONTROLLER_IDENTIFIER_LENGTH 4
|
||||
static const char * const flightControllerIdentifier = CLEANFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
|
||||
static const char *flightControllerIdentifier = CLEANFLIGHT_IDENTIFIER; // 4 UPPER CASE alpha numeric characters that identify the flight controller.
|
||||
|
||||
#define FLIGHT_CONTROLLER_VERSION_LENGTH 3
|
||||
#define FLIGHT_CONTROLLER_VERSION_MASK 0xFFF
|
||||
|
||||
static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||
const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||
#define BOARD_IDENTIFIER_LENGTH 4 // 4 UPPER CASE alpha numeric characters that identify the board being used.
|
||||
#define BOARD_HARDWARE_REVISION_LENGTH 2
|
||||
|
||||
|
@ -396,24 +396,40 @@ static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
|
|||
|
||||
static mspPort_t *currentPort;
|
||||
|
||||
static void serialize32(uint32_t a)
|
||||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
serialWrite(mspSerialPort, t);
|
||||
currentPort->checksum ^= t;
|
||||
t = a >> 8;
|
||||
serialWrite(mspSerialPort, t);
|
||||
currentPort->checksum ^= t;
|
||||
t = a >> 16;
|
||||
serialWrite(mspSerialPort, t);
|
||||
currentPort->checksum ^= t;
|
||||
t = a >> 24;
|
||||
serialWrite(mspSerialPort, t);
|
||||
currentPort->checksum ^= t;
|
||||
}
|
||||
|
||||
static void serialize16(int16_t a)
|
||||
{
|
||||
static uint8_t t;
|
||||
t = a;
|
||||
serialWrite(mspSerialPort, t);
|
||||
currentPort->checksum ^= t;
|
||||
t = a >> 8 & 0xff;
|
||||
serialWrite(mspSerialPort, t);
|
||||
currentPort->checksum ^= t;
|
||||
}
|
||||
|
||||
static void serialize8(uint8_t a)
|
||||
{
|
||||
serialWrite(mspSerialPort, a);
|
||||
currentPort->checksum ^= a;
|
||||
}
|
||||
|
||||
static void serialize16(uint16_t a)
|
||||
{
|
||||
serialize8((uint8_t)(a >> 0));
|
||||
serialize8((uint8_t)(a >> 8));
|
||||
}
|
||||
|
||||
static void serialize32(uint32_t a)
|
||||
{
|
||||
serialize16((uint16_t)(a >> 0));
|
||||
serialize16((uint16_t)(a >> 16));
|
||||
}
|
||||
|
||||
static uint8_t read8(void)
|
||||
{
|
||||
return currentPort->inBuf[currentPort->indRX++] & 0xff;
|
||||
|
@ -666,7 +682,7 @@ void mspInit(serialConfig_t *serialConfig)
|
|||
|
||||
activeBoxIds[activeBoxIdCount++] = BOXOSD;
|
||||
|
||||
if (feature(FEATURE_TELEMETRY) && masterConfig.telemetryConfig.telemetry_switch)
|
||||
if (feature(FEATURE_TELEMETRY && masterConfig.telemetryConfig.telemetry_switch))
|
||||
activeBoxIds[activeBoxIdCount++] = BOXTELEMETRY;
|
||||
|
||||
#ifdef AUTOTUNE
|
||||
|
@ -817,7 +833,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
serialize16(accSmooth[i]);
|
||||
}
|
||||
for (i = 0; i < 3; i++)
|
||||
serialize16(gyroADC[i]);
|
||||
serialize16(gyroData[i]);
|
||||
for (i = 0; i < 3; i++)
|
||||
serialize16(magADC[i]);
|
||||
break;
|
||||
|
@ -1167,12 +1183,9 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
|
||||
case MSP_CF_SERIAL_CONFIG:
|
||||
headSerialReply(
|
||||
((sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4)) * serialGetAvailablePortCount())
|
||||
((sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4)) * SERIAL_PORT_COUNT)
|
||||
);
|
||||
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
|
||||
continue;
|
||||
};
|
||||
serialize8(masterConfig.serialConfig.portConfigs[i].identifier);
|
||||
serialize16(masterConfig.serialConfig.portConfigs[i].functionMask);
|
||||
serialize8(masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex);
|
||||
|
@ -1582,28 +1595,17 @@ static bool processInCommand(void)
|
|||
{
|
||||
uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4);
|
||||
|
||||
if (currentPort->dataSize % portConfigSize != 0) {
|
||||
if ((SERIAL_PORT_COUNT * portConfigSize) != currentPort->dataSize) {
|
||||
headSerialError(0);
|
||||
break;
|
||||
}
|
||||
|
||||
uint8_t remainingPortsInPacket = currentPort->dataSize / portConfigSize;
|
||||
|
||||
while (remainingPortsInPacket--) {
|
||||
uint8_t identifier = read8();
|
||||
|
||||
serialPortConfig_t *portConfig = serialFindPortConfiguration(identifier);
|
||||
if (!portConfig) {
|
||||
headSerialError(0);
|
||||
break;
|
||||
}
|
||||
|
||||
portConfig->identifier = identifier;
|
||||
portConfig->functionMask = read16();
|
||||
portConfig->msp_baudrateIndex = read8();
|
||||
portConfig->gps_baudrateIndex = read8();
|
||||
portConfig->telemetry_baudrateIndex = read8();
|
||||
portConfig->blackbox_baudrateIndex = read8();
|
||||
for (i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
masterConfig.serialConfig.portConfigs[i].identifier = read8();
|
||||
masterConfig.serialConfig.portConfigs[i].functionMask = read16();
|
||||
masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex = read8();
|
||||
masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex = read8();
|
||||
masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex = read8();
|
||||
masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex = read8();
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -1748,7 +1750,6 @@ void mspProcess(void)
|
|||
delay(50);
|
||||
}
|
||||
stopMotors();
|
||||
handleOneshotFeatureChangeOnRestart();
|
||||
systemReset();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -27,63 +27,44 @@
|
|||
|
||||
#include "statusindicator.h"
|
||||
|
||||
void blinkLedAndSoundBeeper(uint8_t num, uint8_t wait, uint8_t repeat)
|
||||
{
|
||||
uint8_t i, r;
|
||||
|
||||
for (r = 0; r < repeat; r++) {
|
||||
for (i = 0; i < num; i++) {
|
||||
LED0_TOGGLE; // switch LEDPIN state
|
||||
BEEP_ON;
|
||||
delay(wait);
|
||||
BEEP_OFF;
|
||||
}
|
||||
delay(60);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
static uint32_t warningLedTimer = 0;
|
||||
|
||||
typedef enum {
|
||||
WARNING_LED_OFF = 0,
|
||||
WARNING_LED_ON,
|
||||
WARNING_LED_FLASH
|
||||
} warningLedState_e;
|
||||
|
||||
static warningLedState_e warningLedState = WARNING_LED_OFF;
|
||||
|
||||
void warningLedResetTimer(void) {
|
||||
uint32_t now = millis();
|
||||
warningLedTimer = now + 500000;
|
||||
}
|
||||
|
||||
void warningLedEnable(void)
|
||||
void enableWarningLed(uint32_t currentTime)
|
||||
{
|
||||
warningLedState = WARNING_LED_ON;
|
||||
}
|
||||
|
||||
void warningLedDisable(void)
|
||||
{
|
||||
warningLedState = WARNING_LED_OFF;
|
||||
}
|
||||
|
||||
void warningLedFlash(void)
|
||||
{
|
||||
warningLedState = WARNING_LED_FLASH;
|
||||
}
|
||||
|
||||
void warningLedRefresh(void)
|
||||
{
|
||||
switch (warningLedState) {
|
||||
case WARNING_LED_OFF:
|
||||
LED0_OFF;
|
||||
break;
|
||||
case WARNING_LED_ON:
|
||||
LED0_ON;
|
||||
break;
|
||||
case WARNING_LED_FLASH:
|
||||
LED0_TOGGLE;
|
||||
break;
|
||||
if (warningLedTimer != 0) {
|
||||
return; // already enabled
|
||||
}
|
||||
|
||||
uint32_t now = micros();
|
||||
warningLedTimer = now + 500000;
|
||||
warningLedTimer = currentTime + 500000;
|
||||
LED0_ON;
|
||||
}
|
||||
|
||||
void warningLedUpdate(void)
|
||||
void disableWarningLed(void)
|
||||
{
|
||||
uint32_t now = micros();
|
||||
|
||||
if ((int32_t)(now - warningLedTimer) < 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
warningLedRefresh();
|
||||
warningLedTimer = 0;
|
||||
LED0_OFF;
|
||||
}
|
||||
|
||||
void updateWarningLed(uint32_t currentTime)
|
||||
{
|
||||
if (warningLedTimer && (int32_t)(currentTime - warningLedTimer) >= 0) {
|
||||
LED0_TOGGLE;
|
||||
warningLedTimer = warningLedTimer + 500000;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -17,8 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
void warningLedEnable(void);
|
||||
void warningLedDisable(void);
|
||||
void warningLedRefresh(void);
|
||||
void warningLedUpdate(void);
|
||||
void warningLedFlash(void);
|
||||
void blinkLedAndSoundBeeper(uint8_t num, uint8_t wait, uint8_t repeat);
|
||||
|
||||
void enableWarningLed(uint32_t currentTime);
|
||||
void disableWarningLed(void);
|
||||
void updateWarningLed(uint32_t currentTime);
|
||||
|
|
|
@ -47,7 +47,6 @@
|
|||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/inverter.h"
|
||||
#include "drivers/flash_m25p16.h"
|
||||
#include "drivers/sonar_hcsr04.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
@ -91,7 +90,6 @@
|
|||
#include "debug.h"
|
||||
|
||||
extern uint32_t previousTime;
|
||||
extern uint8_t motorControlEnable;
|
||||
|
||||
#ifdef SOFTSERIAL_LOOPBACK
|
||||
serialPort_t *loopbackPort;
|
||||
|
@ -116,8 +114,6 @@ void displayInit(rxConfig_t *intialRxConfig);
|
|||
void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse);
|
||||
void loop(void);
|
||||
void spektrumBind(rxConfig_t *rxConfig);
|
||||
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
|
||||
void sonarInit(const sonarHardware_t *sonarHardware);
|
||||
|
||||
#ifdef STM32F303xC
|
||||
// from system_stm32f30x.c
|
||||
|
@ -172,9 +168,6 @@ void init(void)
|
|||
|
||||
systemInit();
|
||||
|
||||
// Latch active features to be used for feature() in the remainder of init().
|
||||
latchActiveFeatures();
|
||||
|
||||
ledInit();
|
||||
|
||||
#ifdef SPEKTRUM_BIND
|
||||
|
@ -200,21 +193,6 @@ void init(void)
|
|||
mixerInit(masterConfig.mixerMode, masterConfig.customMixer);
|
||||
|
||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||
|
||||
#ifdef SONAR
|
||||
const sonarHardware_t *sonarHardware = NULL;
|
||||
|
||||
if (feature(FEATURE_SONAR)) {
|
||||
sonarHardware = sonarGetHardwareConfiguration(&masterConfig.batteryConfig);
|
||||
sonarGPIOConfig_t sonarGPIOConfig = {
|
||||
.echoPin = sonarHardware->trigger_pin,
|
||||
.triggerPin = sonarHardware->echo_pin,
|
||||
.gpio = SONAR_GPIO
|
||||
};
|
||||
pwm_params.sonarGPIOConfig = &sonarGPIOConfig;
|
||||
}
|
||||
#endif
|
||||
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
if (masterConfig.mixerMode == MIXER_AIRPLANE || masterConfig.mixerMode == MIXER_FLYING_WING)
|
||||
pwm_params.airplane = true;
|
||||
|
@ -260,9 +238,6 @@ void init(void)
|
|||
|
||||
mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
|
||||
|
||||
if (!feature(FEATURE_ONESHOT125))
|
||||
motorControlEnable = true;
|
||||
|
||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||
|
||||
#ifdef BEEPER
|
||||
|
@ -303,22 +278,10 @@ void init(void)
|
|||
updateHardwareRevision();
|
||||
#endif
|
||||
|
||||
#if defined(NAZE)
|
||||
if (hardwareRevision == NAZE32_SP) {
|
||||
serialRemovePort(SERIAL_PORT_SOFTSERIAL2);
|
||||
} else {
|
||||
serialRemovePort(SERIAL_PORT_USART3);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C
|
||||
#if defined(NAZE)
|
||||
if (hardwareRevision != NAZE32_SP) {
|
||||
i2cInit(I2C_DEVICE);
|
||||
} else {
|
||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||
i2cInit(I2C_DEVICE);
|
||||
}
|
||||
}
|
||||
#elif defined(CC3D)
|
||||
if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
|
||||
|
@ -408,7 +371,7 @@ void init(void)
|
|||
|
||||
#ifdef SONAR
|
||||
if (feature(FEATURE_SONAR)) {
|
||||
sonarInit(sonarHardware);
|
||||
sonarInit(&masterConfig.batteryConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -488,10 +451,6 @@ void init(void)
|
|||
LED2_ON;
|
||||
#endif
|
||||
|
||||
// Latch active features AGAIN since some may be modified by init().
|
||||
latchActiveFeatures();
|
||||
motorControlEnable = true;
|
||||
|
||||
systemState |= SYSTEM_STATE_READY;
|
||||
}
|
||||
|
||||
|
|
|
@ -97,8 +97,6 @@ uint16_t cycleTime = 0; // this is the number in micro second to achieve
|
|||
int16_t magHold;
|
||||
int16_t headFreeModeHold;
|
||||
|
||||
uint8_t motorControlEnable = false;
|
||||
|
||||
int16_t telemTemperature1; // gyro sensor temperature
|
||||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||
|
||||
|
@ -276,6 +274,11 @@ void annexCode(void)
|
|||
ENABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
if (isCalibrating()) {
|
||||
LED0_TOGGLE;
|
||||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
if (!STATE(SMALL_ANGLE)) {
|
||||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
@ -284,18 +287,13 @@ void annexCode(void)
|
|||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
}
|
||||
|
||||
if (isCalibrating()) {
|
||||
warningLedFlash();
|
||||
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||
disableWarningLed();
|
||||
} else {
|
||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||
warningLedDisable();
|
||||
} else {
|
||||
warningLedFlash();
|
||||
}
|
||||
enableWarningLed(currentTime);
|
||||
}
|
||||
|
||||
warningLedUpdate();
|
||||
updateWarningLed(currentTime);
|
||||
}
|
||||
|
||||
#ifdef TELEMETRY
|
||||
|
@ -388,7 +386,7 @@ void mwArm(void)
|
|||
}
|
||||
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
beeperConfirmationBeeps(1);
|
||||
blinkLedAndSoundBeeper(2, 255, 1);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -730,7 +728,7 @@ void loop(void)
|
|||
if (masterConfig.looptime == 0 || (int32_t)(currentTime - loopTime) >= 0) {
|
||||
loopTime = currentTime + masterConfig.looptime;
|
||||
|
||||
imuUpdate(¤tProfile->accelerometerTrims);
|
||||
imuUpdate(¤tProfile->accelerometerTrims, masterConfig.mixerMode);
|
||||
|
||||
// Measure loop rate just after reading the sensors
|
||||
currentTime = micros();
|
||||
|
@ -803,9 +801,7 @@ void loop(void)
|
|||
writeServos();
|
||||
#endif
|
||||
|
||||
if (motorControlEnable) {
|
||||
writeMotors();
|
||||
}
|
||||
writeMotors();
|
||||
|
||||
#ifdef BLACKBOX
|
||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||
|
|
|
@ -154,5 +154,5 @@ uint8_t calculateBatteryCapacityRemainingPercentage(void)
|
|||
{
|
||||
uint16_t batteryCapacity = batteryConfig->batteryCapacity;
|
||||
|
||||
return constrain((batteryCapacity - constrain(mAhDrawn, 0, 0xFFFF)) * 100.0 / batteryCapacity , 0, 100);
|
||||
return constrain((batteryCapacity - constrain(mAhDrawn, 0, 0xFFFF)) * 100.0f / batteryCapacity , 0, 100);
|
||||
}
|
||||
|
|
|
@ -26,7 +26,6 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "io/beeper.h"
|
||||
#include "io/statusindicator.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
||||
|
@ -96,14 +95,10 @@ static void performAcclerationCalibration(uint8_t gyroMovementCalibrationThresho
|
|||
return;
|
||||
}
|
||||
gyroZero[axis] = (g[axis] + (CALIBRATING_GYRO_CYCLES / 2)) / CALIBRATING_GYRO_CYCLES;
|
||||
blinkLedAndSoundBeeper(10, 15, 1);
|
||||
}
|
||||
}
|
||||
|
||||
if (isOnFinalGyroCalibrationCycle()) {
|
||||
beeper(BEEPER_GYRO_CALIBRATED);
|
||||
}
|
||||
calibratingG--;
|
||||
|
||||
}
|
||||
|
||||
static void applyGyroZero(void)
|
||||
|
|
|
@ -122,8 +122,8 @@ const mpu6050Config_t *selectMPU6050Config(void)
|
|||
|
||||
#ifdef USE_FAKE_GYRO
|
||||
static void fakeGyroInit(void) {}
|
||||
static void fakeGyroRead(int16_t *gyroADC) {
|
||||
memset(gyroADC, 0, sizeof(int16_t[XYZ_AXIS_COUNT]));
|
||||
static void fakeGyroRead(int16_t *gyroData) {
|
||||
memset(gyroData, 0, sizeof(int16_t[XYZ_AXIS_COUNT]));
|
||||
}
|
||||
static void fakeGyroReadTemp(int16_t *tempData) {
|
||||
UNUSED(tempData);
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
|
||||
static int32_t calculatedAltitude;
|
||||
|
||||
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig)
|
||||
void sonarInit(batteryConfig_t *batteryConfig)
|
||||
{
|
||||
#if defined(NAZE) || defined(EUSTM32F103RC) || defined(PORT103R)
|
||||
static const sonarHardware_t const sonarPWM56 = {
|
||||
|
@ -57,9 +57,9 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
|
|||
};
|
||||
// If we are using parallel PWM for our receiver or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8
|
||||
if (feature(FEATURE_RX_PARALLEL_PWM ) || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC) ) {
|
||||
return &sonarPWM56;
|
||||
hcsr04_init(&sonarPWM56);
|
||||
} else {
|
||||
return &sonarRC78;
|
||||
hcsr04_init(&sonarRC78);
|
||||
}
|
||||
#elif defined(OLIMEXINO)
|
||||
UNUSED(batteryConfig);
|
||||
|
@ -70,17 +70,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
|
|||
.exti_pin_source = GPIO_PinSource1,
|
||||
.exti_irqn = EXTI1_IRQn
|
||||
};
|
||||
return &sonarHardware;
|
||||
#elif defined(CC3D)
|
||||
UNUSED(batteryConfig);
|
||||
static const sonarHardware_t const sonarHardware = {
|
||||
.trigger_pin = Pin_5, // (PB5)
|
||||
.echo_pin = Pin_0, // (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
||||
.exti_line = EXTI_Line0,
|
||||
.exti_pin_source = GPIO_PinSource0,
|
||||
.exti_irqn = EXTI0_IRQn
|
||||
};
|
||||
return &sonarHardware;
|
||||
hcsr04_init(&sonarHardware);
|
||||
#elif defined(SPRACINGF3)
|
||||
UNUSED(batteryConfig);
|
||||
static const sonarHardware_t const sonarHardware = {
|
||||
|
@ -90,15 +80,11 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
|
|||
.exti_pin_source = EXTI_PinSource1,
|
||||
.exti_irqn = EXTI1_IRQn
|
||||
};
|
||||
return &sonarHardware;
|
||||
hcsr04_init(&sonarHardware);
|
||||
#else
|
||||
#error Sonar not defined for target
|
||||
#endif
|
||||
}
|
||||
|
||||
void sonarInit(const sonarHardware_t *sonarHardware)
|
||||
{
|
||||
hcsr04_init(sonarHardware);
|
||||
sensorsSet(SENSOR_SONAR);
|
||||
calculatedAltitude = -1;
|
||||
}
|
||||
|
|
|
@ -18,9 +18,9 @@
|
|||
#pragma once
|
||||
#include "sensors/battery.h"
|
||||
|
||||
void sonarInit(batteryConfig_t *batteryConfig);
|
||||
void sonarUpdate(void);
|
||||
|
||||
int32_t sonarRead(void);
|
||||
int32_t sonarCalculateAltitude(int32_t sonarAlt, int16_t tiltAngle);
|
||||
int32_t sonarGetLatestAltitude(void);
|
||||
|
||||
|
|
|
@ -111,18 +111,14 @@
|
|||
#define BLACKBOX
|
||||
#define TELEMETRY
|
||||
#define SERIAL_RX
|
||||
#define SONAR
|
||||
#define AUTOTUNE
|
||||
#define USE_SERVOS
|
||||
#define USE_CLI
|
||||
|
||||
#if defined(OPBL)
|
||||
// disabled some features for OPBL build due to code size.
|
||||
#undef AUTOTUNE
|
||||
#undef SONAR
|
||||
#undef AUTOTUNE // disabled for OPBL build due to code size.
|
||||
#endif
|
||||
|
||||
|
||||
#define SPEKTRUM_BIND
|
||||
// USART3, PB11 (Flexport)
|
||||
#define BIND_PORT GPIOB
|
||||
|
|
|
@ -119,10 +119,9 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_USART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 5
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define SOFTSERIAL_1_TIMER TIM3
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||
|
@ -131,13 +130,6 @@
|
|||
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
||||
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||
|
||||
// USART3 only on NAZE32_SP - Flex Port
|
||||
#define USART3_RX_PIN Pin_11
|
||||
#define USART3_TX_PIN Pin_10
|
||||
#define USART3_GPIO GPIOB
|
||||
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
|
||||
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
|
|
|
@ -230,7 +230,7 @@ static void sendSatalliteSignalQualityAsTemperature2(void)
|
|||
if (telemetryConfig->frsky_unit == FRSKY_UNIT_METRICS) {
|
||||
serialize16(satellite);
|
||||
} else {
|
||||
float tmp = (satellite - 32) / 1.8;
|
||||
float tmp = (satellite - 32) / 1.8f;
|
||||
//Round the value
|
||||
tmp += (tmp < 0) ? -0.5f : 0.5f;
|
||||
serialize16(tmp);
|
||||
|
|
|
@ -15,7 +15,7 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
const char * const targetName = __TARGET__;
|
||||
const char * const shortGitRevision = __REVISION__;
|
||||
const char * const buildDate = __DATE__;
|
||||
const char * const buildTime = __TIME__;
|
||||
char *targetName = __TARGET__;
|
||||
char *shortGitRevision = __REVISION__;
|
||||
char *buildDate = __DATE__;
|
||||
char *buildTime = __TIME__;
|
||||
|
|
|
@ -25,13 +25,13 @@
|
|||
|
||||
#define MW_VERSION 231
|
||||
|
||||
extern const char* const targetName;
|
||||
extern char* targetName;
|
||||
|
||||
#define GIT_SHORT_REVISION_LENGTH 7 // lower case hexadecimal digits.
|
||||
extern const char* const shortGitRevision;
|
||||
extern char* shortGitRevision;
|
||||
|
||||
#define BUILD_DATE_LENGTH 11
|
||||
extern const char* const buildDate; // "MMM DD YYYY" MMM = Jan/Feb/...
|
||||
extern char* buildDate; // "MMM DD YYYY" MMM = Jan/Feb/...
|
||||
|
||||
#define BUILD_TIME_LENGTH 8
|
||||
extern const char* const buildTime; // "HH:MM:SS"
|
||||
extern char* buildTime; // "HH:MM:SS"
|
||||
|
|
|
@ -26,8 +26,8 @@ OBJECT_DIR = ../../obj/test
|
|||
COMMON_FLAGS = \
|
||||
-g \
|
||||
-Wall \
|
||||
-pthread \
|
||||
-Wextra \
|
||||
-pthread \
|
||||
-ggdb3 \
|
||||
-O0 \
|
||||
-DUNIT_TEST \
|
||||
|
@ -39,7 +39,7 @@ C_FLAGS = $(COMMON_FLAGS) \
|
|||
|
||||
# Flags passed to the C++ compiler.
|
||||
CXX_FLAGS = $(COMMON_FLAGS) \
|
||||
-std=gnu++11
|
||||
-std=gnu++98
|
||||
|
||||
# All tests produced by this Makefile. Remember to add new tests you
|
||||
# created to the list.
|
||||
|
@ -83,7 +83,7 @@ GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/inc/gtest/*.h $(GTEST_HEADERS)
|
|||
# compiles fast and for ordinary users its source rarely changes.
|
||||
$(OBJECT_DIR)/gtest-all.o : $(GTEST_SRCS_)
|
||||
@mkdir -p $(dir $@)
|
||||
$(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -Wno-missing-field-initializers -Wno-unused-const-variable -c \
|
||||
$(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest-all.cc -o $@
|
||||
|
||||
$(OBJECT_DIR)/gtest_main.o : $(GTEST_SRCS_)
|
||||
|
@ -134,7 +134,7 @@ battery_unittest : \
|
|||
$(OBJECT_DIR)/battery_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/common/encoding.o : $(USER_DIR)/common/encoding.c $(USER_DIR)/common/encoding.h $(GTEST_HEADERS)
|
||||
@mkdir -p $(dir $@)
|
||||
|
@ -153,7 +153,7 @@ encoding_unittest : \
|
|||
$(OBJECT_DIR)/encoding_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/flight/imu.o : \
|
||||
$(USER_DIR)/flight/imu.c \
|
||||
|
@ -178,7 +178,7 @@ flight_imu_unittest : \
|
|||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/maths_unittest.o : \
|
||||
$(TEST_DIR)/maths_unittest.cc \
|
||||
|
@ -192,7 +192,7 @@ maths_unittest : \
|
|||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
|
@ -217,7 +217,7 @@ altitude_hold_unittest : \
|
|||
$(OBJECT_DIR)/altitude_hold_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/gps_conversion.o : \
|
||||
|
@ -241,7 +241,7 @@ gps_conversion_unittest : \
|
|||
$(OBJECT_DIR)/gps_conversion_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
|
@ -267,7 +267,7 @@ telemetry_hott_unittest : \
|
|||
$(OBJECT_DIR)/flight/gps_conversion.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
|
@ -293,7 +293,7 @@ rc_controls_unittest : \
|
|||
$(OBJECT_DIR)/rc_controls_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/io/ledstrip.o : \
|
||||
|
@ -317,7 +317,7 @@ ledstrip_unittest : \
|
|||
$(OBJECT_DIR)/ledstrip_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
|
||||
|
@ -342,7 +342,7 @@ ws2811_unittest : \
|
|||
$(OBJECT_DIR)/ws2811_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
|
||||
$(OBJECT_DIR)/flight/lowpass.o : \
|
||||
|
@ -366,7 +366,7 @@ lowpass_unittest : \
|
|||
$(OBJECT_DIR)/lowpass_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/flight/mixer.o : \
|
||||
$(USER_DIR)/flight/mixer.c \
|
||||
|
@ -390,7 +390,7 @@ flight_mixer_unittest : \
|
|||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/flight/failsafe.o : \
|
||||
$(USER_DIR)/flight/failsafe.c \
|
||||
|
@ -414,7 +414,7 @@ flight_failsafe_unittest : \
|
|||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/io/serial.o : \
|
||||
$(USER_DIR)/io/serial.c \
|
||||
|
@ -437,7 +437,7 @@ io_serial_unittest : \
|
|||
$(OBJECT_DIR)/io_serial_unittest.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
$(OBJECT_DIR)/rx/rx.o : \
|
||||
$(USER_DIR)/rx/rx.c \
|
||||
|
@ -461,7 +461,7 @@ rx_rx_unittest : \
|
|||
$(OBJECT_DIR)/common/maths.o \
|
||||
$(OBJECT_DIR)/gtest_main.a
|
||||
|
||||
$(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@
|
||||
$(CXX) $(CXX_FLAGS) -lpthread $^ -o $(OBJECT_DIR)/$@
|
||||
|
||||
test: $(TESTS)
|
||||
set -e && for test in $(TESTS) ; do \
|
||||
|
|
|
@ -48,6 +48,18 @@ extern "C" {
|
|||
extern uint8_t servoCount;
|
||||
void forwardAuxChannelsToServos(void);
|
||||
|
||||
void mixerUseConfigs(
|
||||
#ifdef USE_SERVOS
|
||||
servoParam_t *servoConfToUse,
|
||||
gimbalConfig_t *gimbalConfigToUse,
|
||||
#endif
|
||||
flight3DConfig_t *flight3DConfigToUse,
|
||||
escAndServoConfig_t *escAndServoConfigToUse,
|
||||
mixerConfig_t *mixerConfigToUse,
|
||||
airplaneConfig_t *airplaneConfigToUse,
|
||||
rxConfig_t *rxConfigToUse
|
||||
);
|
||||
|
||||
void mixerInit(mixerMode_e mixerMode, motorMixer_t *initialCustomMixers);
|
||||
void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfiguration);
|
||||
}
|
||||
|
@ -303,15 +315,6 @@ void pwmWriteMotor(uint8_t index, uint16_t value) {
|
|||
motors[index].value = value;
|
||||
}
|
||||
|
||||
void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
||||
{
|
||||
uint8_t index;
|
||||
|
||||
for(index = 0; index < motorCount; index++){
|
||||
motors[index].value = 0;
|
||||
}
|
||||
}
|
||||
|
||||
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) {
|
||||
lastOneShotUpdateMotorCount = motorCount;
|
||||
}
|
||||
|
|
|
@ -48,18 +48,13 @@ extern "C" {
|
|||
extern void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfig, pidProfile_t *pidProfile);
|
||||
}
|
||||
|
||||
class RcControlsModesTest : public ::testing::Test {
|
||||
protected:
|
||||
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
||||
|
||||
virtual void SetUp() {
|
||||
memset(&modeActivationConditions, 0, sizeof(modeActivationConditions));
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(RcControlsModesTest, updateActivatedModesWithAllInputsAtMidde)
|
||||
TEST(RcControlsTest, updateActivatedModesWithAllInputsAtMidde)
|
||||
{
|
||||
// given
|
||||
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
||||
memset(&modeActivationConditions, 0, sizeof(modeActivationConditions));
|
||||
|
||||
// and
|
||||
rcModeActivationMask = 0;
|
||||
|
||||
// and
|
||||
|
@ -84,9 +79,12 @@ TEST_F(RcControlsModesTest, updateActivatedModesWithAllInputsAtMidde)
|
|||
}
|
||||
}
|
||||
|
||||
TEST_F(RcControlsModesTest, updateActivatedModesUsingValidAuxConfigurationAndRXValues)
|
||||
TEST(RcControlsTest, updateActivatedModesUsingValidAuxConfigurationAndRXValues)
|
||||
{
|
||||
// given
|
||||
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
||||
memset(&modeActivationConditions, 0, sizeof(modeActivationConditions));
|
||||
|
||||
modeActivationConditions[0].modeId = (boxId_e)0;
|
||||
modeActivationConditions[0].auxChannelIndex = AUX1 - NON_AUX_CHANNEL_COUNT;
|
||||
modeActivationConditions[0].range.startStep = CHANNEL_VALUE_TO_STEP(1700);
|
||||
|
@ -234,33 +232,27 @@ static const adjustmentConfig_t rateAdjustmentConfig = {
|
|||
.data = { { 1 } }
|
||||
};
|
||||
|
||||
class RcControlsAdjustmentsTest : public ::testing::Test {
|
||||
protected:
|
||||
TEST(RcControlsTest, processRcAdjustmentsSticksInMiddle)
|
||||
{
|
||||
// given
|
||||
controlRateConfig_t controlRateConfig = {
|
||||
.rcRate8 = 90,
|
||||
.rcExpo8 = 0,
|
||||
.thrMid8 = 0,
|
||||
.thrExpo8 = 0,
|
||||
.rates = {0, 0, 0},
|
||||
.rates = {0,0,0},
|
||||
.dynThrPID = 0,
|
||||
.rcYawExpo8 = 0,
|
||||
.tpa_breakpoint = 0
|
||||
};
|
||||
|
||||
virtual void SetUp() {
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
// and
|
||||
memset(&rxConfig, 0, sizeof (rxConfig));
|
||||
rxConfig.mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
|
||||
memset(&rxConfig, 0, sizeof (rxConfig));
|
||||
rxConfig.mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
}
|
||||
};
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
|
||||
{
|
||||
// given
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
configureAdjustment(0, AUX3 - NON_AUX_CHANNEL_COUNT, &rateAdjustmentConfig);
|
||||
|
||||
// and
|
||||
|
@ -283,9 +275,28 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
|
|||
EXPECT_EQ(adjustmentStateMask, 0);
|
||||
}
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp)
|
||||
TEST(RcControlsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp)
|
||||
{
|
||||
// given
|
||||
controlRateConfig_t controlRateConfig = {
|
||||
.rcRate8 = 90,
|
||||
.rcExpo8 = 0,
|
||||
.thrMid8 = 0,
|
||||
.thrExpo8 = 0,
|
||||
.rates = {0,0,0},
|
||||
.dynThrPID = 0,
|
||||
.tpa_breakpoint = 0
|
||||
};
|
||||
|
||||
// and
|
||||
memset(&rxConfig, 0, sizeof (rxConfig));
|
||||
rxConfig.mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
|
||||
// and
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
configureAdjustment(0, AUX3 - NON_AUX_CHANNEL_COUNT, &rateAdjustmentConfig);
|
||||
|
||||
// and
|
||||
|
@ -430,9 +441,28 @@ static const adjustmentConfig_t rateProfileAdjustmentConfig = {
|
|||
.data = { { 3 } }
|
||||
};
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processRcRateProfileAdjustments)
|
||||
TEST(RcControlsTest, processRcRateProfileAdjustments)
|
||||
{
|
||||
// given
|
||||
controlRateConfig_t controlRateConfig = {
|
||||
.rcRate8 = 90,
|
||||
.rcExpo8 = 0,
|
||||
.thrMid8 = 0,
|
||||
.thrExpo8 = 0,
|
||||
.rates = {0,0,0},
|
||||
.dynThrPID = 0,
|
||||
.tpa_breakpoint = 0
|
||||
};
|
||||
|
||||
// and
|
||||
memset(&rxConfig, 0, sizeof (rxConfig));
|
||||
rxConfig.mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
|
||||
int adjustmentIndex = 3;
|
||||
configureAdjustment(adjustmentIndex, AUX4 - NON_AUX_CHANNEL_COUNT, &rateProfileAdjustmentConfig);
|
||||
|
||||
|
@ -498,7 +528,7 @@ static const adjustmentConfig_t pidYawDAdjustmentConfig = {
|
|||
.data = { { 1 } }
|
||||
};
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
||||
TEST(RcControlsTest, processPIDIncreasePidController0)
|
||||
{
|
||||
// given
|
||||
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
||||
|
@ -524,6 +554,15 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
controlRateConfig_t controlRateConfig;
|
||||
memset(&controlRateConfig, 0, sizeof (controlRateConfig));
|
||||
|
||||
// and
|
||||
memset(&rxConfig, 0, sizeof (rxConfig));
|
||||
rxConfig.mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
|
||||
configureAdjustment(0, AUX1 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollPAdjustmentConfig);
|
||||
configureAdjustment(1, AUX2 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollIAdjustmentConfig);
|
||||
configureAdjustment(2, AUX3 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollDAdjustmentConfig);
|
||||
|
@ -575,7 +614,7 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
EXPECT_EQ(28, pidProfile.D8[YAW]);
|
||||
}
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController2)
|
||||
TEST(RcControlsTest, processPIDIncreasePidController2)
|
||||
{
|
||||
// given
|
||||
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
||||
|
@ -601,6 +640,15 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController2)
|
|||
controlRateConfig_t controlRateConfig;
|
||||
memset(&controlRateConfig, 0, sizeof (controlRateConfig));
|
||||
|
||||
// and
|
||||
memset(&rxConfig, 0, sizeof (rxConfig));
|
||||
rxConfig.mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
|
||||
configureAdjustment(0, AUX1 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollPAdjustmentConfig);
|
||||
configureAdjustment(1, AUX2 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollIAdjustmentConfig);
|
||||
configureAdjustment(2, AUX3 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollDAdjustmentConfig);
|
||||
|
|
Loading…
Reference in a new issue