Skip to content

Commit

Permalink
Merge pull request #5160 from iNavFlight/development
Browse files Browse the repository at this point in the history
Release INAV 2.3.0
  • Loading branch information
digitalentity authored Nov 24, 2019
2 parents af08641 + 0f6ef4a commit d0bdd38
Show file tree
Hide file tree
Showing 211 changed files with 12,978 additions and 1,159 deletions.
9 changes: 7 additions & 2 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,21 @@
.project
.settings
.cproject
obj/
patches/
startup_stm32f10x_md_gcc.s
.vagrant/
.vscode/
cov-int*
obj/
patches/
tools/
downloads/

# script-generated files
docs/Manual.pdf
README.pdf

# build generated files
/settings.json

# local changes only
make/local.mk
13 changes: 7 additions & 6 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ env:
- GOAL=targets-group-5
- GOAL=targets-group-6
- GOAL=targets-group-7
- GOAL=targets-group-8
- GOAL=targets-group-rest

# use new docker environment
Expand All @@ -22,6 +23,7 @@ addons:
- build-essential
- git
- libc6-i386
- time

# We use cpp for unit tests, and c for the main project.
language: cpp
Expand All @@ -30,21 +32,20 @@ compiler: clang
before_install:

install:
- ./install-toolchain.sh
- export TOOLCHAINPATH=$PWD/gcc-arm-none-eabi-8-2018-q4-major/bin
- export PATH=$TOOLCHAINPATH:$PATH
- make arm_sdk_install

before_script:
- $TOOLCHAINPATH/arm-none-eabi-gcc --version
- make arm_sdk_version
- clang --version
- clang++ --version

script: ./.travis.sh

cache:
apt: true
timeout: 1000
directories:
- $PWD/gcc-arm-none-eabi-8-2018-q4-major
- downloads
- tools

notifications:
#slack: inavflight:UWRoWFJ4cbbpHXT8HJJlAPXa
Expand Down
19 changes: 10 additions & 9 deletions Dockerfile
Original file line number Diff line number Diff line change
@@ -1,22 +1,23 @@
FROM ubuntu:xenial
LABEL maintainer Andy Schwarz <[email protected]>
FROM ubuntu:bionic

# Configuration
VOLUME /home/src/
WORKDIR /home/src/
ARG TOOLCHAIN_VERSION_SHORT
ENV TOOLCHAIN_VERSION_SHORT ${TOOLCHAIN_VERSION_SHORT:-"8-2018q4"}
ARG TOOLCHAIN_VERSION_LONG
ENV TOOLCHAIN_VERSION_LONG ${TOOLCHAIN_VERSION_LONG:-"8-2018-q4-major"}

# Essentials
RUN mkdir -p /home/src && \
apt-get update && \
apt-get install -y software-properties-common python-software-properties ruby make git gcc wget curl bzip2 lib32ncurses5 lib32z1
apt-get install -y software-properties-common ruby make git gcc wget curl bzip2

# Toolchain
ENV TOOLCHAIN=
ENV TOOLCHAIN_ID=
RUN wget -P /tmp https://developer.arm.com/-/media/Files/downloads/gnu-rm/6-2017q2/gcc-arm-none-eabi-6-2017-q2-update-linux.tar.bz2
RUN wget -P /tmp "https://developer.arm.com/-/media/Files/downloads/gnu-rm/$TOOLCHAIN_VERSION_SHORT/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG-linux.tar.bz2"
RUN mkdir -p /opt && \
cd /opt && \
tar xvjf /tmp/gcc-arm-none-eabi-6-2017-q2-update-linux.tar.bz2 -C /opt && \
chmod -R -w /opt/gcc-arm-none-eabi-6-2017-q2-update
tar xvjf "/tmp/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG-linux.tar.bz2" -C /opt && \
chmod -R -w "/opt/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG"

ENV PATH="/opt/gcc-arm-none-eabi-6-2017-q2-update/bin:${PATH}"
ENV PATH="/opt/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG/bin:$PATH"
68 changes: 48 additions & 20 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,15 @@ INCLUDE_DIRS := $(SRC_DIR) \
$(ROOT)/src/main/target
LINKER_DIR := $(ROOT)/src/main/target/link

