mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-12 19:10:27 +03:00
Naze and all it traces removed
This commit is contained in:
parent
3c4668c7ee
commit
bf3d4ac3d0
42 changed files with 42 additions and 633 deletions
|
@ -34,7 +34,6 @@ doc_files=(
|
|||
'Board - CJMCU.md'
|
||||
'Board - ColibriRace.md'
|
||||
'Board - Motolab.md'
|
||||
'Board - Naze32.md'
|
||||
'Board - Olimexino.md'
|
||||
'Board - Paris Air Hero 32.md'
|
||||
'Board - Sparky.md'
|
||||
|
|
|
@ -8,12 +8,10 @@ This is the option you need to select for the bootloader:
|
|||
|
||||

|
||||
|
||||
Currently supported on the SPRACINGF3, STM32F3DISCOVERY, NAZE32 (including clones such as the FLIP32) and CC3D.
|
||||
Currently supported on the SPRACINGF3, STM32F3DISCOVERY and CC3D.
|
||||
|
||||
## Wiring
|
||||
|
||||
- For the NAZE, no external wiring is necessary. Simply plug in the board via USB cable.
|
||||
|
||||
- For the CC3D, connect [a USB to UART adapter](http://bit.ly/cf-cp2102) to the flex port.
|
||||
|
||||
- Ensure MSP is enabled on the flex port. Unfortunatly the main port cannot be used in the current configuration due to the inverter on this port.
|
||||
|
|
|
@ -24,12 +24,6 @@ incorrect voltage or reversed polarity will likely fry your flight controller. E
|
|||
has a voltage divider capable of measuring your particular battery voltage.
|
||||
On the first battery connection is always advisable to use a current limiter device to limit damages if something is wrong in the setup.
|
||||
|
||||
### Naze32
|
||||
|
||||
The Naze32 has an on-board battery divider circuit; just connect your main battery to the VBAT connector.
|
||||
|
||||
**CAUTION:** When installing the connection from main battery to the VBAT connector, be sure to first disconnect the main battery from the frame/power distribution board. Check the wiring very carefully before connecting battery again. Incorrect connections can immediately and completely destroy the flight controller and connected peripherals (ESC, GPS, Receiver etc.).
|
||||
|
||||
### CC3D
|
||||
|
||||
The CC3D has no battery divider. To use voltage monitoring, you must create a divider that gives a 3.3v
|
||||
|
|
|
@ -98,8 +98,7 @@ save.
|
|||
You need to let INAV know which of [your serial ports][] you connect your OpenLog to (i.e. the Blackbox port),
|
||||
which you can do on the Configurator's Ports tab.
|
||||
|
||||
You should use a hardware serial port (such as UART1 on the Naze32, the two-pin Tx/Rx header in the center of the
|
||||
board). SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
|
||||
You should use a hardware serial port. SoftSerial ports can be used for the Blackbox. However, because they are limited to 19200 baud, your logging
|
||||
rate will need to be severely reduced to compensate. Therefore the use of SoftSerial is not recommended.
|
||||
|
||||
When using a hardware serial port, Blackbox should be set to at least 115200 baud on that port. When using fast
|
||||
|
@ -114,24 +113,7 @@ Connect the "TX" pin of the serial port you've chosen to the OpenLog's "RXI" pin
|
|||
pin to the OpenLog, as this will cause the OpenLog to interfere with any shared functions on the serial port while
|
||||
disarmed.
|
||||
|
||||
#### Naze32 serial port choices
|
||||
|
||||
On the Naze32, the TX/RX pins on top of the board are connected to UART1, and are shared with the USB connector.
|
||||
Therefore, MSP must be enabled on UART1 in order to use the Configurator over USB. If Blackbox is connected to the pins
|
||||
on top of the Naze32, the Configurator will stop working once the board is armed. This configuration is usually a good
|
||||
choice if you don't already have an OSD installed which is using those pins while armed, and aren't using the FrSky
|
||||
telemetry pins.
|
||||
|
||||
Pin RC3 on the side of the board is UART2's Tx pin. If Blackbox is configured on UART2, MSP can still be used on UART1
|
||||
when the board is armed, which means that the Configurator will continue to work simultaneously with Blackbox logging.
|
||||
Note that in `PARALLEL_PWM` mode this leaves the board with 6 input channels as RC3 and RC4 pins are used by UART2 as Tx and Rx. INAV automatically shifts logical channel mapping for you when UART2 is enabled in `Ports` tab so you'll have to shift receiver pins that are connected to Naze32 pins 3 to 6 by two.
|
||||
|
||||
The OpenLog tolerates a power supply of between 3.3V and 12V. If you are powering your Naze32 with a standard 5V BEC,
|
||||
then you can use a spare motor header's +5V and GND pins to power the OpenLog with.
|
||||
|
||||
#### Other flight controller hardware
|
||||
Boards other than the Naze32 may have more accessible hardware serial devices, in which case refer to their
|
||||
documentation to decide how to wire up the logger. The key criteria are:
|
||||
The key criteria to choose a serial port are:
|
||||
|
||||
* Should be a hardware serial port rather than SoftSerial.
|
||||
* Cannot be shared with any other function (GPS, telemetry) except MSP.
|
||||
|
@ -173,11 +155,7 @@ tubing instead.
|
|||
Some flight controllers have an onboard SPI NOR dataflash chip which can be used to store flight logs instead of using
|
||||
an OpenLog.
|
||||
|
||||
The full version of the Naze32 and the CC3D have an onboard "m25p16" 2 megabyte dataflash storage chip. This is a small
|
||||
chip with 8 fat legs, which can be found at the base of the Naze32's direction arrow. This chip is not present on the
|
||||
"Acro" version of the Naze32.
|
||||
|
||||
The SPRacingF3 has a larger 8 megabyte dataflash chip onboard which allows for longer recording times.
|
||||
The SPRacingF3 has a 8 megabyte dataflash chip onboard which allows for longer recording times.
|
||||
|
||||
These chips are also supported:
|
||||
|
||||
|
|
|
@ -21,7 +21,6 @@ https://micro-motor-warehouse.com
|
|||
|
||||
Here are the general hardware specifications for this boards:
|
||||
|
||||
- STM32F103CBT6 MCU (ALIENFLIGHTF1)
|
||||
- STM32F303CCT6 MCU (ALIENFLIGHTF3)
|
||||
- STM32F405RGT6 MCU (ALIENFLIGHTF4)
|
||||
- STM32F711RET6 MCU (ALIENFLIGHTNGF7)
|
||||
|
@ -59,8 +58,6 @@ For more detail of the different bind modes please refer the CleanFlight Spektru
|
|||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
|
||||
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
|
||||
|
||||
The AlienFlight firmware will be built as target ALIENFLIGHTF1, ALIENFLIGHTF3, ALIENFLIGHTF4 or ALIENFLIGHTNGF7. The firmware image will come with alternative default settings which will give the user a plug and play experience. There is no computer needed to get this into the air with a small Quadcopter. A preconfigured custom mixer for an Octocopter is part of the default settings to allow clean straight wiring with the AlienFlight. The mixer can be activated with "mixer custom" in the CLI. To use the AlienFlight controller in a Hexa- or Octocopter or to do some more tuning additional configuration changes can be done as usual in the CLI or the BetaFlight configurator.
|
||||
|
|
|
@ -7,8 +7,7 @@ and 6 ports labeled as motor/servo outputs (3 pins each).
|
|||
|
||||
If issues are found with this board please report via the [github issue tracker](https://github.com/iNavFlight/inav/issues).
|
||||
|
||||
The board has a USB port directly connected to the processor. Other boards like the Naze and Flip32
|
||||
have an on-board USB to uart adapter which connect to the processor's serial port instead.
|
||||
The board has a USB port directly connected to the processor.
|
||||
|
||||
The board cannot currently be used for hexacopters/octocopters.
|
||||
|
||||
|
|
|
@ -1,68 +0,0 @@
|
|||
# Board - Naze32
|
||||
|
||||
The Naze32 target supports all Naze hardware revisions. Revision 4 and 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/iNavFlight/inav/issues).
|
||||
|
||||
## 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 | |
|
||||
|
||||
* 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
|
||||
|
||||
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
|
||||
|
||||
| Pin | Identifier | Function | Notes |
|
||||
| --- | ---------- | --------------------------- | -------------------------------- |
|
||||
| 1 | | Ground | |
|
||||
| 2 | Circle | +5V | |
|
||||
| 3 | 1 | RX_PPM | Enable `feature RX_PPM` |
|
||||
| 4 | 2 | RSSI_ADC | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
|
||||
| 5 | 3 | USART2 TX | |
|
||||
| 6 | 4 | USART2 RX | |
|
||||
| 7 | 5 | LED_STRIP | Enable `feature LED_STRIP` |
|
||||
| 8 | 6 | unused | |
|
||||
| 9 | 7 | HC-SR04 Trigger | |
|
||||
| 10 | 8 | HC-SR04 Echo / CURRENT | Enable `feature CURRENT_METER` Connect to the output of a current sensor, 0v-3.3v input |
|
||||
|
||||
When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but two SoftSerial ports are made available to use instead.
|
||||
|
||||
| Pin | Identifier | Function | Notes |
|
||||
| --- | ---------- | -------------- | -------------------------------- |
|
||||
| 7 | 5 | SOFTSERIAL1 RX | Enable `feature SOFTSERIAL` |
|
||||
| 8 | 6 | SOFTSERIAL1 TX | |
|
||||
| 9 | 7 | SOFTSERIAL2 RX | |
|
||||
| 10 | 8 | SOFTSERIAL2 TX | |
|
||||
|
||||
## Recovery
|
||||
|
||||
### 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
|
||||
|
||||
### INAV configurator
|
||||
+ Select the correct hardware and the desired release of the INAV firmware
|
||||
+ Put a check in the "No reboot sequence"
|
||||
+ Flash firmware
|
||||
|
||||
```
|
||||
/-------------------\
|
||||
|O O|
|
||||
| []5V |
|
||||
| [][]Boot |
|
||||
| |
|
||||
| |
|
||||
| |
|
||||
| |
|
||||
|O O|
|
||||
\-------[USB]-------/
|
||||
```
|
|
@ -1,4 +1,4 @@
|
|||
# Board - Paris Air Hero 32 / Acro Naze 32 Mini
|
||||
# Board - Paris Air Hero 32
|
||||
|
||||
This is the AIR3 PARIS Sirius AirHERO 32 F3 board from MultiWiiCopter
|
||||
Source: http://www.multiwiicopter.com/products/inav-air3-fixed-wing
|
||||
|
|
|
@ -1,6 +1,4 @@
|
|||
# Board - Paris Air Hero 32 / Acro Naze 32 Mini
|
||||
|
||||
This board uses the same firmware as the Naze32 board.
|
||||
# Board - Paris Air Hero 32
|
||||
|
||||
## Sensors
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@ The DoDo board is a clone of the SPRacingF3 board in terms of CPU pin mappings.
|
|||
Hardware differences compared to SPRacingF3 are as follows:
|
||||
|
||||
* Rev 1 and Rev 2: the CPU is the cheaper version of the F3 with only 128KB FLASH. Rev 3: the CPU is a F3 version with 256KB FLASH.
|
||||
* The external flash rom is the same size as found on the Naze32 (2MBit)
|
||||
* 2MBit flash size
|
||||
* The barometer is the cheaper BMP280.
|
||||
* It does not have any compass sensor.
|
||||
* Onboard BEC.
|
||||
|
|
|
@ -172,7 +172,7 @@ Flashing INAV will erase the TauLabs bootloader, this is not a problem and can e
|
|||
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input |
|
||||
| 4 | USART3 | RX / PB11 | TX / PB10 | RX/TX is on one end of the 6-pin header about the PWM outputs. |
|
||||
|
||||
USB VCP *can* be used at the same time as other serial ports (unlike Naze32).
|
||||
USB VCP *can* be used at the same time as other serial port.
|
||||
|
||||
All USART ports all support automatic hardware inversion which allows direct connection of serial rx receivers like the FrSky X4RSB - no external inverter needed.
|
||||
|
||||
|
|
|
@ -49,6 +49,5 @@ These boards will work with INAV but are either end-of-life, limited on features
|
|||
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
|
||||
| PARIS Sirius™ AIR HERO | F1 | AIRHERO3 | NMEA | HMC5883 | MS5611, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | SERIAL |
|
||||
| OpenPilot CC3D | F1 | CC3D, CC3D_PPM1 | NMEA | HMC5883 | BMP085, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | no |
|
||||
| AfroFlight NAZE32 | F1 | NAZE | NMEA | HMC5883 | MS5611, BMP280 | LTM | PWM, PPM, SBUS, IBUS, SPEKTRUM | SERIAL, SPIFLASH |
|
||||
| RMRC Seriously DODO | F3 | RMDO | All | All | All | All | All | SERIAL |
|
||||
| ANYFC | F4 | ANYFC | All | All | All | All | All | SERIAL |
|
||||
|
|
|
@ -61,11 +61,6 @@ Examples of a known-working buzzers.
|
|||
|
||||
## Connections
|
||||
|
||||
### Naze32
|
||||
|
||||
Connect a supported buzzer directly to the BUZZ pins. Observe polarity. Also if you are working with flight controller outside of a craft, on a bench for example, you need to supply 5 volts and ground to one of the ESC connections or the buzzer will not function.
|
||||
|
||||
|
||||
### CC3D
|
||||
|
||||
Buzzer support on the CC3D requires that a buzzer circuit be created to which the input is PA15.
|
||||
|
|
|
@ -72,6 +72,4 @@ More can be read about this procedure here: http://www.multiwii.com/forum/viewto
|
|||
|
||||
## Connections
|
||||
|
||||
Connect +5v, Ground, I2C SDA and I2C SCL from the flight controller to the display.
|
||||
|
||||
On Naze32 rev 5 boards the SDA and SCL pads are underneath the board.
|
||||
Connect +5v, Ground, I2C SDA and I2C SCL from the flight controller to the display.
|
|
@ -50,13 +50,11 @@ from another BEC. Just ensure that the GROUND is the same for all BEC outputs a
|
|||
|
||||
| Target | Pin | LED Strip | Signal |
|
||||
| --------------------- | ---- | --------- | -------|
|
||||
| Naze/Olimexino | RC5 | Data In | PA6 |
|
||||
| CC3D | RCO5 | Data In | PB4 |
|
||||
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
|
||||
| Sparky | PWM5 | Data In | PA6 |
|
||||
|
||||
Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time.
|
||||
Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips
|
||||
Additionally, since RC5 is also used for Parallel PWM RC input on both the Chebuzz and STM32F3Discovery targets, led strips
|
||||
can not be used at the same time at Parallel PWM.
|
||||
|
||||
If you have LEDs that are intermittent, flicker or show the wrong colors then drop the VIN to less than 4.7v, e.g. by using an inline
|
||||
|
|
|
@ -15,8 +15,6 @@ BLHeli rev13.0 also supports Oneshot125 and will be automatically selected by th
|
|||
|
||||
## Supported Boards
|
||||
|
||||
The Naze boards are supported, and have been flight tested in a number of configurations.
|
||||
|
||||
CC3D boards have been tested with a PPM receiver, however parallel PWM receivers might not work properly with this board.
|
||||
|
||||
## Enabling Oneshot
|
||||
|
|
|
@ -233,7 +233,7 @@ The highest channel value considered valid. e.g. PWM/PPM pulse length
|
|||
|
||||
See the Serial chapter for some some RX configuration examples.
|
||||
|
||||
To setup spectrum on the Naze32 or clones in the GUI:
|
||||
To setup spectrum in the GUI:
|
||||
1. Start on the "Ports" tab make sure that UART2 has serial RX. If not set the checkbox, save and reboot.
|
||||
2. Move to the "Configuration" page and in the upper lefthand corner choose Serial RX as the receiver type.
|
||||
3. Below that choose the type of serial receiver that you are using. Save and reboot.
|
||||
|
|
|
@ -16,7 +16,7 @@ a dedicated USB to UART adapter. VCP does not 'use' a physical UART port.
|
|||
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 ports are sometimes exposed via on-board USB to UART converters, such as the CP2102 as found on the Naze and Flip32 boards.
|
||||
UART ports are sometimes exposed via on-board USB to UART converters, such as the CP2102.
|
||||
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.
|
||||
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.
|
||||
|
||||
|
|
|
@ -12,12 +12,7 @@ Currently the only supported sensor is the HCSR04 sensor.
|
|||
|
||||
## Connections
|
||||
|
||||
### Naze/Flip32+
|
||||
|
||||
| Mode | Trigger | Echo | Inline 1k resistors |
|
||||
| ------------------------------- | ------------- | ------------- | ------------------- |
|
||||
| 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) |
|
||||
Target dependent
|
||||
|
||||
#### Constraints
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
Spektrum bind with hardware bind plug support.
|
||||
|
||||
The Spektrum bind code is actually enabled for the NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY, CC3D, ALIENWIIF1, ALIENWIIF3 targets.
|
||||
The Spektrum bind code is actually enabled for the CJMCU, EUSTM32F103RC, SPARKY, CC3D, ALIENWIIF1, ALIENWIIF3 targets.
|
||||
|
||||
## Configure the bind code
|
||||
|
||||
|
@ -24,7 +24,7 @@ The hardware bind plug will be enabled via defining HARDWARE_BIND_PLUG during bu
|
|||
|
||||
## Function
|
||||
|
||||
The bind code will actually work for NAZE, NAZE32PRO, CJMCU, EUSTM32F103RC, SPARKY targets (USART2) and CC3D target (USART3, flex port). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
|
||||
The bind code will actually work for CJMCU, EUSTM32F103RC, SPARKY targets (USART2) and CC3D target (USART3, flex port). The spektrum_sat_bind CLI parameter is defining the number of bind impulses (1-10) send to the satellite receiver. Setting spektrum_sat_bind to zero will disable the bind mode in any case. The bind mode will only be activated after an power on or hard reset. Please refer to the table below for the different possible values.
|
||||
|
||||
If the hardware bind plug is configured the bind mode will only be activated if the plug is set during the firmware start-up. The value of the spektrum_sat_bind parameter will be permanently preserved. The bind plug should be always removed for normal flying.
|
||||
|
||||
|
@ -46,7 +46,7 @@ http://wiki.openpilot.org/display/Doc/Spektrum+Satellite
|
|||
|
||||
### Supported Hardware
|
||||
|
||||
NAZE, NAZE32PRO, CJMCU, SPARKY, EUSTM32F103RC, CC3D targets and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
|
||||
CJMCU, SPARKY, EUSTM32F103RC, CC3D targets and ALIENWIIF1, ALIENWIIF3 targets with hardware bind plug
|
||||
|
||||
### Connecting a Spektrum-compatible satellite to a Flip32+ flight controller
|
||||
|
||||
|
|
|
@ -104,6 +104,6 @@ changes from the repository, then rebuild the firmware:
|
|||
git reset --hard
|
||||
git pull
|
||||
|
||||
make clean TARGET=NAZE
|
||||
make TARGET=NAZE
|
||||
make clean TARGET=SPRACINGF3
|
||||
make TARGET=SPRACINGF3
|
||||
```
|
||||
|
|
|
@ -70,11 +70,11 @@ git clone https://github.com/iNavFlight/inav
|
|||
|
||||

|
||||
|
||||
To compile your INAV binaries, enter the inav directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default NAZE target:
|
||||
To compile your INAV binaries, enter the inav directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default SPRACINGF3 target:
|
||||
|
||||
```bash
|
||||
cd inav
|
||||
make TARGET=NAZE
|
||||
make TARGET=SPRACINGF3
|
||||
```
|
||||
|
||||

|
||||
|
@ -83,13 +83,13 @@ within few moments you should have your binary ready:
|
|||
|
||||
```bash
|
||||
(...)
|
||||
arm-none-eabi-size ./obj/main/inav_NAZE.elf
|
||||
arm-none-eabi-size ./obj/main/inav_SPRACINGF3.elf
|
||||
text data bss dec hex filename
|
||||
127468 916 16932 145316 237a4 ./obj/main/inav_NAZE.elf
|
||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/inav_NAZE.elf obj/inav_1.2.1_NAZE.hex
|
||||
127468 916 16932 145316 237a4 ./obj/main/inav_SPRACINGF3.elf
|
||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/inav_SPRACINGF3.elf obj/inav_1.2.1_SPRACINGF3.hex
|
||||
```
|
||||
|
||||
You can use the INAV-Configurator to flash the ```obj/inav_1.2.1_NAZE.hex``` file.
|
||||
You can use the INAV-Configurator to flash the ```obj/inav_1.2.1_SPRACINGF3.hex``` file.
|
||||
|
||||
## Updating and rebuilding
|
||||
|
||||
|
@ -99,6 +99,6 @@ Navigate to the local inavflight repository and use the following steps to pull
|
|||
cd inav
|
||||
git reset --hard
|
||||
git pull
|
||||
make clean TARGET=NAZE
|
||||
make clean TARGET=SPRACINGF3
|
||||
make
|
||||
```
|
||||
|
|
|
@ -69,11 +69,11 @@ git clone https://github.com/iNavFlight/inav.git
|
|||
|
||||

|
||||
|
||||
To compile your INAV binaries, enter the inav directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default NAZE target:
|
||||
To compile your INAV binaries, enter the inav directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default SPRACINGF3 target:
|
||||
|
||||
```bash
|
||||
cd inav
|
||||
make TARGET=NAZE
|
||||
make TARGET=SPRACINGF3
|
||||
```
|
||||
|
||||

|
||||
|
@ -82,13 +82,13 @@ within few moments you should have your binary ready:
|
|||
|
||||
```bash
|
||||
(...)
|
||||
arm-none-eabi-size ./obj/main/inav_NAZE.elf
|
||||
arm-none-eabi-size ./obj/main/inav_SPRACINGF3.elf
|
||||
text data bss dec hex filename
|
||||
95388 308 10980 106676 1a0b4 ./obj/main/inav_NAZE.elf
|
||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/inav_NAZE.elf obj/inav_NAZE.hex
|
||||
95388 308 10980 106676 1a0b4 ./obj/main/inav_SPRACINGF3.elf
|
||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/inav_SPRACINGF3.elf obj/inav_SPRACINGF3.hex
|
||||
```
|
||||
|
||||
You can use the INAV-Configurator to flash the ```obj/inav_NAZE.hex``` file.
|
||||
You can use the INAV-Configurator to flash the ```obj/inav_SPRACINGF3.hex``` file.
|
||||
|
||||
## Updating and rebuilding
|
||||
|
||||
|
@ -99,5 +99,5 @@ cd /cygdrive/c/dev/inav
|
|||
git reset --hard
|
||||
git pull
|
||||
make clean
|
||||
make TARGET=NAZE
|
||||
make TARGET=SPRACINGF3
|
||||
```
|
||||
|
|
|
@ -25,7 +25,7 @@ stop the board, flash the firmware, restart:
|
|||
sleep 100
|
||||
poll
|
||||
flash probe 0
|
||||
flash write_image erase /home/user/git/inav/obj/inav_NAZE.hex 0x08000000
|
||||
flash write_image erase /home/user/git/inav/obj/inav_SPRACINGF3.hex 0x08000000
|
||||
sleep 200
|
||||
soft_reset_halt
|
||||
wait_halt
|
||||
|
@ -47,7 +47,7 @@ If you use cygwin to build the binaries then be sure to have configured your com
|
|||
Create a new `GDB Hardware Debugging` launch configuration from the `Run` menu
|
||||
|
||||
It's important to have build the executable compiled with GDB debugging information first.
|
||||
Select the appropriate .elf file (not hex file) - In these examples the target platform is an OLIMEXINO, not a naze32.
|
||||
Select the appropriate .elf file (not hex file) - In these examples the target platform is an OLIMEXINO.
|
||||
|
||||
DISABLE auto-build
|
||||
|
||||
|
|
|
@ -12,7 +12,7 @@ https://www.youtube.com/watch?v=kjvqySyNw20
|
|||
|
||||
## Hardware
|
||||
|
||||
Various debugging hardware solutions exist, the Segger J-Link clones are cheap and are known to work on Windows with both the Naze and Olimexino platforms.
|
||||
Various debugging hardware solutions exist, the Segger J-Link clones are cheap and are known to work on Windows.
|
||||
|
||||
### J-Link devices
|
||||
|
||||
|
|
|
@ -11,8 +11,6 @@ targets=("PUBLISHMETA=True" \
|
|||
"TARGET=SPRACINGF3EVO" \
|
||||
"TARGET=LUX_RACE" \
|
||||
"TARGET=MOTOLAB" \
|
||||
"TARGET=NAZE" \
|
||||
"TARGET=NAZE32PRO" \
|
||||
"TARGET=OLIMEXINO" \
|
||||
"TARGET=PORT103R" \
|
||||
"TARGET=RMDO" \
|
||||
|
|
|
@ -78,14 +78,6 @@
|
|||
/*
|
||||
static inline void mma8451ConfigureInterrupt(void)
|
||||
{
|
||||
#ifdef NAZE
|
||||
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
|
||||
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
||||
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
|
||||
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU, RESOURCE_EXTI, 0);
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||
#endif
|
||||
|
||||
busWrite(acc->busDev, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
|
||||
busWrite(acc->busDev, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
|
||||
busWrite(acc->busDev, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
|
||||
|
|
|
@ -44,9 +44,6 @@
|
|||
#include "drivers/compass/compass_hmc5883l.h"
|
||||
|
||||
// HMC5883L, default address 0x1E
|
||||
// NAZE Target connections
|
||||
// PB12 connected to MAG_DRDY on rev4 hardware
|
||||
// PC14 connected to MAG_DRDY on rev5 hardware
|
||||
|
||||
/* CTRL_REGA: Control Register A
|
||||
* Read Write
|
||||
|
|
|
@ -47,7 +47,7 @@ void pca9685setPWMOff(uint8_t servoIndex, uint16_t off) {
|
|||
/*
|
||||
Writing new state every cycle for each servo is extremely time consuming
|
||||
and does not makes sense.
|
||||
On Flip32/Naze32 trying to sync 5 servos every 2000us extends looptime
|
||||
Trying to sync 5 servos every 2000us extends looptime
|
||||
to 3500us. Very, very bad...
|
||||
Instead of that, write desired values to temporary
|
||||
table and write it to PCA9685 only when there a need.
|
||||
|
|
|
@ -315,12 +315,6 @@ void validateAndFixConfig(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(NAZE) && defined(USE_RANGEFINDER_HCSR04)
|
||||
if ((rxConfig()->receiverType == RX_TYPE_PWM) && (rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) && featureConfigured(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(OLIMEXINO) && defined(USE_RANGEFINDER_HCSR04)
|
||||
if ((rangefinderConfig()->rangefinder_hardware == RANGEFINDER_HCSR04) && feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
|
||||
featureClear(FEATURE_CURRENT_METER);
|
||||
|
|
|
@ -375,14 +375,6 @@ void init(void)
|
|||
#endif
|
||||
};
|
||||
|
||||
#if defined(NAZE) && defined(USE_HARDWARE_REVISION_DETECTION)
|
||||
if (hardwareRevision >= NAZE32_REV5) {
|
||||
// naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
|
||||
beeperDevConfig.isOD = false;
|
||||
beeperDevConfig.isInverted = true;
|
||||
}
|
||||
#endif
|
||||
|
||||
beeperInit(&beeperDevConfig);
|
||||
#endif
|
||||
#ifdef USE_LIGHTS
|
||||
|
@ -625,11 +617,7 @@ void init(void)
|
|||
#endif
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
#ifdef NAZE
|
||||
if (hardwareRevision == NAZE32_REV5) {
|
||||
m25p16_init(0);
|
||||
}
|
||||
#elif defined(USE_FLASH_M25P16)
|
||||
#ifdef USE_FLASH_M25P16
|
||||
m25p16_init(0);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -167,12 +167,8 @@ static bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse)
|
|||
|
||||
#ifdef USE_ACC_MMA8452
|
||||
case ACC_MMA8452: // MMA8452
|
||||
#ifdef NAZE
|
||||
// Not supported with this frequency
|
||||
if (hardwareRevision < NAZE32_REV5 && mma8452Detect(dev)) {
|
||||
#else
|
||||
|
||||
if (mma8452Detect(dev)) {
|
||||
#endif
|
||||
#ifdef ACC_MMA8452_ALIGN
|
||||
dev->accAlign = ACC_MMA8452_ALIGN;
|
||||
#endif
|
||||
|
|
|
@ -54,10 +54,6 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#ifdef NAZE
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
||||
mag_t mag; // mag access functions
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 3);
|
||||
|
|
|
@ -59,7 +59,7 @@ For more detail of the different bind modes please refer the CleanFlight Spektru
|
|||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
|
||||
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
|
||||
|
||||
|
|
|
@ -59,7 +59,7 @@ For more detail of the different bind modes please refer the CleanFlight Spektru
|
|||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
|
||||
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
|
||||
|
||||
|
|
|
@ -59,7 +59,7 @@ For more detail of the different bind modes please refer the CleanFlight Spektru
|
|||
|
||||
Deltang receivers in serial mode will work like any other Spektrum satellite compatible receiver (10bit, 22ms) only the bind process will be different.
|
||||
|
||||
The pin layout for the AlienFlight F1 is very similar to NAZE32 or the related clones (MW32, Flip32, etc.). The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
The pin layout for the AlienFlight F3 is similar to Sparky. The new AlienFlightF3 V2 design have the sensor connected via SPI and some slightly different pin layout. All AlienFlight F3 flight controllers running the same firmware which takes care on the differences with a hardware detection. The AlienFlight F4 and F7 have their individual pin layouts and are independent designs.
|
||||
|
||||
(**) OpenSky receiver with telemetry is enabled by default if present on the board.
|
||||
|
||||
|
|
|
@ -1 +0,0 @@
|
|||
FEATURES = HIGHEND
|
|
@ -1,131 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/accgyro/accgyro_mpu6500.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
uint8_t hardwareRevision = UNKNOWN;
|
||||
|
||||
void detectHardwareRevision(void)
|
||||
{
|
||||
if (hse_value == 8000000)
|
||||
hardwareRevision = NAZE32;
|
||||
else if (hse_value == 12000000)
|
||||
hardwareRevision = NAZE32_REV5;
|
||||
}
|
||||
|
||||
#ifdef USE_SPI
|
||||
|
||||
#define DISABLE_SPI_CS IOHi(nazeSpiCsPin)
|
||||
#define ENABLE_SPI_CS IOLo(nazeSpiCsPin)
|
||||
|
||||
#define SPI_DEVICE_NONE (0)
|
||||
#define SPI_DEVICE_FLASH (1)
|
||||
#define SPI_DEVICE_MPU (2)
|
||||
|
||||
#define M25P16_INSTRUCTION_RDID 0x9F
|
||||
#define FLASH_M25P16_ID (0x202015)
|
||||
|
||||
static IO_t nazeSpiCsPin = IO_NONE;
|
||||
|
||||
uint8_t detectSpiDevice(void)
|
||||
{
|
||||
#ifdef NAZE_SPI_CS_PIN
|
||||
nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN));
|
||||
#endif
|
||||
|
||||
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
|
||||
uint8_t in[4];
|
||||
uint32_t flash_id;
|
||||
|
||||
// try autodetect flash chip
|
||||
delay(50); // short delay required after initialisation of SPI device instance.
|
||||
ENABLE_SPI_CS;
|
||||
spiTransfer(NAZE_SPI_INSTANCE, in, out, sizeof(out));
|
||||
DISABLE_SPI_CS;
|
||||
|
||||
flash_id = in[1] << 16 | in[2] << 8 | in[3];
|
||||
if (flash_id == FLASH_M25P16_ID)
|
||||
return SPI_DEVICE_FLASH;
|
||||
|
||||
|
||||
// try autodetect MPU
|
||||
delay(50);
|
||||
ENABLE_SPI_CS;
|
||||
spiTransferByte(NAZE_SPI_INSTANCE, MPU_RA_WHO_AM_I | MPU6500_BIT_RESET);
|
||||
in[0] = spiTransferByte(NAZE_SPI_INSTANCE, 0xff);
|
||||
DISABLE_SPI_CS;
|
||||
|
||||
if (in[0] == MPU6500_WHO_AM_I_CONST)
|
||||
return SPI_DEVICE_MPU;
|
||||
|
||||
return SPI_DEVICE_NONE;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
void updateHardwareRevision(void)
|
||||
{
|
||||
#ifdef USE_SPI
|
||||
uint8_t detectedSpiDevice = detectSpiDevice();
|
||||
|
||||
if (detectedSpiDevice == SPI_DEVICE_MPU && hardwareRevision == NAZE32_REV5)
|
||||
hardwareRevision = NAZE32_SP;
|
||||
#endif
|
||||
}
|
||||
|
||||
const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
|
||||
{
|
||||
// MPU_INT output on rev5 hardware PC13
|
||||
static const extiConfig_t nazeRev5MPUIntExtiConfig = {
|
||||
.tag = IO_TAG(PC13)
|
||||
};
|
||||
|
||||
#ifdef AFROMINI
|
||||
return &nazeRev5MPUIntExtiConfig;
|
||||
#else
|
||||
// MPU_INT output on rev4 PB13
|
||||
static const extiConfig_t nazeRev4MPUIntExtiConfig = {
|
||||
.tag = IO_TAG(PB13)
|
||||
};
|
||||
|
||||
if (hardwareRevision < NAZE32_REV5) {
|
||||
return &nazeRev4MPUIntExtiConfig;
|
||||
}
|
||||
else {
|
||||
return &nazeRev5MPUIntExtiConfig;
|
||||
}
|
||||
#endif
|
||||
}
|
|
@ -1,34 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
typedef enum nazeHardwareRevision_t {
|
||||
UNKNOWN = 0,
|
||||
NAZE32, // Naze32 and compatible with 8MHz HSE
|
||||
NAZE32_REV5, // Naze32 and compatible with 12MHz HSE
|
||||
NAZE32_SP // Naze32 w/Sensor Platforms
|
||||
} nazeHardwareRevision_e;
|
||||
|
||||
extern uint8_t hardwareRevision;
|
||||
|
||||
void updateHardwareRevision(void);
|
||||
void detectHardwareRevision(void);
|
||||
|
||||
void spiBusInit(void);
|
||||
|
||||
struct extiConfig_s;
|
||||
const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);
|
|
@ -1,42 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PPM | TIM_USE_PWM}, // PWM1 - RC1
|
||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM2 - RC2
|
||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM3 - RC3
|
||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM }, // PWM4 - RC4
|
||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM5 - RC5
|
||||
{ TIM3, IO_TAG(PA7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM6 - RC6
|
||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM7 - RC7
|
||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_PWM | TIM_USE_MC_CHNFW }, // PWM8 - RC8
|
||||
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR }, // PWM9 - OUT1
|
||||
{ TIM1, IO_TAG(PA11), TIM_Channel_4, 1, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR }, // PWM10 - OUT2
|
||||
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM11 - OUT3
|
||||
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM12 - OUT4
|
||||
{ TIM4, IO_TAG(PB8), TIM_Channel_3, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - OUT5
|
||||
{ TIM4, IO_TAG(PB9), TIM_Channel_4, 0, IOCFG_IPD, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
|
||||
};
|
||||
|
|
@ -1,205 +0,0 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "AFNA" // AFroNAze - NAZE might be considered misleading on Naze clones like the flip32.
|
||||
|
||||
#define LED0 PB3
|
||||
#define LED1 PB4
|
||||
|
||||
#define BEEPER PA12
|
||||
|
||||
#define INVERTER_PIN_UART2 PB2 // PB2 (BOOT1) abused as inverter select GPIO
|
||||
|
||||
#define USE_EXTI
|
||||
#define GYRO_INT_EXTI PC13
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
#define MAG_INT_EXTI PC14
|
||||
#define USE_MAG_DATA_READY_SIGNAL
|
||||
|
||||
// SPI2
|
||||
// PB15 28 SPI2_MOSI
|
||||
// PB14 27 SPI2_MISO
|
||||
// PB13 26 SPI2_SCK
|
||||
// PB12 25 SPI2_NSS
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
#define NAZE_SPI_BUS BUS_SPI2
|
||||
#define NAZE_SPI_CS_GPIO GPIOB
|
||||
#define NAZE_SPI_CS_PIN PB12
|
||||
#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
|
||||
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_SOFTSERIAL1
|
||||
|
||||
#ifdef AIRHERO32
|
||||
// MWC PARIS Sirius AirHero32
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_RX_PIN PB11
|
||||
#define UART3_TX_PIN PB10
|
||||
|
||||
#define I2C_DEVICE_SHARES_UART3
|
||||
|
||||
#define SERIAL_PORT_COUNT 4 // UART1, UART2, UART3, SS1
|
||||
|
||||
#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL
|
||||
#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO
|
||||
#define MPU6500_CS_PIN NAZE_SPI_CS_PIN
|
||||
#define MPU6500_SPI_BUS NAZE_SPI_BUS
|
||||
#else
|
||||
// Afroflight NAZE
|
||||
#define USE_HARDWARE_REVISION_DETECTION
|
||||
#define USE_SOFTSERIAL2
|
||||
|
||||
#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO
|
||||
#define M25P16_CS_PIN NAZE_SPI_CS_PIN
|
||||
#define M25P16_SPI_BUS NAZE_SPI_BUS
|
||||
|
||||
#define SERIAL_PORT_COUNT 4 // UART1, UART2, SS1, SS2
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#endif
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_MPU6050
|
||||
#define USE_GYRO_MPU6500
|
||||
|
||||
#define GYRO_MPU6050_ALIGN CW0_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_MPU6050
|
||||
#define USE_ACC_MPU6500
|
||||
|
||||
#define ACC_MPU6050_ALIGN CW0_DEG
|
||||
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||
|
||||
#define USE_BARO
|
||||
#define USE_BARO_MS5611 // needed for Flip32 board
|
||||
#define USE_BARO_BMP280
|
||||
|
||||
#define USE_MAG
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define MAG_HMC5883_ALIGN CW180_DEG
|
||||
|
||||
// #define USE_RANGEFINDER
|
||||
// #define USE_RANGEFINDER_HCSR04
|
||||
// #define USE_RANGEFINDER_SRF10
|
||||
// #define RANGEFINDER_HCSR04_TRIGGER_PIN PB0
|
||||
// #define RANGEFINDER_HCSR04_ECHO_PIN PB1
|
||||
// #define RANGEFINDER_HCSR04_TRIGGER_PIN_PWM PB8
|
||||
// #define RANGEFINDER_HCSR04_ECHO_PIN_PWM PB9
|
||||
|
||||
#define SOFTSERIAL_1_RX_PIN PA6
|
||||
#define SOFTSERIAL_1_TX_PIN PA7
|
||||
#define SOFTSERIAL_2_RX_PIN PB0
|
||||
#define SOFTSERIAL_2_TX_PIN PB1
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_2)
|
||||
|
||||
// #define SOFT_I2C // enable to test software i2c
|
||||
// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011)
|
||||
// #define SOFT_I2C_PB67
|
||||
|
||||
//#define USE_RX_NRF24
|
||||
#ifdef USE_RX_NRF24
|
||||
#define USE_RX_SPI
|
||||
|
||||
#define USE_RX_CX10
|
||||
#define USE_RX_H8_3D
|
||||
#define USE_RX_INAV
|
||||
//#define USE_RX_SYMA
|
||||
//#define USE_RX_V202
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_REF
|
||||
#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_CX10A
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
|
||||
//#define USE_SOFTSPI
|
||||
//#define USE_RX_SOFTSPI
|
||||
|
||||
// RC pinouts
|
||||
// RC1 GND
|
||||
// RC2 power
|
||||
// RC3 PA0/TIM2 RX_PPM
|
||||
// RC4 PA1/TIM2 CE / RSSI_ADC
|
||||
// RC5 PA2/TIM2 USART2 TX
|
||||
// RC6 PA3/TIM2 USART2 RX
|
||||
// RC7 PA6/TIM3 CSN / softserial1 RX / LED_STRIP
|
||||
// RC8 PA7/TIM3 SCK / softserial1 TX
|
||||
// RC9 PB0/TIM3 MISO / softserial2 RX / HC-SR04 trigger
|
||||
// RC10 PB1/TIM3 MOSI /softserial2 TX / HC-SR04 echo / current
|
||||
|
||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
#define RX_CE_PIN PA1
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_PIN PA6
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_SCK_PIN PA7
|
||||
#define RX_MOSI_PIN PB1
|
||||
#define RX_MISO_PIN PB0
|
||||
#endif // USE_NRF24
|
||||
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PB1
|
||||
#define ADC_CHANNEL_2_PIN PA4
|
||||
#define ADC_CHANNEL_3_PIN PA1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
//#define NAV_AUTO_MAG_DECLINATION
|
||||
//#define NAV_GPS_GLITCH_DETECTION
|
||||
|
||||
// #define USE_LED_STRIP
|
||||
// #define WS2811_PIN PA6
|
||||
// #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6
|
||||
// #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER
|
||||
|
||||
#undef USE_SERIALRX_SPEKTRUM
|
||||
#undef USE_SERIALRX_IBUS
|
||||
//#define USE_SPEKTRUM_BIND
|
||||
//#define BIND_PIN PA3
|
||||
|
||||
//#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_MOTOR_COUNT 6
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_VBAT)
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
||||
|
||||
// Number of available PWM outputs
|
||||
#define MAX_PWM_OUTPUT_PORTS 10
|
||||
|
||||
// IO - assuming all IOs on 48pin package
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) )
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 14
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
|
|
@ -1,17 +0,0 @@
|
|||
F1_TARGETS += $(TARGET)
|
||||
FEATURES = ONBOARDFLASH HIGHEND
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6050.c \
|
||||
drivers/accgyro/accgyro_mpu6500.c \
|
||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
io/flashfs.c \
|
||||
hardware_revision.c
|
Loading…
Add table
Add a link
Reference in a new issue