mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
Merge branch 'master' into serial-port-options
This commit is contained in:
commit
507a022e90
23 changed files with 446 additions and 116 deletions
37
Makefile
37
Makefile
|
@ -29,6 +29,9 @@ DEBUG ?=
|
||||||
# Serial port/Device for flashing
|
# Serial port/Device for flashing
|
||||||
SERIAL_DEVICE ?= /dev/ttyUSB0
|
SERIAL_DEVICE ?= /dev/ttyUSB0
|
||||||
|
|
||||||
|
# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override.
|
||||||
|
FLASH_SIZE ?=
|
||||||
|
|
||||||
###############################################################################
|
###############################################################################
|
||||||
# Things that need to be maintained as the source changes
|
# Things that need to be maintained as the source changes
|
||||||
#
|
#
|
||||||
|
@ -40,6 +43,19 @@ VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 CC3D CJMCU
|
||||||
# Valid targets for OP BootLoader support
|
# Valid targets for OP BootLoader support
|
||||||
OPBL_VALID_TARGETS = CC3D
|
OPBL_VALID_TARGETS = CC3D
|
||||||
|
|
||||||
|
# Configure default flash sizes for the targets
|
||||||
|
ifeq ($(FLASH_SIZE),)
|
||||||
|
ifeq ($(TARGET),$(filter $(TARGET),CJMCU))
|
||||||
|
FLASH_SIZE = 64
|
||||||
|
else ifeq ($(TARGET),$(filter $(TARGET),NAZE CC3D ALIENWIIF1 SPRACINGF3 OLIMEXINO))
|
||||||
|
FLASH_SIZE = 128
|
||||||
|
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPARKY ALIENWIIF3))
|
||||||
|
FLASH_SIZE = 256
|
||||||
|
else
|
||||||
|
$(error FLASH_SIZE not configured for target)
|
||||||
|
endif
|
||||||
|
endif
|
||||||
|
|
||||||
REVISION = $(shell git log -1 --format="%h")
|
REVISION = $(shell git log -1 --format="%h")
|
||||||
|
|
||||||
# Working directories
|
# Working directories
|
||||||
|
@ -92,7 +108,7 @@ DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\
|
||||||
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_256k.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
|
||||||
|
|
||||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||||
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
|
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
|
||||||
|
@ -125,7 +141,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(CMSIS_DIR)/CM3/CoreSupport \
|
$(CMSIS_DIR)/CM3/CoreSupport \
|
||||||
$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
|
$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \
|
||||||
|
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_256k.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
|
||||||
|
|
||||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m3
|
ARCH_FLAGS = -mthumb -mcpu=cortex-m3
|
||||||
TARGET_FLAGS = -D$(TARGET) -pedantic
|
TARGET_FLAGS = -D$(TARGET) -pedantic
|
||||||
|
@ -169,7 +185,7 @@ DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \
|
||||||
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_128k.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld
|
||||||
|
|
||||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m3
|
ARCH_FLAGS = -mthumb -mcpu=cortex-m3
|
||||||
TARGET_FLAGS = -D$(TARGET) -pedantic
|
TARGET_FLAGS = -D$(TARGET) -pedantic
|
||||||
|
@ -177,6 +193,10 @@ DEVICE_FLAGS = -DSTM32F10X_MD -DSTM32F10X
|
||||||
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
ifneq ($(FLASH_SIZE),)
|
||||||
|
DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
|
||||||
|
endif
|
||||||
|
|
||||||
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
|
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
|
||||||
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
||||||
|
|
||||||
|
@ -368,14 +388,10 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
|
||||||
$(HIGHEND_SRC) \
|
$(HIGHEND_SRC) \
|
||||||
$(COMMON_SRC)
|
$(COMMON_SRC)
|
||||||
|
|
||||||
ifeq ($(TARGET),CJMCU)
|
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_64k.ld
|
|
||||||
endif
|
|
||||||
|
|
||||||
ifeq ($(OPBL),yes)
|
ifeq ($(OPBL),yes)
|
||||||
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
|
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
|
||||||
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
|
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_128k_opbl.ld
|
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
|
||||||
.DEFAULT_GOAL := binary
|
.DEFAULT_GOAL := binary
|
||||||
else
|
else
|
||||||
$(error OPBL specified with a unsupported target)
|
$(error OPBL specified with a unsupported target)
|
||||||
|
@ -509,14 +525,11 @@ SPRACINGF3_SRC = \
|
||||||
drivers/compass_hmc5883l.c \
|
drivers/compass_hmc5883l.c \
|
||||||
drivers/display_ug2864hsweg01.h \
|
drivers/display_ug2864hsweg01.h \
|
||||||
drivers/flash_m25p16.c \
|
drivers/flash_m25p16.c \
|
||||||
|
drivers/sonar_hcsr04.c \
|
||||||
io/flashfs.c \
|
io/flashfs.c \
|
||||||
$(HIGHEND_SRC) \
|
$(HIGHEND_SRC) \
|
||||||
$(COMMON_SRC)
|
$(COMMON_SRC)
|
||||||
|
|
||||||
ifeq ($(TARGET),SPRACINGF3)
|
|
||||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_128k.ld
|
|
||||||
endif
|
|
||||||
|
|
||||||
# Search path and source files for the ST stdperiph library
|
# Search path and source files for the ST stdperiph library
|
||||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@ Disconnect main power, connect to cli via USB/FTDI.
|
||||||
|
|
||||||
dump using cli
|
dump using cli
|
||||||
|
|
||||||
`rate profile 0`
|
`rateprofile 0`
|
||||||
`profile 0`
|
`profile 0`
|
||||||
`dump`
|
`dump`
|
||||||
|
|
||||||
|
@ -40,10 +40,10 @@ dump profiles using cli if you use them
|
||||||
|
|
||||||
dump rate profiles using cli if you use them
|
dump rate profiles using cli if you use them
|
||||||
|
|
||||||
`rate profile 1`
|
`rateprofile 1`
|
||||||
`dump rates`
|
`dump rates`
|
||||||
|
|
||||||
`rate profile 2`
|
`rateprofile 2`
|
||||||
`dump rates`
|
`dump rates`
|
||||||
|
|
||||||
copy screen output to a file and save it.
|
copy screen output to a file and save it.
|
||||||
|
@ -142,7 +142,6 @@ Re-apply any new defaults as desired.
|
||||||
| nav_slew_rate | | 0 | 100 | 30 | Profile | UINT8 |
|
| nav_slew_rate | | 0 | 100 | 30 | Profile | UINT8 |
|
||||||
| serialrx_provider | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | 0 | 6 | 0 | Master | UINT8 |
|
| serialrx_provider | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | 0 | 6 | 0 | Master | UINT8 |
|
||||||
| spektrum_sat_bind | | 0 | 10 | 0 | Master | UINT8 |
|
| spektrum_sat_bind | | 0 | 10 | 0 | Master | UINT8 |
|
||||||
| telemetry_provider | Choose what type of telemetry to output. See Telemetry section. | 0 | 3 | 0 | Master | UINT8 |
|
|
||||||
| telemetry_switch | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | 0 | 1 | 0 | Master | UINT8 |
|
| telemetry_switch | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | 0 | 1 | 0 | Master | UINT8 |
|
||||||
| telemetry_inversion | | 0 | 1 | 0 | Master | UINT8 |
|
| telemetry_inversion | | 0 | 1 | 0 | Master | UINT8 |
|
||||||
| frsky_default_lattitude | | -90 | 90 | 0 | Master | FLOAT |
|
| frsky_default_lattitude | | -90 | 90 | 0 | Master | FLOAT |
|
||||||
|
|
|
@ -10,15 +10,15 @@ The idea is that you set throttle and other controls so the aircraft descends in
|
||||||
|
|
||||||
Flight controller based failsafe is where the flight controller attempts to detect signal loss from your receiver.
|
Flight controller based failsafe is where the flight controller attempts to detect signal loss from your receiver.
|
||||||
|
|
||||||
It is possible to use both types at the same time which may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect.
|
It is possible to use both types at the same time, which may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect.
|
||||||
|
|
||||||
## Flight controller failsafe system
|
## Flight controller failsafe system
|
||||||
|
|
||||||
The failsafe system is not activated until 5 seconds after the flight controller boots up. This is to prevent failsafe from activating, as in the case of TX/RX gear with long bind procedures, before the RX sends out valid data.
|
The failsafe system is not activated until 5 seconds after the flight controller boots up. This is to prevent failsafe from activating, as in the case of TX/RX gear with long bind procedures, before the RX sends out valid data. Note that you need to activate the 'FAILSAFE' feature in order to activate failsafe on flight controller.
|
||||||
|
|
||||||
After the failsafe has forced a landing, the flight controller cannot be armed and has to be reset.
|
After the failsafe has forced a landing, the flight controller cannot be armed and has to be reset.
|
||||||
|
|
||||||
The failsafe system attempts to detect when your receiver loses signal. It then attempts to prevent your aircraft from flying away uncontrollably by enabling an auto-level mode and setting the throttle that should allow the craft to come to a safter landing.
|
The failsafe system attempts to detect when your receiver loses signal. It then attempts to prevent your aircraft from flying away uncontrollably by enabling an auto-level mode and setting the throttle that should allow the craft to come to a safer landing.
|
||||||
|
|
||||||
The failsafe is activated when:
|
The failsafe is activated when:
|
||||||
|
|
||||||
|
@ -53,21 +53,21 @@ Bench test the failsafe system before flying - remove props while doing so.
|
||||||
1. Observe motors spin at configured throttle setting for configured duration.
|
1. Observe motors spin at configured throttle setting for configured duration.
|
||||||
1. Turn on TX or reconnect RX.
|
1. Turn on TX or reconnect RX.
|
||||||
1. Ensure that your switch positions don't now cause the craft to disarm (otherwise it would fall out of the sky on regained signal).
|
1. Ensure that your switch positions don't now cause the craft to disarm (otherwise it would fall out of the sky on regained signal).
|
||||||
1. Observe that normal flight behaviour is resumed.
|
1. Observe that normal flight behavior is resumed.
|
||||||
1. Disarm.
|
1. Disarm.
|
||||||
|
|
||||||
Field test the failsafe system
|
Field test the failsafe system
|
||||||
|
|
||||||
1. Perform bench testing first!
|
1. Perform bench testing first!
|
||||||
1. On a calm day go to an un-populated area away from buildings or test indoors in a safe controlled environment - e.g. inside a big net.
|
1. On a calm day go to an unpopulated area away from buildings or test indoors in a safe controlled environment - e.g. inside a big net.
|
||||||
1. Arm the craft.
|
1. Arm the craft.
|
||||||
1. Hover over something soft (long grass, ferns, heather, foam, etc).
|
1. Hover over something soft (long grass, ferns, heather, foam, etc.).
|
||||||
1. Descend the craft and observe throttle position and record throttle value from your TX channel monitor. Ideally 1500 should be hover. So your value should be less than 1500.
|
1. Descend the craft and observe throttle position and record throttle value from your TX channel monitor. Ideally 1500 should be hover. So your value should be less than 1500.
|
||||||
1. Stop, disarm.
|
1. Stop, disarm.
|
||||||
1. Set failsafe thottle to the recorded value.
|
1. Set failsafe throttle to the recorded value.
|
||||||
1. Arm, hover over something soft again.
|
1. Arm, hover over something soft again.
|
||||||
1. Turn off TX (!)
|
1. Turn off TX (!)
|
||||||
1. Observe craft descends and motors continue to spin for the configurated duration.
|
1. Observe craft descends and motors continue to spin for the configured duration.
|
||||||
1. Observe FC disarms after the configured duration.
|
1. Observe FC disarms after the configured duration.
|
||||||
1. Remove flight battery.
|
1. Remove flight battery.
|
||||||
|
|
||||||
|
@ -93,8 +93,10 @@ See your receiver's documentation for direction on how to accomplish one of thes
|
||||||
|
|
||||||
3. Set 'failsafe_throttle' to a value that allows the aircraft to descend at approximately one meter per second.
|
3. Set 'failsafe_throttle' to a value that allows the aircraft to descend at approximately one meter per second.
|
||||||
|
|
||||||
|
4. Enable 'FAILSAFE' feature in Cleanflight GUI or via CLI using `feature FAILSAFE`
|
||||||
|
|
||||||
These are the basic steps for flight controller failsafe configuration, see Failsafe Settings below for additional settings that may be changed.
|
|
||||||
|
These are the basic steps for flight controller failsafe configuration; see Failsafe Settings below for additional settings that may be changed.
|
||||||
|
|
||||||
##Failsafe Settings
|
##Failsafe Settings
|
||||||
|
|
||||||
|
@ -132,5 +134,5 @@ Only valid when using Parallel PWM or PPM receivers.
|
||||||
|
|
||||||
This setting helps detect when your RX stops sending any data when the RX looses signal.
|
This setting helps detect when your RX stops sending any data when the RX looses signal.
|
||||||
|
|
||||||
With a Graupner GR-24 configured for PWM output with failsafe on channels 1-4 set to OFF in the receiver settings
|
With a Graupner GR-24 configured for PWM output with failsafe on channels 1-4 set to OFF in the receiver settings then this setting, at its default value, will allow failsafe to be activated.
|
||||||
then this setting, at its default value, will allow failsafe to be activated.
|
|
||||||
|
|
17
docs/Gps.md
17
docs/Gps.md
|
@ -134,4 +134,19 @@ From the UBlox documentation:
|
||||||
## Hardware
|
## Hardware
|
||||||
|
|
||||||
There are many GPS receivers available on the market.
|
There are many GPS receivers available on the market.
|
||||||
See Gps_-_Tested_Hardware.md for a list of user tested hardware.
|
Below are some examples of user-tested hardware.
|
||||||
|
|
||||||
|
### Ublox
|
||||||
|
|
||||||
|
Ublox Neo-M8N GPS with Compass
|
||||||
|
|
||||||
|
Ublox Neo-7M GPS with Compass and Pedestal Mount
|
||||||
|
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
|
||||||
|
|
||||||
|
Ublox NEO-6M GPS with Compass
|
||||||
|
http://www.ebay.com/itm/111585855757
|
||||||
|
|
||||||
|
|
||||||
|
### Serial NMEA
|
||||||
|
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
|
||||||
|
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426
|
||||||
|
|
|
@ -1,13 +0,0 @@
|
||||||
## User tested hardware
|
|
||||||
|
|
||||||
###Ublox
|
|
||||||
|
|
||||||
Ublox Neo-M8N GPS with Compass
|
|
||||||
|
|
||||||
Ublox Neo-7M GPS with Compass and Pedestal Mount
|
|
||||||
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
|
|
||||||
|
|
||||||
|
|
||||||
###Serial NMEA
|
|
||||||
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
|
|
||||||
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426
|
|
|
@ -2,7 +2,7 @@
|
||||||
|
|
||||||
Telemetry allows you to know what is happening on your aircraft while you are flying it. Among other things you can receive battery voltages and GPS positions on your transmitter.
|
Telemetry allows you to know what is happening on your aircraft while you are flying it. Among other things you can receive battery voltages and GPS positions on your transmitter.
|
||||||
|
|
||||||
Telemetry can be either always on, or enabled when armed. If no serial port is set to be telemetry-only then telemetry will only be enabled when armed.
|
Telemetry can be either always on, or enabled when armed. If a serial port for telemetry is shared with other functionality then then telemetry will only be enabled when armed on that port.
|
||||||
|
|
||||||
Telemetry is enabled using the 'TELEMETRY` feature.
|
Telemetry is enabled using the 'TELEMETRY` feature.
|
||||||
|
|
||||||
|
@ -10,24 +10,9 @@ Telemetry is enabled using the 'TELEMETRY` feature.
|
||||||
feature TELEMETRY
|
feature TELEMETRY
|
||||||
```
|
```
|
||||||
|
|
||||||
Multiple telemetry providers are currently supported, FrSky (the default), Graupner HoTT V4, SmartPort (S.Port) and MultiWii Serial Protocol (MSP)
|
Multiple telemetry providers are currently supported, FrSky, Graupner HoTT V4, SmartPort (S.Port) and MultiWii Serial Protocol (MSP)
|
||||||
|
|
||||||
Use the `telemetry_provider` cli command to select one.
|
All telemetry systems use serial ports, configure serial ports to use the telemetry system required.
|
||||||
|
|
||||||
| Value | Meaning |
|
|
||||||
| ----- | --------------- |
|
|
||||||
| 0 | FrSky (Default) |
|
|
||||||
| 1 | HoTT |
|
|
||||||
| 2 | MSP |
|
|
||||||
| 3 | SmartPort |
|
|
||||||
|
|
||||||
Example:
|
|
||||||
|
|
||||||
```
|
|
||||||
set telemetry_provider = 1
|
|
||||||
```
|
|
||||||
|
|
||||||
There are further examples in the Configuration section of the documentation.
|
|
||||||
|
|
||||||
## FrSky telemetry
|
## FrSky telemetry
|
||||||
|
|
||||||
|
@ -72,11 +57,14 @@ RPM requires that the 'blades' setting is set to 12 on your receiver/display - t
|
||||||
|
|
||||||
## HoTT telemetry
|
## HoTT telemetry
|
||||||
|
|
||||||
HoTT telemetry can be used when the TX and RX pins of a serial port are connected using a diode and a single wire to the T port on a HoTT receiver.
|
Only Electric Air Modules and GPS Modules are emulated.
|
||||||
|
|
||||||
Only Electric Air Modules and GPS Modules are emulated, remember to enable them on your transmitter - in the Telemetry Menu on the MX-20.
|
Use the latest Graupner firmware for your transmitter and receiver.
|
||||||
|
|
||||||
Serial ports use two wires but HoTT uses a single wire so some electronics are required so that the signals don't get mixed up.
|
Older HoTT transmitters required the EAM and GPS modules to be enabled in the telemetry menu of the transmitter. (e.g. on MX-20)
|
||||||
|
|
||||||
|
Serial ports use two wires but HoTT uses a single wire so some electronics are required so that the signals don't get mixed up. The TX and RX pins of
|
||||||
|
a serial port should be connected using a diode and a single wire to the `T` port on a HoTT receiver.
|
||||||
|
|
||||||
Connect as follows:
|
Connect as follows:
|
||||||
|
|
||||||
|
@ -93,11 +81,11 @@ The diode should be arranged to allow the data signals to flow the right way
|
||||||
|
|
||||||
As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which has 5V tolerant digital pins.
|
As noticed by Skrebber the GR-12 (and probably GR-16/24, too) are based on a PIC 24FJ64GA-002, which has 5V tolerant digital pins.
|
||||||
|
|
||||||
Note: The SoftSerial ports are not listed as 5V tolerant in the STM32F103xx data sheet pinouts and pin description section. Verify if you require a 5v/3.3v level shifters.
|
Note: The SoftSerial ports may not be 5V tolerant on your board. Verify if you require a 5v/3.3v level shifters.
|
||||||
|
|
||||||
## MultiWii Serial Protocol (MSP)
|
## MultiWii Serial Protocol (MSP)
|
||||||
|
|
||||||
MSP Telemetry simply transmitts MSP packets in sequence to any MSP device attached to the telemetry port. It rotates though a fixes sequence of command responses.
|
MSP Telemetry simply transmits MSP packets in sequence to any MSP device attached to the telemetry port. It rotates though a fixes sequence of command responses.
|
||||||
|
|
||||||
It is transmit only, it can work at any supported baud rate.
|
It is transmit only, it can work at any supported baud rate.
|
||||||
|
|
||||||
|
|
109
docs/development/Building in Mac OS X.md
Executable file
109
docs/development/Building in Mac OS X.md
Executable file
|
@ -0,0 +1,109 @@
|
||||||
|
# Building in Mac OS X
|
||||||
|
|
||||||
|
Building in Mac OS X can be accomplished in just a few steps:
|
||||||
|
|
||||||
|
* Install general development tools (clang, make, git)
|
||||||
|
* Install ARM GCC 4.8 series compiler
|
||||||
|
* Checkout Cleanflight sourcecode through git
|
||||||
|
* Build the code
|
||||||
|
|
||||||
|
## Install general development tools (clang, make, git)
|
||||||
|
|
||||||
|
Open up a terminal and run `make`. If it is installed already, you should see a message like this, which means that you
|
||||||
|
already have the required development tools installed:
|
||||||
|
|
||||||
|
```
|
||||||
|
make: *** No targets specified and no makefile found. Stop.
|
||||||
|
```
|
||||||
|
|
||||||
|
If it isn't installed yet, you might get a popup like this. If so, click the "install" button to install the commandline
|
||||||
|
developer tools:
|
||||||
|
|
||||||
|