# import macros common to all supported build systems
include $(ROOT)/make/system-id.mk

# developer preferences, edit these at will, they'll be gitignored
-include $(ROOT)/make/local.mk

# default xtal value for F4 targets
HSE_VALUE = 8000000
MHZ_VALUE ?=

# used for turning on features like VCP and SDCARD
FEATURES =
Expand All @@ -82,8 +89,9 @@ VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
VALID_TARGETS := $(sort $(VALID_TARGETS))

CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) )

ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
Expand Down Expand Up @@ -123,9 +131,10 @@ GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPR
GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4
GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 ALIENFLIGHTNGF7 PIXRACER YUPIF4 YUPIF4MINI YUPIF4R2 YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX
GROUP_5_TARGETS := ASGARD32F7 CHEBUZZF3 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4
GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV KROOZX MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS), $(VALID_TARGETS))
GROUP_8_TARGETS := MATEKF765
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS))

REVISION = $(shell git rev-parse --short HEAD)

Expand Down Expand Up @@ -168,6 +177,10 @@ ifneq ($(HSE_VALUE),)
DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
endif

ifneq ($(MHZ_VALUE),)
DEVICE_FLAGS := $(DEVICE_FLAGS) -DMHZ_VALUE=$(MHZ_VALUE)
endif

ifneq ($(BASE_TARGET), $(TARGET))
TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET)
endif
Expand All @@ -189,19 +202,21 @@ include $(ROOT)/make/source.mk
include $(ROOT)/make/release.mk

###############################################################################
# Things that might need changing to use different tools
#
# Toolchain installer
#

TOOLS_DIR := $(ROOT)/tools
DL_DIR := $(ROOT)/downloads

include $(ROOT)/make/tools.mk

#
# Tool names
ifneq ($(TOOLCHAINPATH),)
CROSS_CC = $(TOOLCHAINPATH)/arm-none-eabi-gcc
OBJCOPY = $(TOOLCHAINPATH)/arm-none-eabi-objcopy
SIZE = $(TOOLCHAINPATH)/arm-none-eabi-size
else
CROSS_CC = arm-none-eabi-gcc
OBJCOPY = arm-none-eabi-objcopy
SIZE = arm-none-eabi-size
endif
#
CROSS_CC = $(ARM_SDK_PREFIX)gcc
OBJCOPY = $(ARM_SDK_PREFIX)objcopy
SIZE = $(ARM_SDK_PREFIX)size

#
# Tool options.
Expand Down Expand Up @@ -313,16 +328,16 @@ $(GENERATED_SETTINGS): $(SETTINGS_GENERATOR) $(SETTINGS_FILE) $(STAMP)
CFLAGS += -I$(TARGET_OBJ_DIR)

$(STAMP): .FORCE
$(V1) CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP)
$(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP)

# Use a pattern rule, since they're different than normal rules.
# See https://www.gnu.org/software/make/manual/make.html#Pattern-Examples
%generated.h %generated.c:
$(V1) echo "settings.yaml -> settings_generated.h, settings_generated.c" "$(STDOUT)"
$(V1) CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR)
$(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR)

settings-json:
$(V0) CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json
$(V0) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json

clean-settings:
$(V1) $(RM) $(GENERATED_SETTINGS)
Expand Down Expand Up @@ -369,6 +384,14 @@ $(TARGET_OBJ_DIR)/%.o: %.S
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<


# mkdirs
$(DL_DIR):
mkdir -p $@

$(TOOLS_DIR):
mkdir -p $@


## all : Build all valid targets
all: $(VALID_TARGETS)

Expand All @@ -393,6 +416,9 @@ targets-group-6: $(GROUP_6_TARGETS)
## targets-group-7 : build some targets
targets-group-7: $(GROUP_7_TARGETS)

## targets-group-8 : build some targets
targets-group-8: $(GROUP_8_TARGETS)

## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3)
targets-group-rest: $(GROUP_OTHER_TARGETS)

Expand Down Expand Up @@ -438,11 +464,12 @@ flash_$(TARGET): $(TARGET_HEX)
## flash : flash firmware (.hex) onto flight controller
flash: flash_$(TARGET)

st-flash_$(TARGET): $(TARGET_BIN)
$(V0) st-flash --reset write $< 0x08000000
$(STFLASH_TARGETS) :
$(V0) $(MAKE) -j 8 TARGET=$(subst st-flash_,,$@) st-flash

## st-flash : flash firmware (.bin) onto flight controller
st-flash: st-flash_$(TARGET)
st-flash: $(TARGET_BIN)
$(V0) st-flash --reset write $< 0x08000000

binary: $(TARGET_BIN)
hex: $(TARGET_HEX)
Expand Down Expand Up @@ -487,6 +514,7 @@ targets:
$(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)"
$(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)"
$(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)"
$(V0) @echo "targets-group-7: $(GROUP_8_TARGETS)"
$(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)"
$(V0) @echo "Release targets: $(RELEASE_TARGETS)"

Expand Down
14 changes: 12 additions & 2 deletions build.sh
Original file line number Diff line number Diff line change
@@ -1,2 +1,12 @@
echo "Building target" $1
docker run --rm -v `pwd`:/home/src/ flyandi/docker-inav make TARGET=$1
if [ -z "$1" ]; then
echo "Usage syntax: ./build.sh <TARGET>"
exit 1
fi

if [ -z "$(docker images -q inav-build)" ]; then
echo -e "*** Building image\n"
docker build -t inav-build .
fi

echo -e "*** Building target $1\n"
docker run --rm -v "$(pwd)":/home/src/ inav-build make TARGET="$1"
6 changes: 3 additions & 3 deletions docs/Board - Airbot F4 and Flip32 F4.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

## Radio Receivers

This board does not support Parallel PWM receiver connection. Only SerialRX, PPM and MSP receivers are supported.
SerialRX, PPM and MSP receivers are supported.

SerialRX and PPM receivers should be connected to dedicated _PPM SBUS_ connector above _Motor 1_. MSP receivers should be connected to one of UARTs configured as MSP.

Expand Down Expand Up @@ -77,9 +77,9 @@ LED strip is enabled on Motor 5 pin (PA1)

## SoftwareSerial

This board allows for single **SoftwareSerial** port on small soldering pads located next to UART3 pins.
This board allows for single **SoftwareSerial** port on small soldering pads located next to UART3 pins.

| Pad | SoftwareSerial Role |
| ---- | ---- |
| CH5 | RX |
| CH6 | TX |
| CH6 | TX |
2 changes: 1 addition & 1 deletion docs/Board - BeeRotor F4.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@

## Radio Receivers

This board does not support Parallel PWM receiver connection. Only SerialRX, PPM and MSP receivers are supported.
SerialRX, PPM and MSP receivers are supported.

SerialRX and PPM receivers should be connected to dedicated _PPM SBUS_ pin on the _RX_ connector. MSP receivers should be connected to one of UARTs configured as MSP.

Expand Down
2 changes: 1 addition & 1 deletion docs/Board - Matek F411 Wing.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
* `MATEKF411` if you want to control LEDs and have SS1 TX on ST1 pad.
* `MATEKF411_FD_SFTSRL` if you need the softserial to be full-duplex (TX = ST1 pad, RX = LED pad), at the cost of losing the LED output.
* `MATEKF411_RSSI` if you want to have analog RSSI input on ST1 pad. SS1 TX will be available on the LED pad.
* `MATEKF411_SFTSRL2`if you want to use two softserials (TX only) at the same time. Eg. Smart Audio + S. Port, Smart Audio + LTM
* `MATEKF411_SFTSRL2`if you want to use two softserials (TX only) at the same time. Eg. Smart Audio + S. Port, Smart Audio + LTM. (SS1 TX will be on ST1 pad and SS2 TX will be on LED pad).

## Where to buy:

Expand Down
22 changes: 17 additions & 5 deletions docs/Board - MatekF405.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ Due to differences on the board (I2C - see below), there are two firmware varian
* Current Sensor: Yes (AIO, CTR), otherwise FCHUB-6S option
* Integrated Power Distribution Board: Yes (AIO, CTR), otherwise FCHUB-6S option
* Integrated Voltage Regulator: 5V 2A & 9V 2A (AIO), 5V 2A (CTR), otherwise FCHUB-6S option
* 6 PWM / DSHOT capable outputs (iNav does not implement DSHOT)
* 6 PWM / DSHOT capable outputs
* WS2812 Led Strip : Yes
* Beeper: Yes
* RSSI: Yes
Expand Down Expand Up @@ -75,8 +75,22 @@ I2C requires that the WS2812 led strip is moved to S5, thus WS2812 is not usable
Soft serial is available as an alternative to a hardware UART on RX4/TX4 and TX2. By default this is NOT inverted. In order to use this feature:

* Enable soft serial
* Do not assign any function to hardware UART4 or UART2-TX
* Assign the desired function to the soft-serial port
* Do not assign any function to hardware UART4
* Assign the desired function to the soft-serial ports
* UART4 TX/RX pads will be used as SoftSerial 1 TX/RX pads
* UART2 TX pad will be used as SoftSerial 2 TX pad

RX2 and SBUS pads can be used as normal for receiver-only UART. If you need a full duplex UART (IE: TBS Crossfire) and SoftSerial, then use UART 1, 3 or 5 for Full Duplex.

#### Common scenarios for SoftSerial on this boards:
You need to wire a FrSky receiver (SBUS and SmartPort) to the Flight controller
* Connect SBUS from Receiver to SBUS pin on the Flight Controller
* Connect SmartPort from Receiver to TX2 pad on the Flight Controller
* Enable SoftSerial and set UART2 for Serial RX and SoftSerial 2 for SmartPort Telemetry

You need to wire a SmartAudio or Trump VTX to the Flight controller
* Connect SmartAudio/Tramp from VTX to the TX4 pad on the Flight Controller
* Enable SoftSerial and set SoftSerial 1 for SmartAudio or Tramp

### USB

Expand Down Expand Up @@ -108,5 +122,3 @@ Rcgroups Thread Matek F405: https://www.rcgroups.com/forums/showthread.php?28892
Rcgroups Thread Matek F405-AIO: https://www.rcgroups.com/forums/showthread.php?2912273-Matek-Flight-Controller-F405-AIO

This board doesn't have hardware inverters for UART pins. This page explains getting SmartPort telemetry working on F4 board: https://github.com/iNavFlight/inav/blob/master/docs/Telemetry.md


28 changes: 28 additions & 0 deletions docs/Board - MatekF765-Wing.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# Board - [MATEKSYS F765-Wing](https://inavflight.com/shop/s/bg/1557661)

![Matek F765 Wing](http://www.mateksys.com/wp-content/uploads/2019/08/F765-WING_2.jpg)

## Specification:

* STM32F765 216MHz CPU
* 2-8S LiPo support
* 132A current sensor
* OSD
* BMP280 barometer
* SD slot
* 7 UART serial ports
* 2 I2C
* PDB for 2 motors
* 12 outputs (10 DSHOT)
* 8A BEC for the servos
* 9V supply for FPV gear
* Dual camera switcher

## Details

* For Matek F765-WING use `MATEKF765` firmware.
* No need for SBUS inversion

## Where to buy:

* [Banggood](https://inavflight.com/shop/s/bg/1557661)
2 changes: 1 addition & 1 deletion docs/Board - Omnibus F4.md
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ More target options:

## Radio Receivers

This board does not support Parallel PWM receiver connection. Only SerialRX, PPM and MSP receivers are supported.
SerialRX, PPM and MSP receivers are supported.

SerialRX and PPM receivers should be connected to dedicated _PPM SBUS_ connector above _Motor 1_. MSP receivers should be connected to one of UARTs configured as MSP.

Expand Down
2 changes: 1 addition & 1 deletion docs/Board - Omnibus F7.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

## Radio Receivers

This board does not support Parallel PWM receiver connection. Only SerialRX, PPM and MSP receivers are supported.
SerialRX, PPM and MSP receivers are supported.

SerialRX and PPM receivers should be connected to dedicated _PPM SBUS_ connector. For SerialRX use UART2

Expand Down
Loading

0 comments on commit d0bdd38

Please sign in to comment.