|
||||||
|
|
||||||
|
If you just get an error like this instead of a helpful popup prompt:
|
||||||
|
|
||||||
|
```
|
||||||
|
-bash: make: command not found
|
||||||
|
```
|
||||||
|
|
||||||
|
Try running `xcode-select --install` instead to trigger the popup.
|
||||||
|
|
||||||
|
If that doesn't work, you'll need to install the XCode development environment [from the App Store][]. After
|
||||||
|
installation, open up XCode and enter its preferences menu. Go to the "downloads" tab and install the
|
||||||
|
"command line tools" package.
|
||||||
|
|
||||||
|
[from the App Store]: https://itunes.apple.com/us/app/xcode/id497799835
|
||||||
|
|
||||||
|
## Install ARM GCC 4.8 series compiler
|
||||||
|
|
||||||
|
Cleanflight is built using the 4.8 series GCC compiler provided by the [GNU Tools for ARM Embedded Processors project][].
|
||||||
|
The newest "4.9" series compiler produces builds that don't boot on CC3D and Sparky targets (and perhaps others), so it's
|
||||||
|
better to use the older 4.8 compiler for the moment.
|
||||||
|
|
||||||
|
Hit the "all downloads" link on the right side of the GNU Tools for ARM page to view [the older releases][]. Grab the
|
||||||
|
Mac installation tarball for the latest version in the 4.8 series (e.g. 4.8-2014-q3-update). Move it somewhere useful
|
||||||
|
such as a `~/development` folder (in your home directory) and double click it to unpack it. You should end up with a
|
||||||
|
folder called `~/development/gcc-arm-none-eabi-4_8-2014q3/`.
|
||||||
|
|
||||||
|
Now you just need to add the `bin/` directory from inside the GCC directory to your system's path. Run `nano ~/.profile`. Add a
|
||||||
|
new line at the end of the file which adds the path for the `bin/` folder to your path, like so:
|
||||||
|
|
||||||
|
```
|
||||||
|
export PATH=$PATH:~/development/gcc-arm-none-eabi-4_8-2014q3/bin
|
||||||
|
```
|
||||||
|
|
||||||
|
Press CTRL+X to exit nano, and answer "y" when prompted to save your changes.
|
||||||
|
|
||||||
|
Now *close this terminal window* and open a new one. Try running:
|
||||||
|
|
||||||
|
```
|
||||||
|
arm-none-eabi-gcc --version
|
||||||
|
```
|
||||||
|
|
||||||
|
You should get output similar to:
|
||||||
|
|
||||||
|
```
|
||||||
|
arm-none-eabi-gcc (GNU Tools for ARM Embedded Processors) 4.8.4 20140725 (release) [ARM/embedded-4_8-branch revision 213147]
|
||||||
|
Copyright (C) 2013 Free Software Foundation, Inc.
|
||||||
|
This is free software; see the source for copying conditions. There is NO
|
||||||
|
warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
```
|
||||||
|
|
||||||
|
If `arm-none-eabi-gcc` couldn't be found, go back and check that you entered the correct path in your `~/.profile` file.
|
||||||
|
|
||||||
|
[GNU Tools for ARM Embedded Processors project]: https://launchpad.net/gcc-arm-embedded
|
||||||
|
[the older releases]: https://launchpad.net/gcc-arm-embedded/+download
|
||||||
|
|
||||||
|
## Checkout CleanFlight sourcecode through git
|
||||||
|
|
||||||
|
Enter your development directory and clone the [Cleanflight repository][] using the "HTTPS clone URL" which is shown on
|
||||||
|
the right side of the Cleanflight GitHub page, like so:
|
||||||
|
|
||||||
|
```
|
||||||
|
git clone https://github.com/cleanflight/cleanflight.git
|
||||||
|
```
|
||||||
|
|
||||||
|
This will download the entire Cleanflight repository for you into a new folder called "cleanflight".
|
||||||
|
|
||||||
|
[CleanFlight repository]: https://github.com/cleanflight/cleanflight
|
||||||
|
|
||||||
|
## Build the code
|
||||||
|
|
||||||
|
Enter the cleanflight directory and run `make TARGET=NAZE` to build firmware for the Naze32. When the build completes,
|
||||||
|
the .hex firmware should be available as `obj/cleanflight_NAZE.hex` for you to flash using the Cleanflight
|
||||||
|
Configurator.
|
||||||
|
|
||||||
|
## Updating to the latest source
|
||||||
|
|
||||||
|
If you want to erase your local changes and update to the latest version of the Cleanflight source, enter your
|
||||||
|
cleanflight directory and run these commands to first erase your local changes, fetch and merge the latest
|
||||||
|
changes from the repository, then rebuild the firmware:
|
||||||
|
|
||||||
|
```
|
||||||
|
git reset --hard
|
||||||
|
git pull
|
||||||
|
|
||||||
|
make clean TARGET=NAZE
|
||||||
|
make TARGET=NAZE
|
||||||
|
```
|
83
docs/development/Configuration Storage.md
Normal file
83
docs/development/Configuration Storage.md
Normal file
|
@ -0,0 +1,83 @@
|
||||||
|
# Configuration
|
||||||
|
|
||||||
|
The configuration in cleanflight is stored at the end of the flash ram, currently it uses 2KB of flash.
|
||||||
|
|
||||||
|
Sometimes it's necesaary to erase this during development.
|
||||||
|
|
||||||
|
## Erasing
|
||||||
|
|
||||||
|
Generate a 2kb blank file.
|
||||||
|
|
||||||
|
```
|
||||||
|
dd if=/dev/zero of=obj/blankconfig.bin bs=1024 count=2
|
||||||
|
```
|
||||||
|
|
||||||
|
Overwrite configuration using JLink
|
||||||
|
|
||||||
|
Run JLink (OSX: `/Applications/SEGGER/JLink/JLinkExe`)
|
||||||
|
|
||||||
|
Execute commands
|
||||||
|
`device <your device>`, e.g. `STM32F303CB`
|
||||||
|
`r`
|
||||||
|
`h`
|
||||||
|
`loadbin obj/blankconfig.bin, <address>`, address 128k device = 0x801F800, 256k device = 0x803f800
|
||||||
|
`r` to Reboot FC.
|
||||||
|
`q` to quit
|
||||||
|
|
||||||
|
Example session
|
||||||
|
|
||||||
|
```
|
||||||
|
$ /Applications/SEGGER/JLink/JLinkExe
|
||||||
|
SEGGER J-Link Commander V4.90c ('?' for help)
|
||||||
|
Compiled Aug 29 2014 09:52:38
|
||||||
|
DLL version V4.90c, compiled Aug 29 2014 09:52:33
|
||||||
|
Firmware: J-Link ARM-OB STM32 compiled Aug 22 2012 19:52:04
|
||||||
|
Hardware: V7.00
|
||||||
|
S/N: -1
|
||||||
|
Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull
|
||||||
|
VTarget = 3.300V
|
||||||
|
Info: Could not measure total IR len. TDO is constant high.
|
||||||
|
Info: Could not measure total IR len. TDO is constant high.
|
||||||
|
No devices found on JTAG chain. Trying to find device on SWD.
|
||||||
|
Info: Found SWD-DP with ID 0x2BA01477
|
||||||
|
Info: Found Cortex-M4 r0p1, Little endian.
|
||||||
|
Info: FPUnit: 6 code (BP) slots and 2 literal slots
|
||||||
|
Info: TPIU fitted.
|
||||||
|
Info: ETM fitted.
|
||||||
|
Cortex-M4 identified.
|
||||||
|
Target interface speed: 100 kHz
|
||||||
|
J-Link>device STM32F303CC
|
||||||
|
Info: Device "STM32F303CC" selected (256 KB flash, 32 KB RAM).
|
||||||
|
Reconnecting to target...
|
||||||
|
Info: Found SWD-DP with ID 0x2BA01477
|
||||||
|
Info: Found SWD-DP with ID 0x2BA01477
|
||||||
|
Info: Found Cortex-M4 r0p1, Little endian.
|
||||||
|
Info: FPUnit: 6 code (BP) slots and 2 literal slots
|
||||||
|
Info: TPIU fitted.
|
||||||
|
Info: ETM fitted.
|
||||||
|
J-Link>r
|
||||||
|
Reset delay: 0 ms
|
||||||
|
Reset type NORMAL: Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
|
||||||
|
J-Link>h
|
||||||
|
PC = 08001154, CycleCnt = 00000000
|
||||||
|
R0 = 00000000, R1 = 00000000, R2 = 00000000, R3 = 00000000
|
||||||
|
R4 = 00000000, R5 = 00000000, R6 = 00000000, R7 = 00000000
|
||||||
|
R8 = 00000000, R9 = 00000000, R10= 00000000, R11= 00000000
|
||||||
|
R12= 00000000
|
||||||
|
SP(R13)= 2000A000, MSP= 2000A000, PSP= 00000000, R14(LR) = FFFFFFFF
|
||||||
|
XPSR = 01000000: APSR = nzcvq, EPSR = 01000000, IPSR = 000 (NoException)
|
||||||
|
CFBP = 00000000, CONTROL = 00, FAULTMASK = 00, BASEPRI = 00, PRIMASK = 00
|
||||||
|
FPU regs: FPU not enabled / not implemented on connected CPU.
|
||||||
|
J-Link>loadbin obj/blankconfig.bin, 0x803f800
|
||||||
|
Downloading file [obj/blankconfig.bin]...
|
||||||
|
WARNING: CPU is running at low speed (7989 kHz).
|
||||||
|
Info: J-Link: Flash download: Flash programming performed for 1 range (2048 bytes)
|
||||||
|
Info: J-Link: Flash download: Total time needed: 1.254s (Prepare: 0.698s, Compare: 0.009s, Erase: 0.075s, Program: 0.405s, Verify: 0.005s, Restore: 0.059s)
|
||||||
|
O.K.
|
||||||
|
J-Link>r
|
||||||
|
Reset delay: 0 ms
|
||||||
|
Reset type NORMAL: Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
|
||||||
|
J-Link>q
|
||||||
|
```
|
||||||
|
|
||||||
|
|
BIN
docs/development/assets/mac-prompt-tools-install.png
Normal file
BIN
docs/development/assets/mac-prompt-tools-install.png
Normal file
Binary file not shown.
After Width: | Height: | Size: 17 KiB |
|
@ -88,24 +88,44 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
||||||
|
|
||||||
#define FLASH_TO_RESERVE_FOR_CONFIG 0x800
|
#define FLASH_TO_RESERVE_FOR_CONFIG 0x800
|
||||||
|
|
||||||
#ifndef FLASH_PAGE_COUNT
|
#if !defined(FLASH_SIZE)
|
||||||
#ifdef STM32F303xC
|
#error "Flash size not defined for target. (specify in KB)"
|
||||||
#define FLASH_PAGE_COUNT 128
|
|
||||||
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef STM32F10X_MD
|
|
||||||
#define FLASH_PAGE_COUNT 128
|
#ifndef FLASH_PAGE_SIZE
|
||||||
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
|
#ifdef STM32F303xC
|
||||||
|
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F10X_MD
|
||||||
|
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F10X_HD
|
||||||
|
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef STM32F10X_HD
|
#if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
|
||||||
#define FLASH_PAGE_COUNT 128
|
#ifdef STM32F10X_MD
|
||||||
#define FLASH_PAGE_SIZE ((uint16_t)0x800)
|
#define FLASH_PAGE_COUNT 128
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F10X_HD
|
||||||
|
#define FLASH_PAGE_COUNT 128
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(FLASH_PAGE_COUNT) || !defined(FLASH_PAGE_SIZE)
|
#if defined(FLASH_SIZE)
|
||||||
|
#define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(FLASH_PAGE_SIZE)
|
||||||
|
#error "Flash page size not defined for target."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(FLASH_PAGE_COUNT)
|
||||||
#error "Flash page count not defined for target."
|
#error "Flash page count not defined for target."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -758,6 +778,12 @@ void validateAndFixConfig(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(SPRACINGF3) && defined(SONAR)
|
||||||
|
if (feature(FEATURE_RX_PARALLEL_PWM) && feature(FEATURE_SONAR) ) {
|
||||||
|
featureClear(FEATURE_SONAR);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
useRxConfig(&masterConfig.rxConfig);
|
useRxConfig(&masterConfig.rxConfig);
|
||||||
|
|
||||||
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
serialConfig_t *serialConfig = &masterConfig.serialConfig;
|
||||||
|
|
|
@ -72,8 +72,5 @@ void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
|
||||||
|
|
||||||
void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
|
void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
|
||||||
{
|
{
|
||||||
UNUSED(portsrc);
|
SYSCFG_EXTILineConfig(portsrc, pinsrc);
|
||||||
UNUSED(pinsrc);
|
|
||||||
|
|
||||||
// FIXME needed yet? implement?
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -21,6 +21,7 @@
|
||||||
#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0)
|
#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0)
|
||||||
#define NVIC_PRIO_USB NVIC_BUILD_PRIORITY(2, 0)
|
#define NVIC_PRIO_USB NVIC_BUILD_PRIORITY(2, 0)
|
||||||
#define NVIC_PRIO_USB_WUP NVIC_BUILD_PRIORITY(1, 0)
|
#define NVIC_PRIO_USB_WUP NVIC_BUILD_PRIORITY(1, 0)
|
||||||
|
#define NVIC_PRIO_SONAR_ECHO NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||||
#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f)
|
||||||
|
|
||||||
// utility macros to join/split priority
|
// utility macros to join/split priority
|
||||||
|
|
|
@ -22,6 +22,7 @@
|
||||||
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
|
#include "nvic.h"
|
||||||
|
|
||||||
#include "sonar_hcsr04.h"
|
#include "sonar_hcsr04.h"
|
||||||
|
|
||||||
|
@ -74,22 +75,37 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware)
|
||||||
|
|
||||||
sonarHardware = initialSonarHardware;
|
sonarHardware = initialSonarHardware;
|
||||||
|
|
||||||
|
#ifdef STM32F10X
|
||||||
// enable AFIO for EXTI support
|
// enable AFIO for EXTI support
|
||||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
// tp - trigger pin
|
#ifdef STM32F303xC
|
||||||
|
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
|
||||||
|
|
||||||
|
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// trigger pin
|
||||||
gpio.pin = sonarHardware->trigger_pin;
|
gpio.pin = sonarHardware->trigger_pin;
|
||||||
gpio.mode = Mode_Out_PP;
|
gpio.mode = Mode_Out_PP;
|
||||||
gpio.speed = Speed_2MHz;
|
gpio.speed = Speed_2MHz;
|
||||||
gpioInit(GPIOB, &gpio);
|
gpioInit(GPIOB, &gpio);
|
||||||
|
|
||||||
// ep - echo pin
|
// echo pin
|
||||||
gpio.pin = sonarHardware->echo_pin;
|
gpio.pin = sonarHardware->echo_pin;
|
||||||
gpio.mode = Mode_IN_FLOATING;
|
gpio.mode = Mode_IN_FLOATING;
|
||||||
gpioInit(GPIOB, &gpio);
|
gpioInit(GPIOB, &gpio);
|
||||||
|
|
||||||
|
#ifdef STM32F10X
|
||||||
// setup external interrupt on echo pin
|
// setup external interrupt on echo pin
|
||||||
gpioExtiLineConfig(GPIO_PortSourceGPIOB, sonarHardware->exti_pin_source);
|
gpioExtiLineConfig(GPIO_PortSourceGPIOB, sonarHardware->exti_pin_source);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
gpioExtiLineConfig(EXTI_PortSourceGPIOB, sonarHardware->exti_pin_source);
|
||||||
|
#endif
|
||||||
|
|
||||||
EXTI_ClearITPendingBit(sonarHardware->exti_line);
|
EXTI_ClearITPendingBit(sonarHardware->exti_line);
|
||||||
|
|
||||||
|
@ -99,7 +115,13 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware)
|
||||||
EXTIInit.EXTI_LineCmd = ENABLE;
|
EXTIInit.EXTI_LineCmd = ENABLE;
|
||||||
EXTI_Init(&EXTIInit);
|
EXTI_Init(&EXTIInit);
|
||||||
|
|
||||||
NVIC_EnableIRQ(sonarHardware->exti_irqn);
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = sonarHardware->exti_irqn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SONAR_ECHO);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SONAR_ECHO);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
|
||||||
lastMeasurementAt = millis() - 60; // force 1st measurement in hcsr04_get_distance()
|
lastMeasurementAt = millis() - 60; // force 1st measurement in hcsr04_get_distance()
|
||||||
}
|
}
|
||||||
|
|
|
@ -203,7 +203,7 @@ static const motorMixer_t mixerDualcopter[] = {
|
||||||
|
|
||||||
// Keep synced with mixerMode_e
|
// Keep synced with mixerMode_e
|
||||||
const mixer_t mixers[] = {
|
const mixer_t mixers[] = {
|
||||||
// Mo Se Mixtable
|
// motors, servos, motor mixer
|
||||||
{ 0, 0, NULL }, // entry 0
|
{ 0, 0, NULL }, // entry 0
|
||||||
{ 3, 1, mixerTri }, // MIXER_TRI
|
{ 3, 1, mixerTri }, // MIXER_TRI
|
||||||
{ 4, 0, mixerQuadP }, // MIXER_QUADP
|
{ 4, 0, mixerQuadP }, // MIXER_QUADP
|
||||||
|
@ -224,7 +224,7 @@ const mixer_t mixers[] = {
|
||||||
{ 4, 0, mixerVtail4 }, // MIXER_VTAIL4
|
{ 4, 0, mixerVtail4 }, // MIXER_VTAIL4
|
||||||
{ 6, 0, mixerHex6H }, // MIXER_HEX6H
|
{ 6, 0, mixerHex6H }, // MIXER_HEX6H
|
||||||
{ 0, 1, NULL }, // * MIXER_PPM_TO_SERVO
|
{ 0, 1, NULL }, // * MIXER_PPM_TO_SERVO
|
||||||
{ 2, 1, mixerDualcopter }, // MIXER_DUALCOPTER
|
{ 2, 1, mixerDualcopter }, // MIXER_DUALCOPTER
|
||||||
{ 1, 1, NULL }, // MIXER_SINGLECOPTER
|
{ 1, 1, NULL }, // MIXER_SINGLECOPTER
|
||||||
{ 4, 0, mixerAtail4 }, // MIXER_ATAIL4
|
{ 4, 0, mixerAtail4 }, // MIXER_ATAIL4
|
||||||
{ 0, 0, NULL }, // MIXER_CUSTOM
|
{ 0, 0, NULL }, // MIXER_CUSTOM
|
||||||
|
@ -665,9 +665,11 @@ void mixTable(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// constrain servos
|
// constrain servos
|
||||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++)
|
if (useServo) {
|
||||||
servo[i] = constrain(servo[i], servoConf[i].min, servoConf[i].max); // limit the values
|
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
|
servo[i] = constrain(servo[i], servoConf[i].min, servoConf[i].max); // limit the values
|
||||||
|
}
|
||||||
|
}
|
||||||
// forward AUX1-4 to servo outputs (not constrained)
|
// forward AUX1-4 to servo outputs (not constrained)
|
||||||
if (gimbalConfig->gimbal_flags & GIMBAL_FORWARDAUX) {
|
if (gimbalConfig->gimbal_flags & GIMBAL_FORWARDAUX) {
|
||||||
forwardAuxChannelsToServos();
|
forwardAuxChannelsToServos();
|
||||||
|
|
|
@ -407,18 +407,18 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
|
||||||
case ADJUSTMENT_PITCH_ROLL_RATE:
|
case ADJUSTMENT_PITCH_ROLL_RATE:
|
||||||
case ADJUSTMENT_PITCH_RATE:
|
case ADJUSTMENT_PITCH_RATE:
|
||||||
newValue = (int)controlRateConfig->rates[FD_PITCH] + delta;
|
newValue = (int)controlRateConfig->rates[FD_PITCH] + delta;
|
||||||
controlRateConfig->rates[FD_PITCH] = constrain(newValue, 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
controlRateConfig->rates[FD_PITCH] = constrain(newValue, 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
|
||||||
if (adjustmentFunction == ADJUSTMENT_PITCH_RATE) {
|
if (adjustmentFunction == ADJUSTMENT_PITCH_RATE) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// follow though for combined ADJUSTMENT_PITCH_ROLL_RATE
|
// follow though for combined ADJUSTMENT_PITCH_ROLL_RATE
|
||||||
case ADJUSTMENT_ROLL_RATE:
|
case ADJUSTMENT_ROLL_RATE:
|
||||||
newValue = (int)controlRateConfig->rates[FD_ROLL] + delta;
|
newValue = (int)controlRateConfig->rates[FD_ROLL] + delta;
|
||||||
controlRateConfig->rates[FD_ROLL] = constrain(newValue, 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
controlRateConfig->rates[FD_ROLL] = constrain(newValue, 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
|
||||||
break;
|
break;
|
||||||
case ADJUSTMENT_YAW_RATE:
|
case ADJUSTMENT_YAW_RATE:
|
||||||
newValue = (int)controlRateConfig->rates[FD_YAW] + delta;
|
newValue = (int)controlRateConfig->rates[FD_YAW] + delta;
|
||||||
controlRateConfig->rates[FD_YAW] = constrain(newValue, 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
controlRateConfig->rates[FD_YAW] = constrain(newValue, 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX);
|
||||||
break;
|
break;
|
||||||
case ADJUSTMENT_PITCH_ROLL_P:
|
case ADJUSTMENT_PITCH_ROLL_P:
|
||||||
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
if (IS_PID_CONTROLLER_FP_BASED(pidProfile->pidController)) {
|
||||||
|
|
|
@ -100,6 +100,14 @@ typedef enum {
|
||||||
#define MIN_MODE_RANGE_STEP 0
|
#define MIN_MODE_RANGE_STEP 0
|
||||||
#define MAX_MODE_RANGE_STEP ((CHANNEL_RANGE_MAX - CHANNEL_RANGE_MIN) / 25)
|
#define MAX_MODE_RANGE_STEP ((CHANNEL_RANGE_MAX - CHANNEL_RANGE_MIN) / 25)
|
||||||
|
|
||||||
|
// Roll/pitch rates are a proportion used for mixing, so it tops out at 1.0:
|
||||||
|
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 100
|
||||||
|
|
||||||
|
/* Meaningful yaw rates are effectively unbounded because they are treated as a rotation rate multiplier: */
|
||||||
|
#define CONTROL_RATE_CONFIG_YAW_RATE_MAX 255
|
||||||
|
|
||||||
|
#define CONTROL_RATE_CONFIG_TPA_MAX 100
|
||||||
|
|
||||||
// steps are 25 apart
|
// steps are 25 apart
|
||||||
// a value of 0 corresponds to a channel value of 900 or less
|
// a value of 0 corresponds to a channel value of 900 or less
|
||||||
// a value of 48 corresponds to a channel value of 2100 or more
|
// a value of 48 corresponds to a channel value of 2100 or more
|
||||||
|
|
|
@ -397,10 +397,10 @@ const clivalue_t valueTable[] = {
|
||||||
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, 0, 100 },
|
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, 0, 100 },
|
||||||
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, 0, 100 },
|
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, 0, 100 },
|
||||||
{ "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, 0, 100 },
|
{ "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, 0, 100 },
|
||||||
{ "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], 0, 100 },
|
{ "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX },
|
||||||
{ "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], 0, 100 },
|
{ "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX },
|
||||||
{ "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], 0, 100 },
|
{ "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX },
|
||||||
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, 0, 100},
|
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, 0, CONTROL_RATE_CONFIG_TPA_MAX},
|
||||||
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
|
||||||
|
|
||||||
{ "failsafe_delay", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_delay, 0, 200 },
|
{ "failsafe_delay", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_delay, 0, 200 },
|
||||||
|
|
|
@ -1221,6 +1221,7 @@ static bool processInCommand(void)
|
||||||
{
|
{
|
||||||
uint32_t i;
|
uint32_t i;
|
||||||
uint16_t tmp;
|
uint16_t tmp;
|
||||||
|
uint8_t rate;
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
uint8_t wp_no;
|
uint8_t wp_no;
|
||||||
int32_t lat = 0, lon = 0, alt = 0;
|
int32_t lat = 0, lon = 0, alt = 0;
|
||||||
|
@ -1331,9 +1332,11 @@ static bool processInCommand(void)
|
||||||
currentControlRateProfile->rcRate8 = read8();
|
currentControlRateProfile->rcRate8 = read8();
|
||||||
currentControlRateProfile->rcExpo8 = read8();
|
currentControlRateProfile->rcExpo8 = read8();
|
||||||
for (i = 0; i < 3; i++) {
|
for (i = 0; i < 3; i++) {
|
||||||
currentControlRateProfile->rates[i] = read8();
|
rate = read8();
|
||||||
|
currentControlRateProfile->rates[i] = MIN(rate, i == FD_YAW ? CONTROL_RATE_CONFIG_YAW_RATE_MAX : CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
|
||||||
}
|
}
|
||||||
currentControlRateProfile->dynThrPID = read8();
|
rate = read8();
|
||||||
|
currentControlRateProfile->dynThrPID = MIN(rate, CONTROL_RATE_CONFIG_TPA_MAX);
|
||||||
currentControlRateProfile->thrMid8 = read8();
|
currentControlRateProfile->thrMid8 = read8();
|
||||||
currentControlRateProfile->thrExpo8 = read8();
|
currentControlRateProfile->thrExpo8 = read8();
|
||||||
currentControlRateProfile->tpa_breakpoint = read16();
|
currentControlRateProfile->tpa_breakpoint = read16();
|
||||||
|
|
|
@ -191,6 +191,8 @@ void init(void)
|
||||||
|
|
||||||
timerInit(); // timer must be initialized before any channel is allocated
|
timerInit(); // timer must be initialized before any channel is allocated
|
||||||
|
|
||||||
|
serialInit(&masterConfig.serialConfig);
|
||||||
|
|
||||||
mixerInit(masterConfig.mixerMode, masterConfig.customMixer);
|
mixerInit(masterConfig.mixerMode, masterConfig.customMixer);
|
||||||
|
|
||||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||||
|
@ -341,8 +343,6 @@ void init(void)
|
||||||
|
|
||||||
imuInit();
|
imuInit();
|
||||||
|
|
||||||
serialInit(&masterConfig.serialConfig);
|
|
||||||
|
|
||||||
mspInit(&masterConfig.serialConfig);
|
mspInit(&masterConfig.serialConfig);
|
||||||
cliInit(&masterConfig.serialConfig);
|
cliInit(&masterConfig.serialConfig);
|
||||||
|
|
||||||
|
|
|
@ -69,6 +69,15 @@ void sonarInit(void)
|
||||||
.exti_irqn = EXTI1_IRQn
|
.exti_irqn = EXTI1_IRQn
|
||||||
};
|
};
|
||||||
hcsr04_init(&sonarHardware);
|
hcsr04_init(&sonarHardware);
|
||||||
|
#elif defined(SPRACINGF3)
|
||||||
|
static const sonarHardware_t const sonarHardware = {
|
||||||
|
.trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
||||||
|
.echo_pin = Pin_1, // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
||||||
|
.exti_line = EXTI_Line1,
|
||||||
|
.exti_pin_source = EXTI_PinSource1,
|
||||||
|
.exti_irqn = EXTI1_IRQn
|
||||||
|
};
|
||||||
|
hcsr04_init(&sonarHardware);
|
||||||
#else
|
#else
|
||||||
#error Sonar not defined for target
|
#error Sonar not defined for target
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -20,9 +20,6 @@
|
||||||
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
|
||||||
#define USE_HARDWARE_REVISION_DETECTION
|
#define USE_HARDWARE_REVISION_DETECTION
|
||||||
|
|
||||||
#define FLASH_PAGE_COUNT 64
|
|
||||||
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
|
|
||||||
|
|
||||||
#define LED0_GPIO GPIOC
|
#define LED0_GPIO GPIOC
|
||||||
#define LED0_PIN Pin_14 // PC14 (LED)
|
#define LED0_PIN Pin_14 // PC14 (LED)
|
||||||
#define LED0
|
#define LED0
|
||||||
|
@ -61,7 +58,6 @@
|
||||||
// #define SOFT_I2C_PB67
|
// #define SOFT_I2C_PB67
|
||||||
|
|
||||||
#define SERIAL_RX
|
#define SERIAL_RX
|
||||||
//#define BLACKBOX
|
|
||||||
//#define USE_SERVOS
|
//#define USE_SERVOS
|
||||||
|
|
||||||
#define SPEKTRUM_BIND
|
#define SPEKTRUM_BIND
|
||||||
|
@ -71,3 +67,7 @@
|
||||||
|
|
||||||
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
|
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
|
||||||
#define USE_QUAD_MIXER_ONLY
|
#define USE_QUAD_MIXER_ONLY
|
||||||
|
|
||||||
|
#if (FLASH_SIZE > 64)
|
||||||
|
#define BLACKBOX
|
||||||
|
#endif
|
||||||
|
|
|
@ -48,6 +48,7 @@
|
||||||
#define USE_FLASHFS
|
#define USE_FLASHFS
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
|
||||||
|
#define SONAR
|
||||||
#define BEEPER
|
#define BEEPER
|
||||||
#define LED0
|
#define LED0
|
||||||
|
|
||||||
|
|
|
@ -65,6 +65,13 @@ extern "C" {
|
||||||
#include "unittest_macros.h"
|
#include "unittest_macros.h"
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
|
// input
|
||||||
|
#define TEST_RC_MID 1500
|
||||||
|
|
||||||
|
// output
|
||||||
|
#define TEST_MIN_COMMAND 1000
|
||||||
|
#define TEST_SERVO_MID 1500
|
||||||
|
|
||||||
typedef struct motor_s {
|
typedef struct motor_s {
|
||||||
uint16_t value;
|
uint16_t value;
|
||||||
} motor_t;
|
} motor_t;
|
||||||
|
@ -87,17 +94,17 @@ TEST(FlightMixerTest, TestForwardAuxChannelsToServosWithNoServos)
|
||||||
memset(&servos, 0, sizeof(servos));
|
memset(&servos, 0, sizeof(servos));
|
||||||
servoCount = 0;
|
servoCount = 0;
|
||||||
|
|
||||||
rcData[AUX1] = 1500;
|
rcData[AUX1] = TEST_RC_MID;
|
||||||
rcData[AUX2] = 1500;
|
rcData[AUX2] = TEST_RC_MID;
|
||||||
rcData[AUX3] = 1500;
|
rcData[AUX3] = TEST_RC_MID;
|
||||||
rcData[AUX4] = 1500;
|
rcData[AUX4] = TEST_RC_MID;
|
||||||
|
|
||||||
// when
|
// when
|
||||||
forwardAuxChannelsToServos();
|
forwardAuxChannelsToServos();
|
||||||
|
|
||||||
// then
|
// then
|
||||||
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
EXPECT_EQ(servos[i].value, 0);
|
EXPECT_EQ(0, servos[i].value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -122,10 +129,10 @@ TEST(FlightMixerTest, TestForwardAuxChannelsToServosWithMaxServos)
|
||||||
}
|
}
|
||||||
|
|
||||||
// -1 for zero based offset
|
// -1 for zero based offset
|
||||||
EXPECT_EQ(servos[MAX_SUPPORTED_SERVOS - 3 - 1].value, 1000);
|
EXPECT_EQ(1000, servos[MAX_SUPPORTED_SERVOS - 3 - 1].value);
|
||||||
EXPECT_EQ(servos[MAX_SUPPORTED_SERVOS - 2 - 1].value, 1250);
|
EXPECT_EQ(1250, servos[MAX_SUPPORTED_SERVOS - 2 - 1].value);
|
||||||
EXPECT_EQ(servos[MAX_SUPPORTED_SERVOS - 1 - 1].value, 1750);
|
EXPECT_EQ(1750, servos[MAX_SUPPORTED_SERVOS - 1 - 1].value);
|
||||||
EXPECT_EQ(servos[MAX_SUPPORTED_SERVOS - 0 - 1].value, 2000);
|
EXPECT_EQ(2000, servos[MAX_SUPPORTED_SERVOS - 0 - 1].value);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(FlightMixerTest, TestForwardAuxChannelsToServosWithLessServosThanAuxChannelsToForward)
|
TEST(FlightMixerTest, TestForwardAuxChannelsToServosWithLessServosThanAuxChannelsToForward)
|
||||||
|
@ -149,8 +156,8 @@ TEST(FlightMixerTest, TestForwardAuxChannelsToServosWithLessServosThanAuxChannel
|
||||||
}
|
}
|
||||||
|
|
||||||
// -1 for zero based offset
|
// -1 for zero based offset
|
||||||
EXPECT_EQ(servos[0].value, 1000);
|
EXPECT_EQ(1000, servos[0].value);
|
||||||
EXPECT_EQ(servos[1].value, 1250);
|
EXPECT_EQ(1250, servos[1].value);
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST(FlightMixerTest, TestTricopterServo)
|
TEST(FlightMixerTest, TestTricopterServo)
|
||||||
|
@ -163,7 +170,7 @@ TEST(FlightMixerTest, TestTricopterServo)
|
||||||
|
|
||||||
escAndServoConfig_t escAndServoConfig;
|
escAndServoConfig_t escAndServoConfig;
|
||||||
memset(&escAndServoConfig, 0, sizeof(escAndServoConfig));
|
memset(&escAndServoConfig, 0, sizeof(escAndServoConfig));
|
||||||
escAndServoConfig.mincommand = 1000;
|
escAndServoConfig.mincommand = TEST_MIN_COMMAND;
|
||||||
|
|
||||||
servoParam_t servoConf[MAX_SUPPORTED_SERVOS];
|
servoParam_t servoConf[MAX_SUPPORTED_SERVOS];
|
||||||
memset(&servoConf, 0, sizeof(servoConf));
|
memset(&servoConf, 0, sizeof(servoConf));
|
||||||
|
@ -213,9 +220,67 @@ TEST(FlightMixerTest, TestTricopterServo)
|
||||||
writeServos();
|
writeServos();
|
||||||
|
|
||||||
// then
|
// then
|
||||||
EXPECT_EQ(servos[0].value, 1500);
|
EXPECT_EQ(TEST_SERVO_MID, servos[0].value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST(FlightMixerTest, TestQuadMotors)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
mixerConfig_t mixerConfig;
|
||||||
|
memset(&mixerConfig, 0, sizeof(mixerConfig));
|
||||||
|
|
||||||
|
//servoParam_t servoConf[MAX_SUPPORTED_SERVOS];
|
||||||
|
//memset(&servoConf, 0, sizeof(servoConf));
|
||||||
|
|
||||||
|
escAndServoConfig_t escAndServoConfig;
|
||||||
|
memset(&escAndServoConfig, 0, sizeof(escAndServoConfig));
|
||||||
|
escAndServoConfig.mincommand = TEST_MIN_COMMAND;
|
||||||
|
|
||||||
|
gimbalConfig_t gimbalConfig = {
|
||||||
|
.gimbal_flags = 0
|
||||||
|
};
|
||||||
|
|
||||||
|
mixerUseConfigs(
|
||||||
|
NULL,// servoConf,
|
||||||
|
&gimbalConfig,
|
||||||
|
NULL,
|
||||||
|
&escAndServoConfig,
|
||||||
|
&mixerConfig,
|
||||||
|
NULL,
|
||||||
|
NULL
|
||||||
|
);
|
||||||
|
|
||||||
|
motorMixer_t customMixer[MAX_SUPPORTED_MOTORS];
|
||||||
|
memset(&customMixer, 0, sizeof(customMixer));
|
||||||
|
|
||||||
|
mixerInit(MIXER_QUADX, customMixer);
|
||||||
|
|
||||||
|
// and
|
||||||
|
pwmOutputConfiguration_t pwmOutputConfiguration = {
|
||||||
|
.servoCount = 0,
|
||||||
|
.motorCount = 4
|
||||||
|
};
|
||||||
|
|
||||||
|
mixerUsePWMOutputConfiguration(&pwmOutputConfiguration);
|
||||||
|
|
||||||
|
// and
|
||||||
|
memset(rcCommand, 0, sizeof(rcCommand));
|
||||||
|
|
||||||
|
// and
|
||||||
|
memset(axisPID, 0, sizeof(axisPID));
|
||||||
|
axisPID[YAW] = 0;
|
||||||
|
|
||||||
|
|
||||||
|
// when
|
||||||
|
mixTable();
|
||||||
|
writeMotors();
|
||||||
|
|
||||||
|
// then
|
||||||
|
EXPECT_EQ(TEST_MIN_COMMAND, motors[0].value);
|
||||||
|
EXPECT_EQ(TEST_MIN_COMMAND, motors[1].value);
|
||||||
|
EXPECT_EQ(TEST_MIN_COMMAND, motors[2].value);
|
||||||
|
EXPECT_EQ(TEST_MIN_COMMAND, motors[3].value);
|
||||||
|
}
|
||||||
|
|
||||||
// STUBS
|
// STUBS
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue