1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-18 22:05:15 +03:00

Merge branch 'development' into dzikuvx-nav-cruise-improvements

This commit is contained in:
Pawel Spychalski (DzikuVx) 2020-05-30 10:42:13 +02:00
commit cb0f1e83aa
317 changed files with 5662 additions and 3252 deletions

2
.dockerignore Normal file
View file

@ -0,0 +1,2 @@
.vagrant/
obj/

View file

@ -7,6 +7,19 @@ assignees: ''
---
**PLEASE MAKE SURE YOU READ AND UNDERSTAND THE SOCIAL MEDIA SUPPORT CHANNELS. QUESTIONS ABOUT FLASHING, CONFIGURING, PILOTING MAY BE CLOSED WITHOUT FURTHER INTERACTION.**
* [Telegram channel](https://t.me/INAVFlight)
* [Facebook group](https://www.facebook.com/groups/INAVOfficial)
* [RC Groups thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-%28navigation-rewrite%29-project)
**Please double-check that nobody reported the issue before by using search in this bug tracker.**
**PLEASE DELETE THE TEXT ABOVE AFTER READING AND UNDERSTANDING IT**
****
## Current Behavior
<!-- If applicable, add screenshots, videos and blackbox logs to help explain your problem. -->

View file

@ -1,23 +0,0 @@
---
name: "❓Question"
about: Have a question?
title: ''
labels: ''
assignees: ''
---
For immediate help, just ask your question on one of the following platforms:
* [Telegram channel](https://t.me/INAVFlight)
* [Facebook group](https://www.facebook.com/groups/INAVOfficial)
* [RC Groups thread](https://www.rcgroups.com/forums/showthread.php?2495732-Cleanflight-iNav-%28navigation-rewrite%29-project)
You can also read public documentations or watch video tutorials:
* [Official documentation](https://github.com/iNavFlight/inav/tree/master/docs)
* [Official Wiki](https://github.com/iNavFlight/inav/wiki)
* [Video series by Painless360](https://www.youtube.com/playlist?list=PLYsWjANuAm4qdXEGFSeUhOZ10-H8YTSnH)
* [Video series by Paweł Spychalski](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLloACrA6f1_daCjhqY2x0fB)
* [How to setup INAV on a flying wing](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLn_lCX7UB2OPLzR4w5G4el3)
* [How to setup INAV on a 5" quad](https://www.youtube.com/playlist?list=PLOUQ8o2_nCLl9M6Vm-ZNLMCr6_9yNVHQG)

68
.github/workflows/ci.yml vendored Normal file
View file

@ -0,0 +1,68 @@
name: Build firmware
# Don't enable CI on push, just on PR. If you
# are working on the main repo and want to trigger
# a CI build submit a draft PR.
on: pull_request
jobs:
build:
runs-on: ubuntu-18.04
strategy:
matrix:
start: [0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100]
count: [10]
steps:
- uses: actions/checkout@v2
- name: Setup environment
run: |
# This is the hash of the commit for the PR
# when the action is triggered by PR, empty otherwise
COMMIT_ID=${{ github.event.pull_request.head.sha }}
# This is the hash of the commit when triggered by push
# but the hash of refs/pull/<n>/merge, which is different
# from the hash of the latest commit in the PR, that's
# why we try github.event.pull_request.head.sha first
COMMIT_ID=${COMMIT_ID:-${{ github.sha }}}
BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID})
echo "::set-env name=TARGETS::$(./src/utils/build-targets.sh -n -s ${{ matrix.start }} -c ${{ matrix.count }})"
echo "::set-env name=BUILD_SUFFIX::${BUILD_SUFFIX}"
echo "::set-env name=BUILD_NAME::inav-$(make print_version)-${BUILD_SUFFIX}"
echo "::set-env name=IS_LAST_JOB::$([ $(expr ${{ strategy.job-index }} + 1) = ${{ strategy.job-total }} ] && echo yes)"
- name: Ensure all targets will be tested
if: ${{ env.IS_LAST_JOB }}
run: |
UNTESTED=$(./src/utils/build-targets.sh -n -s $(expr ${{ matrix.start }} + ${{ matrix.count }}) -c 10000)
if ! [ -z "${UNTESTED}" ]; then
echo "Untested targets: ${UNTESTED}" >&2
exit 1
fi
- uses: actions/cache@v1
with:
path: downloads
key: ${{ runner.os }}-downloads-${{ hashFiles('Makefile') }}-${{ hashFiles('**/make/*.mk')}}
- name: Install ARM toolchain
run: make arm_sdk_install
- name: Build targets (${{ matrix.start }})
if: ${{ env.TARGETS }}
run: ./src/utils/build-targets.sh -s ${{ matrix.start }} -c ${{ matrix.count }} -S ${{ env.BUILD_SUFFIX }}
- name: Upload artifacts
if: ${{ env.TARGETS }}
uses: actions/upload-artifact@v2-preview
with:
name: ${{ env.BUILD_NAME }}.zip
path: ./obj/dist/*.hex
test:
needs: [build]
runs-on: ubuntu-18.04
steps:
- uses: actions/checkout@v2
- uses: actions/cache@v1
with:
path: downloads
key: ${{ runner.os }}-downloads-${{ hashFiles('Makefile') }}-${{ hashFiles('**/make/*.mk')}}
- name: Install ARM toolchain
run: make arm_sdk_install
- name: Run Tests
run: make test

View file

@ -4,9 +4,9 @@ FROM ubuntu:bionic
VOLUME /home/src/
WORKDIR /home/src/
ARG TOOLCHAIN_VERSION_SHORT
ENV TOOLCHAIN_VERSION_SHORT ${TOOLCHAIN_VERSION_SHORT:-"8-2018q4"}
ENV TOOLCHAIN_VERSION_SHORT ${TOOLCHAIN_VERSION_SHORT:-"9-2019q4"}
ARG TOOLCHAIN_VERSION_LONG
ENV TOOLCHAIN_VERSION_LONG ${TOOLCHAIN_VERSION_LONG:-"8-2018-q4-major"}
ENV TOOLCHAIN_VERSION_LONG ${TOOLCHAIN_VERSION_LONG:-"9-2019-q4-major"}
# Essentials
RUN mkdir -p /home/src && \
@ -14,10 +14,13 @@ RUN mkdir -p /home/src && \
apt-get install -y software-properties-common ruby make git gcc wget curl bzip2
# Toolchain
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 wget -P /tmp "https://developer.arm.com/-/media/Files/downloads/gnu-rm/$TOOLCHAIN_VERSION_SHORT/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG-x86_64-linux.tar.bz2"
RUN mkdir -p /opt && \
cd /opt && \
tar xvjf "/tmp/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG-linux.tar.bz2" -C /opt && \
tar xvjf "/tmp/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG-x86_64-linux.tar.bz2" -C /opt && \
chmod -R -w "/opt/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG"
ENV PATH="/opt/gcc-arm-none-eabi-$TOOLCHAIN_VERSION_LONG/bin:$PATH"
RUN useradd inav
USER inav

View file

@ -64,8 +64,6 @@ endif
# Things that need to be maintained as the source changes
#
FORKNAME = inav
# Working directories
SRC_DIR := $(ROOT)/src/main
OBJECT_DIR := $(ROOT)/obj/main
@ -85,17 +83,9 @@ MHZ_VALUE ?=
# used for turning on features like VCP and SDCARD
FEATURES =
include $(ROOT)/make/version.mk
include $(ROOT)/make/targets.mk
REVISION = $(shell git rev-parse --short HEAD)
FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
FC_VER_SUFFIX ?=
BUILD_DATE = $(shell date +%Y%m%d)
# Search path for sources
@ -174,12 +164,15 @@ SIZE = $(ARM_SDK_PREFIX)size
# Tool options.
#
# Save original CFLAGS before modifying them, so we don't
# add them twice when calling this Makefile recursively
# for each target
SAVED_CFLAGS := $(CFLAGS)
ifeq ($(DEBUG),GDB)
OPTIMIZE = -O0
LTO_FLAGS = $(OPTIMIZE)
LTO_FLAGS =
else
OPTIMIZE = -Os
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
LTO_FLAGS = -flto -fuse-linker-plugin
endif
ifneq ($(SEMIHOSTING),)
@ -252,9 +245,6 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
# Things we will build
#
TARGET_BIN := $(BIN_DIR)/$(FORKNAME)_$(FC_VER)
ifneq ($(FC_VER_SUFFIX),)
TARGET_BIN := $(TARGET_BIN)-$(FC_VER_SUFFIX)
endif
TARGET_BIN := $(TARGET_BIN)_$(TARGET)
ifneq ($(BUILD_SUFFIX),)
TARGET_BIN := $(TARGET_BIN)_$(BUILD_SUFFIX)
@ -301,16 +291,38 @@ $(TARGET_ELF): $(TARGET_OBJS)
$(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(LDFLAGS)
$(V0) $(SIZE) $(TARGET_ELF)
OPTIMIZE_FLAG_SPEED := "-Os"
OPTIMIZE_FLAG_SIZE := "-Os"
OPTIMIZE_FLAG_NORMAL := "-Os"
ifneq ($(TARGET_MCU_GROUP), STM32F3)
OPTIMIZE_FLAG_SPEED := "-Ofast"
OPTIMIZE_FLAG_SIZE := "-Os"
OPTIMIZE_FLAG_NORMAL := "-O2"
endif
define compile_file
echo "%% $(1) $(2) $<" "$(STDOUT)" && \
$(CROSS_CC) -c -o $@ $(CFLAGS) $(2) $<
endef
# Compile
$(TARGET_OBJ_DIR)/%.o: %.c
$(V1) mkdir -p $(dir $@)
$(V1) echo %% $(notdir $<) "$(STDOUT)"
$(V1) $(CROSS_CC) -c -o $@ $(CFLAGS) $<
$(V1) $(if $(findstring $<,$(SIZE_OPTIMISED_SRC)), \
$(call compile_file,(size),$(OPTIMIZE_FLAG_SIZE)) \
, \
$(if $(findstring $<,$(SPEED_OPTIMISED_SRC)), \
$(call compile_file,(speed),$(OPTIMIZE_FLAG_SPEED)) \
, \
$(call compile_file,(normal),$(OPTIMIZE_FLAG_NORMAL)) \
) \
)
ifeq ($(GENERATE_ASM), 1)
$(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $<
endif
# Assemble
$(TARGET_OBJ_DIR)/%.o: %.s
$(V1) mkdir -p $(dir $@)
@ -340,7 +352,7 @@ release: $(RELEASE_TARGETS)
$(VALID_TARGETS):
$(V0) echo "" && \
echo "Building $@" && \
$(MAKE) -j 8 TARGET=$@ && \
CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$@ && \
echo "Building $@ succeeded."
## clean : clean up all temporary / machine-generated files

View file

@ -1,5 +1,9 @@
# INAV - navigation capable flight controller
## F3 based flight controllers
> STM32 F3 flight controllers like Omnibus F3 or SP Racing F3 are deprecated and soon they will reach the end of support in INAV. If you are still using F3 boards, please migrate to F4 or F7.
![INAV](http://static.rcgroups.net/forums/attachments/6/1/0/3/7/6/a9088858-102-inav.png)
![Travis CI status](https://travis-ci.org/iNavFlight/inav.svg?branch=master)

View file

@ -30,7 +30,7 @@ For most hobby-sized airplanes roll/pitch rate limits should be in range 70-120
Other things to check:
* It's highly recommended that you fly in PASTHROUGH and trim your servo midpoints for stable flight
* It's highly recommended that you fly in MANUAL and trim your servo midpoints for stable flight
* Make sure you have center of gravity according to manual to your aircraft
* Check that your failsafe activates correctly (test on the ground with propeller off for safety)
@ -54,6 +54,6 @@ The more you fly the better it will get. Let autotune analyze how your airplane
## Completing the tune
Once you have tuned reasonable PIFF parameters with AUTOTUNE you should complete the tune by switching out of AUTOTUNE to ANGLE or PASTHROUGH and landing the airplane.
Once you have tuned reasonable PIFF parameters with AUTOTUNE you should complete the tune by switching out of AUTOTUNE to ANGLE or MANUAL and landing the airplane.
Note that AUTOTUNE mode doesn't automatically save parameters to EEPROM. You need to disarm and issue a [stick command](Controls.md) to save configuration parameters.

View file

@ -26,7 +26,7 @@ On the first battery connection is always advisable to use a current limiter dev
### Sparky
See the [Sparky board chapter](Board - Sparky.md).
See the [Sparky board chapter](Board%20-%20Sparky.md).
## Voltage measurement

View file

@ -22,7 +22,7 @@ Full details on the MATEKSYS F722-SE can be found on the Matek Website: [mateksy
### Integrated PDB Specs
* *Input:* 6-36v (3-8S LiPo) w/TVS protection
* *Input:* 6-36v (2-8S LiPo) w/TVS protection
* *ESC Pads:* Rated 4x30A per ESC pad set (4x46A burst)
* Voltage Regulators:
* *5v BEC:* 2A continuous load (3A burst)

View file

@ -152,7 +152,7 @@ A shorter form is also supported to enable and disable functions using `serial <
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
| reboot_character | 82 | Special character used to trigger reboot |
| gps_provider | UBLOX | Which GPS protocol to be used |
| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). |
| gps_sbas_mode | NONE | Which SBAS mode to be used |
| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. |
| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. |
@ -163,7 +163,7 @@ A shorter form is also supported to enable and disable functions using `serial <
| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. |
| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. |
| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) |
| inav_reset_home | EACH_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM |
| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM |
| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] |
| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate |
| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes |
@ -215,6 +215,7 @@ A shorter form is also supported to enable and disable functions using `serial <
| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) |
| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error |
| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] |
| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] |
| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s |
@ -231,6 +232,7 @@ A shorter form is also supported to enable and disable functions using `serial <
| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. |
| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees |
| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]|
| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing |
| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire |
| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). |
@ -291,6 +293,7 @@ A shorter form is also supported to enable and disable functions using `serial <
| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] |
| yaw_motor_direction | 1 | Use if you need to inverse yaw motor direction. |
| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. |
| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) |
| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] |
| servo_center_pulse | 1500 | Servo midpoint |
| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. |
@ -339,12 +342,15 @@ A shorter form is also supported to enable and disable functions using `serial <
| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) |
| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) |
| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) |
| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. |
| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe |
| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` |
| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. |
| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON |
| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
@ -369,6 +375,9 @@ A shorter form is also supported to enable and disable functions using `serial <
| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH |
| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing) |
| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing) |
| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing) |
| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) |
| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) |
| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |

View file

@ -26,6 +26,8 @@ _Global Functions_ (abbr. GF) are a mechanism allowing to override certain fligh
| 5 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
| 6 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
| 7 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
| 8 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
| 8 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
## Flags

View file

@ -13,6 +13,7 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL
* `<rule>` - ID of Logic Condition rule
* `<enabled>` - `0` evaluates as disabled, `1` evaluates as enabled
* `<activatorId>` - the ID of _LogicCondition_ used to activate this _Condition_. _Logic Condition_ will be evaluated only then Activator evaluates as `true`. `-1` evaluates as `true`
* `<operation>` - See `Operations` paragraph
* `<operand A type>` - See `Operands` paragraph
* `<operand A value>` - See `Operands` paragraph

View file

@ -82,7 +82,7 @@ Each servo mixing rule has the following parameters:
| 26 | Stabilized PITCH- | Clipped between -1000 and 0 |
| 27 | Stabilized YAW+ | Clipped between 0 and 1000 |
| 28 | Stabilized YAW- | Clipped between -1000 and 0 |
| 29 | One | Constant value of 500 |
| 29 | MAX | Constant value of 500 |
The `smix reset` command removes all the existing motor mixing rules.

View file

@ -1,6 +1,6 @@
# Navigation
Navigation system in INAV is responsible for assisting the pilot allowing altitude and position hold, return-to-home and waypoint flight.
The navigation system in INAV is responsible for assisting the pilot allowing altitude and position hold, return-to-home and waypoint flight.
## NAV ALTHOLD mode - altitude hold
@ -23,7 +23,7 @@ Throttle tilt compensation attempts to maintain constant vertical thrust when co
## NAV POSHOLD mode - position hold
Position hold requires GPS, accelerometer and compass sensors. Flight modes that require a compass (POSHOLD, RTH) are locked until compass is properly calibrated.
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). Can be activated together with ALTHOLD to get a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
When activated, this mode will attempt to keep copter where it is (based on GPS coordinates). From inav 2.0, POSHOLD is a full 3D position hold. Heading hold in this mode is assumed and activated automatically.
### CLI parameters affecting ALTHOLD mode:
* *nav_user_control_mode* - can be set to "0" (GPS_ATTI) or "1" (GPS_CRUISE), controls how firmware will respond to roll/pitch stick movement. When in GPS_ATTI mode, right stick controls attitude, when it is released, new position is recorded and held. When in GPS_CRUISE mode right stick controls velocity and firmware calculates required attitude on its own.
@ -36,7 +36,7 @@ PID meaning:
## NAV RTH - return to home mode
Home for RTH is position, where copter was armed. RTH requires accelerometer, compass and GPS sensors.
Home for RTH is the position where vehicle was armed. This position may be offset by the CLI settings `nav_rth_home_offset_distance` and `nav_rth_home_offset_direction`. RTH requires accelerometer, compass and GPS sensors.
If barometer is NOT present, RTH will fly directly to home, altitude control here is up to pilot.
@ -54,11 +54,17 @@ When deciding what altitude to maintain, RTH has 4 different modes of operation
`wp load` - Load list of waypoints from EEPROM to FC.
`wp <n> <action> <lat> <lon> <alt> <p1> <flag>` - Set parameters of waypoint with index `<n>`.
`wp <n> <action> <lat> <lon> <alt> <p1> <p2> <p3> <flag>` - Set parameters of waypoint with index `<n>`. Note that prior to inav 2.5, the `p2` and `p3` parameters were not required. From 2.5, inav will accept either version but always saves and lists the later full version.
Parameters:
* `<action>` - When 0 then waypoint is not used, when 1 then it is normal waypoint, when 4 then it is RTH.
* `<action>` - The action to be taken at the WP. The following are enumerations are available in inav 2.5 and later:
* 0 - Unused / Unassigned
* 1 - WAYPOINT
* 3 - POSHOLD_TIME
* 4 - RTH
* 6 - JUMP
* 8 - LAND
* `<lat>` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789).
@ -66,10 +72,39 @@ Parameters:
* `<alt>` - Altitude in cm.
* `<p1>` - For a "RTH waypoint" p1 > 0 alow landing. For a normal waypoint it means speed to this waypoint, it is taken into account only for multicopters and when > 50 and < nav_auto_speed.
* `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number).
* `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP.
* `<p3>` - Reserved for future use. If `p2` is provided, then `p3` is also required.
* `<flag>` - Last waypoint must have set `flag` to 165 (0xA5), otherwise 0.
`wp save` - Checks list of waypoints and save from FC to EEPROM (warning: it also saves all unsaved CLI settings like normal `save`).
`wp reset` - Resets the list, sets the waypoints number to 0 and mark it as invalid (but doesn't delete the waypoints).
`wp reset` - Resets the list, sets the number of waypoints to 0 and marks the list as invalid (but doesn't delete the waypoint definitions).
### `wp` example
```
# wp load
# wp
#wp 11 valid
wp 0 1 543533193 -45179273 3500 0 0 0 0
wp 1 1 543535723 -45193913 3500 0 0 0 0
wp 2 1 543544541 -45196617 5000 0 0 0 0
wp 3 1 543546578 -45186895 5000 0 0 0 0
wp 4 6 0 0 0 1 2 0 0
wp 5 1 543546688 -45176009 3500 0 0 0 0
wp 6 1 543541225 -45172673 3500 0 0 0 0
wp 7 6 0 0 0 0 1 0 0
wp 8 3 543531383 -45190405 3500 45 0 0 0
wp 9 1 543548470 -45182104 3500 0 0 0 0
wp 10 8 543540521 -45178091 6000 0 0 0 165
wp 11 0 0 0 0 0 0 0 0
...
wp 59 0 0 0 0 0 0 0 0
```
Note that the `wp` CLI command shows waypoint list indices, while the MW-XML definition used by mwp, ezgui and the configurator use WP numbers.

View file

@ -83,6 +83,22 @@ The bug prevents use of all 16 channels. Upgrade to the latest OpenTX version t
without the fix you are limited to 8 channels regardless of the CH1-16/D16 settings.
### F.Port
F.Port is a protocol running on async serial allowing 16 controls channels and telemetry on a single UART.
Supported receivers include FrSky R-XSR, X4R, X4R-SB, XSR, XSR-M, R9M Slim, R9M Slim+, R9 Mini. For ACCST receivers you need to flash the corresponding firmware for it to output F.Port. For ACCESS receivers the protocol output from the receiver can be switched between S.Bus and F.Port from the model's setup page in the RX options.
#### Connection
Just connect the S.Port wire from the receiver to the TX pad of a free UART on your flight controller
#### Configuration
```
set serialrx_inverted = true
set serialrx_halfduplex = true
```
### XBUS

View file

@ -120,7 +120,7 @@ The following sensors are transmitted
* **0420** : distance to GPS home fix, in meters
* **0430** : if `frsky_pitch_roll = ON` set this will be pitch degrees*10
* **0440** : if `frsky_pitch_roll = ON` set this will be roll degrees*10
* **0450** : 'Flight Path Vector' or 'Course over ground' in degrees*10
### Compatible SmartPort/INAV telemetry flight status
To quickly and easily monitor these SmartPort sensors and flight modes, install [iNav LuaTelemetry](https://github.com/iNavFlight/LuaTelemetry) to your Taranis Q X7, X9D, X9D+ or X9E transmitter.

View file

@ -1,24 +1,34 @@
# Building with Docker
Building in Docker is remarkably easy.
Building with [Docker](https://www.docker.com/) is remarkably easy: an isolated container will hold all the needed compilation tools so that they won't interfere with your system and you won't need to install and manage them by yourself. You'll only need to have Docker itself [installed](https://docs.docker.com/install/).
## Build a container with toolchain
The first time that you'll run a build it will take a little more time than following executions since it will be building its base image first. Once this initial process is completed, the firmware will be always built immediately.
If you want to start from scratch - _even if that's rarely needed_ - delete the `inav-build` image on your system (`docker image rm inav-build`).
## Linux
In the repo's root, run:
```
docker build -t inav-build .
./build.sh <TARGET>
```
## Building firmware with Docker on Ubuntu
Where `<TARGET>` must be replaced with the name of the target that you want to build. For example:
Build specified target
```
sh build.sh SPRACINGF3
./build.sh MATEKF405SE
```
## Building firmware with Docker on Windows 10
## Windows 10
Path in Docker on Windows works in a _strange_ way, so you have to provide full path for `docker run` command. For example:
Docker on Windows requires full paths for mounting volumes in `docker run` commands. For example: `c:\Users\pspyc\Documents\Projects\inav` becomes `//c/Users/pspyc/Documents/Projects/inav` .
`docker run --rm -v //c/Users/pspyc/Documents/Projects/inav:/home/src/ inav-build make TARGET=AIRBOTF4`
You'll have to manually execute the same steps that the build script does:
So, `c:\Users\pspyc\Documents\Projects\inav` becomes `//c/Users/pspyc/Documents/Projects/inav`
1. `docker build -t inav-build .`
+ This step is only needed the first time.
2. `docker run --rm -v <PATH_TO_REPO>:/home/src/ inav-build make TARGET=<TARGET>`
+ Where `<PATH_TO_REPO>` must be replaced with the absolute path of where you cloned this repo (see above), and `<TARGET>` with the name of the target that you want to build.
Refer to the [Linux](#Linux) instructions or the [build script](/build.sh) for more details.

View file

@ -1,111 +0,0 @@
# Building in Ubuntu
iNav requires a reasonably modern `gcc-arm-none-eabi` compiler. As a consequence of the long term support options in Ubuntu, it is possible that the distribution compiler will be too old to build iNav firmware. For example, Ubuntu 16.04 LTS ships with version 4.9.3 which cannot compile contemporary iNav.
As of August 2018, the recommendation for Ubuntu releases is:
| Release | Compiler Source |
| ------- | --------------- |
| 16.04 or earlier | Use the 'official' PPA |
| 17.10 | Use the 'official' PPA as the distro compiler (5.4) *may* be too old |
| 18.04 | Use the 'official' PPA, as the distro compiler (6.3) was broken when last tested |
For Ubuntu derivatives (ElementaryOS, Mint etc.), please check the distro provided version, and if it's lower than 6, use the PPA.
e.g. ElementaryOS
```
$ apt show gcc-arm-none-eabi
...
Version: 15:4.9.3+svn231177-1
```
This 4.9.3 and will not build iNav, so we need the PPA.
## Installer commands
Older versions of Debian / Ubuntu and derivatives use the `apt-get` command; newer versions use `apt`. Use the appropriate command for your release.
# Prerequisites
Regardless of the cross-compiler version, it is necessary to install some other tools:
```
sudo apt install git
sudo apt install gcc
sudo apt install ruby
```
A ruby release of at least 2 or later is recommended, if your release only provides 1.9, it is necessary to install a later version:
```
sudo apt-get remove ruby
sudo apt-add-repository ppa:brightbox/ruby-ng
sudo apt-get update
sudo apt-get install ruby2.4 ruby2.4-dev
```
# Using the Distro compiler
In case Ubuntu ever provides a modern compiler (as of August 2018, not recommended):
```
sudo apt install gcc-arm-none-eabi
```
# Using the PPA compiler
The PPA compiler is recommended for all cases:
```
sudo apt-get remove binutils-arm-none-eabi gcc-arm-none-eabi
sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa
sudo apt-get update
sudo apt-get install gcc-arm-embedded
```
After these steps, on Ubuntu 16.04, (at least of March 2018) you should now have:
```
$ arm-none-eabi-gcc -dumpversion
7.2.1
```
Which is more than adequate for our purposes.
# Building from the Github repository
After the ARM cross-compiler toolchain from is installed, you should be able to build from source.
```
mkdir src
cd src
git clone https://github.com/iNavFlight/inav.git
cd inav
make
```
If you have a github account with registered ssh key you can replace the `git clone` command with `git clone git@github.com:iNavFlight/inav.git` instead of the https link.
By default, this builds the REVO target, to build another target, specify the target name to the make command, for example:
```
make TARGET=MATEKF405
```
The resultant hex file are in the `obj/` directory.
You can use the INAV Configurator to flash the local ```obj/inav_TARGET.hex``` file, or use `stm32flash` or `dfu-util` directly from the command line.
[msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing.
# Updating and rebuilding
In order to update your local firmware build:
* Navigate to the local iNav repository
* Use the following steps to pull the latest changes and rebuild your local version of iNav:
```
cd src/inav
git pull
make TARGET=<TARGET>
```

View file

@ -74,7 +74,7 @@ If the CLI `log_topics` is non-zero, then all topics matching the mask will be d
## Code usage
A set of macros `LOG_S()` (log system) through `LOG_D()` (log debug) may be used, subject to compile time log level constraints. These provide `printf` style logging for a given topic.
A set of macros `LOG_E()` (log error) through `LOG_D()` (log debug) may be used, subject to compile time log level constraints. These provide `printf` style logging for a given topic.
```
// LOG_D(topic, fmt, ...)

View file

@ -2,35 +2,38 @@
## Our Pledge
In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation.
We as members, contributors, and leaders pledge to make participation in our community a harassment-free experience for everyone, regardless of age, body size, visible or invisible disability, ethnicity, sex characteristics, gender identity and expression, level of experience, education, socio-economic status, nationality, personal appearance, race, religion, or sexual identity and orientation.
We pledge to act and interact in ways that contribute to an open, welcoming, diverse, inclusive, and healthy community.
## Our Standards
Examples of behavior that contributes to creating a positive environment include:
Examples of behavior that contributes to creating a positive environment include but are not limited to:
* Using welcoming and inclusive language
* Being respectful of differing viewpoints and experiences
* Gracefully accepting constructive criticism
* Focusing on what is best for the community
* Showing empathy towards other community members
* Demonstrating empathy and kindness toward other people
* Being respectful of differing opinions, viewpoints, and experiences
* Giving and gracefully accepting constructive feedback
* Accepting responsibility and apologizing to those affected by our mistakes, and learning from the experience
* Focusing on what is best not just for us as individuals, but for the overall community
Examples of unacceptable behavior by participants include:
Examples of unacceptable behavior include but are not limited to:
* The use of sexualized language or imagery and unwelcome sexual attention or advances
* Trolling, insulting/derogatory comments, and personal or political attacks
* The use of sexualized language or imagery, and sexual attention or advances of any kind
* Trolling, insulting or derogatory comments, and personal or political attacks
* Public or private harassment
* Publishing others' private information, such as a physical or electronic address, without explicit permission
* Publishing others private information, such as a physical or email address, without their explicit permission
* Other conduct which could reasonably be considered inappropriate in a professional setting
* Acts of unacceptable behavior on other public resources outside of but in relation to this project
## Our Responsibilities
Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior.
Project maintainers and community leaders are responsible for clarifying and enforcing our standards of acceptable behavior and will take appropriate and fair corrective action in response to any behavior that they deem inappropriate, threatening, offensive, or harmful.
Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful.
Project maintainers and community leaders have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, and will communicate reasons for moderation decisions when appropriate.
## Scope
This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers.
This Code of Conduct applies within all community spaces, and also applies when an individual is officially representing the community in public spaces. Examples of representing our community include using an official e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event.
## Enforcement
@ -40,7 +43,7 @@ Project maintainers who do not follow or enforce the Code of Conduct in good fai
## Attribution
This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [http://contributor-covenant.org/version/1/4][version]
This Code of Conduct is adapted from the [Contributor Covenant][homepage],
version 2.0, available at https://www.contributor-covenant.org/version/2/0/code_of_conduct.html.
[homepage]: http://contributor-covenant.org
[version]: http://contributor-covenant.org/version/1/4/

View file

@ -1,4 +1,4 @@
# INAV New Hardware policies
# INAV Hardware Policy
## General
@ -10,33 +10,42 @@ To prevent explosive growth of different target and feature count and ensure rea
"Hardware" - physical hardware requiring support from firmware side.
"Requester" - manufacturer or community member seeking addition of new hardware or target
## New target additions
New targets are accepted into INAV code if any of the following conditions is satisfied:
1. Board manufacturer provides specs, schematics and production samples are provided to at least two core developers. In this case the new target becomes part of official INAV release.
1. Requester is a manufacturer of the hardware or an affiliated community member. Requester provides specs, schematics and production samples are provided to at least two core developers. In this case the new target becomes part of official INAV release.
2. Community member or board manufacturer provides board samples to at least one core developer and the target already exists in official Cleanflight or Betaflight firmware. In this case the new target may or may not become part of official release based on the decision made by core developers.
2. Requester is a community member not affiliated with a manufacturer of the hardware. Requester provides board samples to at least one core developer and the target is already supported in official Cleanflight or Betaflight firmware. In this case the new target may or may not become part of official release based on the decision made by core developers.
# New hardware support
3. The new target must meet the following minimal requirements:
* On-board sensors include at least the IMU (gyroscope + accelerometer)
* At least 2 hardware serial ports are available with both TX and RX pins
* At least 512K of firmware flash memory and at least of 64K of RAM available
* At least one I2C bus broken out (SCL and SDA pins) and not shared with other functions
## New hardware support
For the hardware which does not require a new target, but still require support from the firmware side the following rules apply:
1. Hardware manufacturer provides specs and production samples for the unsupported hardware to at least two core developers.
1. Requester is a manufacturer of the hardware or an affiliated community member. Requester provides specs and production samples for the unsupported hardware to at least two core developers.
2. Community member or hardware manufacturer provides hardware samples to at least one core developer and the firmware support already exists in official Cleanflight or Betaflight firmware.
2. Requester is a community member not affiliated with a manufacturer of the hardware. Requester provides hardware samples to at least one core developer and the firmware support already exists in official Cleanflight or Betaflight firmware.
# Using own hardware exception
## Using own hardware exception
If one of the core developers has the hardware in possession they may opt in and submit support for it anyway. In this case the support is not official and is generally not included in official releases.
If one of the core developers has the hardware in possession they may opt in and submit support for it anyway. In this case the support is not official and may not be included in official releases.
# Providing samples to developers
## Providing samples to developers
1. Hardware provided to the developers would be considered a donation to the INAV project. Under no circumstances developer will be obliged to return the hardware.
1. Hardware provided to the developers would be considered a donation to the INAV project. Under no circumstances developer will be obliged to return the hardware or pay for it.
2. Manufacturer or community member providing the hardware bears all the costs of the hardware, delivery and VAT/customs duties. Hardware manufacturer also assumes the responsibility to provide up to date specs, documentation and firmware (if applicable).
2. Requester bears all the costs of the hardware, delivery and VAT/customs duties. Hardware manufacturer also assumes the responsibility to provide up to date specs, documentation and firmware (if applicable).
3. Before sending samples the providing party should reach out to developers and agree on specific terms of implementing support for the unsupported hardware. Developers may place additional requirements on a case by case basis and at their sole discretion.
3. Before sending samples the Requester should reach out to developers and agree on specific terms of implementing support for the unsupported hardware. Developers may place additional requirements on a case by case basis and at their sole discretion.
4. The new target and new hardware policies do not apply in the following cases. Developers may still chose to apply the "own hardware exception" at their own discretion.
@ -46,4 +55,16 @@ If one of the core developers has the hardware in possession they may opt in and
5. It's advised to provide more than one sample to avoid issues with damaged or dead on arrival hardware.
## Implementing support for the new target or hardware
1. Pull request to add the new target or hardware may be authored by a contributor outside INAV team or by one of the core developers.
2. There is no obligation to accept a pull request made by an outside contributor. INAV team reserves the right to reject that pull request and re-implement the support or take that pull request as a baseline and amend it.
3. INAV team reserves the right to reject the new target or hardware or remove the support for an unforeseen reason including, but not limited to violation of [INAV Code of Conduct](CODE_OF_CONDUCT.md) by the manufacturer or an affiliated outside contributor.
## Guidelines on contacting the team
1. Requester is advised to open a feature request to add support for certain hardware to INAV by following [this link](https://github.com/iNavFlight/inav/issues/new/choose)
2. After opening a feature request, Requester is advised to contact the core development team by [email](mailto:coredev@inavflight.com) mentioning the open feature request and communicate with developer team via email to arrange hardware and specifications delivery.

View file

@ -29,7 +29,6 @@ EXCLUDES = stm32f4xx_crc.c \
stm32f4xx_cryp_aes.c \
stm32f4xx_hash_md5.c \
stm32f4xx_cryp_des.c \
stm32f4xx_rtc.c \
stm32f4xx_hash.c \
stm32f4xx_dbgmcu.c \
stm32f4xx_cryp_tdes.c \

View file

@ -37,8 +37,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_hal_nor.c \
stm32f7xx_hal_qspi.c \
stm32f7xx_hal_rng.c \
stm32f7xx_hal_rtc.c \
stm32f7xx_hal_rtc_ex.c \
stm32f7xx_hal_sai.c \
stm32f7xx_hal_sai_ex.c \
stm32f7xx_hal_sd.c \

View file

@ -1,6 +1,6 @@
RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD
RELEASE_TARGETS += LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405
RELEASE_TARGETS += LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL
RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO
RELEASE_TARGETS += ALIENFLIGHTNGF7
@ -10,7 +10,7 @@ RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV
RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL
RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2
RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7
RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2
RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7

View file

@ -16,6 +16,7 @@ COMMON_SRC = \
common/log.c \
common/logic_condition.c \
common/global_functions.c \
common/global_variables.c \
common/maths.c \
common/memory.c \
common/olc.c \
@ -43,8 +44,10 @@ COMMON_SRC = \
drivers/exti.c \
drivers/io.c \
drivers/io_pca9685.c \
drivers/irlock.c \
drivers/light_led.c \
drivers/osd.c \
drivers/persistent.c \
drivers/resource.c \
drivers/rx_nrf24l01.c \
drivers/rx_spi.c \
@ -62,7 +65,9 @@ COMMON_SRC = \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
drivers/time.c \
drivers/timer.c \
drivers/usb_msc.c \
drivers/lights_io.c \
drivers/1-wire.c \
drivers/1-wire/ds_crc.c \
@ -101,6 +106,7 @@ COMMON_SRC = \
flight/dynamic_gyro_notch.c \
io/beeper.c \
io/esc_serialshot.c \
io/servo_sbus.c \
io/frsky_osd.c \
io/osd_dji_hd.c \
io/lights.c \
@ -127,6 +133,7 @@ COMMON_SRC = \
rx/nrf24_syma.c \
rx/nrf24_v202.c \
rx/pwm.c \
rx/frsky_crc.c \
rx/rx.c \
rx/rx_spi.c \
rx/sbus.c \
@ -139,13 +146,14 @@ COMMON_SRC = \
scheduler/scheduler.c \
sensors/acceleration.c \
sensors/battery.c \
sensors/temperature.c \
sensors/boardalignment.c \
sensors/compass.c \
sensors/diagnostics.c \
sensors/gyro.c \
sensors/initialisation.c \
sensors/esc_sensor.c \
sensors/irlock.c \
sensors/temperature.c \
uav_interconnect/uav_interconnect_bus.c \
uav_interconnect/uav_interconnect_rangefinder.c \
blackbox/blackbox.c \
@ -200,6 +208,7 @@ COMMON_SRC = \
navigation/navigation_pos_estimator.c \
navigation/navigation_pos_estimator_agl.c \
navigation/navigation_pos_estimator_flow.c \
navigation/navigation_rover_boat.c \
sensors/barometer.c \
sensors/pitotmeter.c \
sensors/rangefinder.c \
@ -234,6 +243,7 @@ TARGET_SRC := $(filter-out $(MCU_EXCLUDES), $(TARGET_SRC))
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
TARGET_SRC += \
drivers/flash.c \
drivers/flash_m25p16.c \
io/flashfs.c \
$(MSC_SRC)
@ -268,7 +278,6 @@ TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_cfft_f32.c
TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_rfft_fast_init_f32.c
TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_cfft_radix8_f32.c
TARGET_SRC += $(DSP_LIB)/Source/CommonTables/arm_common_tables.c
TARGET_SRC += $(DSP_LIB)/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
TARGET_SRC += $(DSP_LIB)/Source/StatisticsFunctions/arm_max_f32.c
@ -277,3 +286,14 @@ endif
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
SIZE_OPTIMISED_SRC := ""
SPEED_OPTIMISED_SRC := ""
ifneq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
# SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
# ./src/main/common/filter.c \
# SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
# ./src/main/common/maths.c \
endif #!F3

View file

@ -18,6 +18,13 @@ ifeq ($(UNAME), Linux)
LINUX := 1
endif
# FreeBSD
ifeq ($(UNAME), FreeBSD)
OSFAMILY := linux
LINUX := 1
endif
# Mac OSX
ifeq ($(UNAME), Darwin)
OSFAMILY := macosx

View file

@ -32,9 +32,20 @@ ifdef WINDOWS
endif
ARM_SDK_FILE := $(notdir $(ARM_SDK_URL))
ARM_SDK_DOWNLOAD_PATH := $(DL_DIR)/$(ARM_SDK_FILE)
SDK_INSTALL_MARKER := $(ARM_SDK_DIR)/bin/arm-none-eabi-gcc-$(GCC_REQUIRED_VERSION)
.PHONY: arm_sdk_print_filename
arm_sdk_print_filename:
@echo $(ARM_SDK_FILE)
.PHONY: arm_sdk_print_download_path
arm_sdk_print_download_path:
@echo $(ARM_SDK_DOWNLOAD_PATH)
arm_sdk_install: | $(TOOLS_DIR)
arm_sdk_install: arm_sdk_download $(SDK_INSTALL_MARKER)
@ -42,17 +53,17 @@ arm_sdk_install: arm_sdk_download $(SDK_INSTALL_MARKER)
$(SDK_INSTALL_MARKER):
ifneq ($(OSFAMILY), windows)
# binary only release so just extract it
$(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)"
$(V1) tar -C $(TOOLS_DIR) -xjf "$(ARM_SDK_DOWNLOAD_PATH)"
else
$(V1) unzip -q -d $(ARM_SDK_DIR) "$(DL_DIR)/$(ARM_SDK_FILE)"
$(V1) unzip -q -d $(ARM_SDK_DIR) "$(ARM_SDK_DOWNLOAD_PATH)"
endif
.PHONY: arm_sdk_download
arm_sdk_download: | $(DL_DIR)
arm_sdk_download: $(DL_DIR)/$(ARM_SDK_FILE)
$(DL_DIR)/$(ARM_SDK_FILE):
arm_sdk_download: $(ARM_SDK_DOWNLOAD_PATH)
$(ARM_SDK_DOWNLOAD_PATH):
# download the source only if it's newer than what we already have
$(V1) curl -L -k -o "$(DL_DIR)/$(ARM_SDK_FILE)" -z "$(DL_DIR)/$(ARM_SDK_FILE)" "$(ARM_SDK_URL)"
$(V1) curl -L -k -o "$(ARM_SDK_DOWNLOAD_PATH)" -z "$(ARM_SDK_DOWNLOAD_PATH)" "$(ARM_SDK_URL)"
## arm_sdk_clean : Uninstall Arm SDK
@ -69,7 +80,7 @@ arm_sdk_clean:
ifeq ($(shell [ -d "$(ARM_SDK_DIR)" ] && echo "exists"), exists)
ARM_SDK_PREFIX := $(ARM_SDK_DIR)/bin/arm-none-eabi-
else ifeq (,$(findstring _install,$(MAKECMDGOALS)))
else ifeq (,$(findstring print_,$(MAKECMDGOALS))$(filter targets,$(MAKECMDGOALS))$(findstring arm_sdk,$(MAKECMDGOALS)))
GCC_VERSION = $(shell arm-none-eabi-gcc -dumpversion)
ifeq ($(GCC_VERSION),)
$(error **ERROR** arm-none-eabi-gcc not in the PATH. Run 'make arm_sdk_install' to install automatically in the tools folder of this repo)

18
make/version.mk Normal file
View file

@ -0,0 +1,18 @@
FORKNAME := inav
FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' )
FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' )
FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH)
FC_VER_SUFFIX ?=
ifneq ($(FC_VER_SUFFIX),)
FC_VER += -$(FC_VER_SUFFIX)
endif
REVISION := $(shell git rev-parse --short HEAD)
.PHONY: print_version
print_version:
@echo $(FC_VER)

View file

@ -77,6 +77,7 @@
#include "sensors/pitotmeter.h"
#include "sensors/rangefinder.h"
#include "sensors/sensors.h"
#include "sensors/esc_sensor.h"
#include "flight/wind_estimator.h"
#include "sensors/temperature.h"
@ -390,6 +391,10 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
{"sens6Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)},
{"sens7Temp", -1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)},
#endif
#ifdef USE_ESC_SENSOR
{"escRPM", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
{"escTemperature", -1, SIGNED, PREDICT(PREVIOUS), ENCODING(SIGNED_VB)},
#endif
};
typedef enum BlackboxState {
@ -498,6 +503,10 @@ typedef struct blackboxSlowState_s {
#ifdef USE_TEMPERATURE_SENSOR
int16_t tempSensorTemperature[MAX_TEMP_SENSORS];
#endif
#ifdef USE_ESC_SENSOR
uint32_t escRPM;
int8_t escTemperature;
#endif
} __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
//From rc_controls.c
@ -866,7 +875,7 @@ static void writeIntraframe(void)
blackboxLoggedAnyFrames = true;
}
static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHistory, int count)
static void blackboxWriteArrayUsingAveragePredictor16(int arrOffsetInHistory, int count)
{
int16_t *curr = (int16_t*) ((char*) (blackboxHistory[0]) + arrOffsetInHistory);
int16_t *prev1 = (int16_t*) ((char*) (blackboxHistory[1]) + arrOffsetInHistory);
@ -880,6 +889,20 @@ static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHist
}
}
static void blackboxWriteArrayUsingAveragePredictor32(int arrOffsetInHistory, int count)
{
int32_t *curr = (int32_t*) ((char*) (blackboxHistory[0]) + arrOffsetInHistory);
int32_t *prev1 = (int32_t*) ((char*) (blackboxHistory[1]) + arrOffsetInHistory);
int32_t *prev2 = (int32_t*) ((char*) (blackboxHistory[2]) + arrOffsetInHistory);
for (int i = 0; i < count; i++) {
// Predictor is the average of the previous two history states
int32_t predictor = ((int64_t)prev1[i] + (int64_t)prev2[i]) / 2;
blackboxWriteSignedVB(curr[i] - predictor);
}
}
static void writeInterframe(void)
{
blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
@ -1014,16 +1037,16 @@ static void writeInterframe(void)
blackboxWriteTag8_8SVB(deltas, optionalFieldCount);
//Since gyros, accs and motors are noisy, base their predictions on the average of the history:
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, attitude), XYZ_AXIS_COUNT);
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, attitude), XYZ_AXIS_COUNT);
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT);
blackboxWriteArrayUsingAveragePredictor32(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT);
}
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, motor), getMotorCount());
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, motor), getMotorCount());
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SERVOS)) {
blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS);
blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, servo), MAX_SUPPORTED_SERVOS);
}
#ifdef NAV_BLACKBOX
@ -1104,6 +1127,10 @@ static void writeSlowFrame(void)
blackboxWriteSigned16VBArray(slowHistory.tempSensorTemperature, MAX_TEMP_SENSORS);
#endif
#ifdef USE_ESC_SENSOR
blackboxWriteUnsignedVB(slowHistory.escRPM);
blackboxWriteSignedVB(slowHistory.escTemperature);
#endif
blackboxSlowFrameIterationTimer = 0;
}
@ -1156,6 +1183,11 @@ static void loadSlowState(blackboxSlowState_t *slow)
}
#endif
#ifdef USE_ESC_SENSOR
escSensorData_t * escSensor = escSensorGetData();
slow->escRPM = escSensor->rpm;
slow->escTemperature = escSensor->temperature;
#endif
}
/**

View file

@ -17,25 +17,9 @@
#pragma once
// only set_BASEPRI is implemented in device library. It does always create memory barrier
// missing versions are implemented here
#ifdef UNIT_TEST
static inline void __set_BASEPRI(uint32_t basePri) {(void)basePri;}
static inline void __set_BASEPRI_MAX(uint32_t basePri) {(void)basePri;}
static inline void __set_BASEPRI_nb(uint32_t basePri) {(void)basePri;}
static inline void __set_BASEPRI_MAX_nb(uint32_t basePri) {(void)basePri;}
#else
// set BASEPRI and BASEPRI_MAX register, but do not create memory barrier
__attribute__( ( always_inline ) ) static inline void __set_BASEPRI_nb(uint32_t basePri)
{
__ASM volatile ("\tMSR basepri, %0\n" : : "r" (basePri) );
}
__attribute__( ( always_inline ) ) static inline void __set_BASEPRI_MAX_nb(uint32_t basePri)
{
__ASM volatile ("\tMSR basepri_max, %0\n" : : "r" (basePri) );
}
#endif // UNIT_TEST
// cleanup BASEPRI restore function, with global memory barrier
@ -51,68 +35,19 @@ static inline uint8_t __basepriSetMemRetVal(uint8_t prio)
return 1;
}
// cleanup BASEPRI restore function, no memory barrier
static inline void __basepriRestore(uint8_t *val)
{
__set_BASEPRI_nb(*val);
}
// set BASEPRI_MAX function, no memory barrier, returns true
static inline uint8_t __basepriSetRetVal(uint8_t prio)
{
__set_BASEPRI_MAX_nb(prio);
return 1;
}
// The CMSIS provides the function __set_BASEPRI(priority) for changing the value of the BASEPRI register.
// The function uses the hardware convention for the priority argument, which means that the priority must
// be shifted left by the number of unimplemented bits (8 __NVIC_PRIO_BITS).
//
// NOTE: The priority numbering convention used in __set_BASEPRI(priority) is thus different than in the
// NVIC_SetPriority(priority) function, which expects the “priority” argument not shifted.
// Run block with elevated BASEPRI (using BASEPRI_MAX), restoring BASEPRI on exit. All exit paths are handled
// Full memory barrier is placed at start and exit of block
#ifdef UNIT_TEST
#define ATOMIC_BLOCK(prio) {}
#define ATOMIC_BLOCK_NB(prio) {}
#else
#define ATOMIC_BLOCK(prio) for ( uint8_t __basepri_save __attribute__((__cleanup__(__basepriRestoreMem))) = __get_BASEPRI(), \
__ToDo = __basepriSetMemRetVal(prio); __ToDo ; __ToDo = 0 )
// Run block with elevated BASEPRI (using BASEPRI_MAX), but do not create any (explicit) memory barrier.
// Be careful when using this, you must use some method to prevent optimizer form breaking things
// - lto is used for Cleanflight compilation, so function call is not memory barrier
// - use ATOMIC_BARRIER or proper volatile to protect used variables
// - gcc 4.8.4 does write all values in registers to memory before 'asm volatile', so this optimization does not help much
// but that can change in future versions
#define ATOMIC_BLOCK_NB(prio) for ( uint8_t __basepri_save __attribute__((__cleanup__(__basepriRestore))) = __get_BASEPRI(), \
__ToDo = __basepriSetRetVal(prio); __ToDo ; __ToDo = 0 ) \
__ToDo = __basepriSetMemRetVal((prio) << (8U - __NVIC_PRIO_BITS)); __ToDo ; __ToDo = 0 )
#endif // UNIT_TEST
// ATOMIC_BARRIER
// Create memory barrier
// - at the beginning (all data must be reread from memory)
// - at exit of block (all exit paths) (all data must be written, but may be cached in register for subsequent use)
// ideally this would only protect memory passed as parameter (any type should work), but gcc is currently creating almost full barrier
// this macro can be used only ONCE PER LINE, but multiple uses per block are fine
#if (__GNUC__ > 9)
#warning "Please verify that ATOMIC_BARRIER works as intended"
// increment version number is BARRIER works
// TODO - use flag to disable ATOMIC_BARRIER and use full barrier instead
// you should check that local variable scope with cleanup spans entire block
#endif
#ifndef __UNIQL
# define __UNIQL_CONCAT2(x,y) x ## y
# define __UNIQL_CONCAT(x,y) __UNIQL_CONCAT2(x,y)
# define __UNIQL(x) __UNIQL_CONCAT(x,__LINE__)
#endif
// this macro uses local function for cleanup. CLang block can be substituted
#define ATOMIC_BARRIER(data) \
__extension__ void __UNIQL(__barrierEnd)(typeof(data) **__d) { \
__asm__ volatile ("\t# barier(" #data ") end\n" : : "m" (**__d)); \
} \
typeof(data) __attribute__((__cleanup__(__UNIQL(__barrierEnd)))) *__UNIQL(__barrier) = &data; \
__asm__ volatile ("\t# barier (" #data ") start\n" : "+m" (*__UNIQL(__barrier)))
// define these wrappers for atomic operations, use gcc buildins
#define ATOMIC_OR(ptr, val) __sync_fetch_and_or(ptr, val)
#define ATOMIC_AND(ptr, val) __sync_fetch_and_and(ptr, val)

View file

@ -70,5 +70,6 @@ typedef enum {
DEBUG_NAV_YAW,
DEBUG_DYNAMIC_FILTER,
DEBUG_DYNAMIC_FILTER_FREQUENCY,
DEBUG_IRLOCK,
DEBUG_COUNT
} debugType_e;

View file

@ -766,7 +766,7 @@ void cmsMenuOpen(void)
{
if (!cmsInMenu) {
// New open
setServoOutputEnabled(false);
setServoOutputEnabled(false);
pCurrentDisplay = cmsDisplayPortSelectCurrent();
if (!pCurrentDisplay)
return;

View file

@ -36,6 +36,7 @@
#include "config/feature.h"
#include "drivers/flash.h"
#include "drivers/time.h"
#include "fc/config.h"
@ -53,7 +54,7 @@ static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
flashfsEraseCompletely();
while (!flashfsIsReady()) {
while (!flashIsReady()) {
delay(100);
}

View file

@ -108,6 +108,7 @@ static const OSD_Entry cmsx_menuFixedWingEntries[] =
OSD_SETTING_ENTRY("MAX DIVE ANGLE", SETTING_NAV_FW_DIVE_ANGLE),
OSD_SETTING_ENTRY("PITCH TO THR RATIO", SETTING_NAV_FW_PITCH2THR),
OSD_SETTING_ENTRY("LOITER RADIUS", SETTING_NAV_FW_LOITER_RADIUS),
OSD_SETTING_ENTRY("CONTROL SMOOTHNESS", SETTING_NAV_FW_CONTROL_SMOOTHNESS),
OSD_BACK_AND_END_ENTRY,
};

View file

@ -273,6 +273,7 @@ static const OSD_Entry menuOsdElemsEntries[] =
#ifdef USE_ESC_SENSOR
OSD_ELEMENT_ENTRY("ESC RPM", OSD_ESC_RPM),
OSD_ELEMENT_ENTRY("ESC TEMPERATURE", OSD_ESC_TEMPERATURE),
#endif
OSD_BACK_AND_END_ENTRY,
@ -378,6 +379,7 @@ static const OSD_Entry menuOsdHud2Entries[] = {
OSD_SETTING_ENTRY("RADAR MIN RANGE", SETTING_OSD_HUD_RADAR_RANGE_MIN),
OSD_SETTING_ENTRY("RADAR MAX RANGE", SETTING_OSD_HUD_RADAR_RANGE_MAX),
OSD_SETTING_ENTRY("RADAR DET. NEAREST", SETTING_OSD_HUD_RADAR_NEAREST),
OSD_SETTING_ENTRY("NEXT WAYPOINTS", SETTING_OSD_HUD_WP_DISP),
OSD_BACK_ENTRY,
OSD_END_ENTRY,
};

View file

@ -142,7 +142,7 @@ static void cms_Vtx_initSettings(void)
vtxPitMode = onoff ? 2 : 1;
}
else {
vtxPitMode = vtxSettingsConfig()->lowPowerDisarm ? 2 : 1;
vtxPitMode = 0;
}
}
@ -165,7 +165,6 @@ static long cms_Vtx_Commence(displayPort_t *pDisp, const void *self)
vtxSettingsConfigMutable()->band = vtxBand;
vtxSettingsConfigMutable()->channel = vtxChan;
vtxSettingsConfigMutable()->power = vtxPower;
vtxSettingsConfigMutable()->lowPowerDisarm = (vtxPitMode == 2 ? 1 : 0);
saveConfigAndNotify();

View file

@ -75,17 +75,19 @@ int bitArrayFindFirstSet(const bitarrayElement_t *array, unsigned start, size_t
const uint32_t *end = ptr + (size / 4);
const uint32_t *p = ptr + start / (8 * 4);
int ret;
// First iteration might need to mask some bits
uint32_t mask = 0xFFFFFFFF << (start % (8 * 4));
if ((ret = __CTZ(*p & mask)) != 32) {
return (((char *)p) - ((char *)ptr)) * 8 + ret;
}
p++;
while (p < end) {
if ((ret = __CTZ(*p)) != 32) {
if (p < end) {
// First iteration might need to mask some bits
uint32_t mask = 0xFFFFFFFF << (start % (8 * 4));
if ((ret = __CTZ(*p & mask)) != 32) {
return (((char *)p) - ((char *)ptr)) * 8 + ret;
}
p++;
while (p < end) {
if ((ret = __CTZ(*p)) != 32) {
return (((char *)p) - ((char *)ptr)) * 8 + ret;
}
p++;
}
}
return -1;
}

View file

@ -33,7 +33,7 @@
#include "common/vector.h"
typedef enum {
ZERO_CALIBRATION_NONE,
ZERO_CALIBRATION_NONE = 0,
ZERO_CALIBRATION_IN_PROGRESS,
ZERO_CALIBRATION_DONE,
ZERO_CALIBRATION_FAIL,

View file

@ -132,3 +132,14 @@ uint8_t crc8_update(uint8_t crc, const void *data, uint32_t length)
}
return crc;
}
uint8_t crc8_sum_update(uint8_t crc, const void *data, uint32_t length)
{
const uint8_t *p = (const uint8_t *)data;
const uint8_t *pend = p + length;
for (; p != pend; p++) {
crc += *p;
}
return crc;
}

View file

@ -34,3 +34,5 @@ void crc8_xor_sbuf_append(struct sbuf_s *dst, uint8_t *start);
uint8_t crc8(uint8_t crc, uint8_t a);
uint8_t crc8_update(uint8_t crc, const void *data, uint32_t length);
uint8_t crc8_sum_update(uint8_t crc, const void *data, uint32_t length);

View file

@ -15,6 +15,10 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
FILE_COMPILE_FOR_SPEED
#include "encoding.h"
/**

View file

@ -22,6 +22,8 @@
#include "platform.h"
FILE_COMPILE_FOR_SPEED
#include "common/filter.h"
#include "common/maths.h"
#include "common/utils.h"
@ -116,10 +118,9 @@ float rateLimitFilterApply4(rateLimitFilter_t *filter, float input, float rate_l
return filter->state;
}
float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff)
float filterGetNotchQ(float centerFrequencyHz, float cutoffFrequencyHz)
{
const float octaves = log2f((float)centerFreq / (float)cutoff) * 2;
return sqrtf(powf(2, octaves)) / (powf(2, octaves) - 1);
return centerFrequencyHz * cutoffFrequencyHz / (centerFrequencyHz * centerFrequencyHz - cutoffFrequencyHz * cutoffFrequencyHz);
}
void biquadFilterInitNotch(biquadFilter_t *filter, uint32_t samplingIntervalUs, uint16_t filterFreq, uint16_t cutoffHz)

View file

@ -79,7 +79,7 @@ void biquadFilterInit(biquadFilter_t *filter, uint16_t filterFreq, uint32_t samp
float biquadFilterApply(biquadFilter_t *filter, float sample);
float biquadFilterReset(biquadFilter_t *filter, float value);
float biquadFilterApplyDF1(biquadFilter_t *filter, float input);
float filterGetNotchQ(uint16_t centerFreq, uint16_t cutoff);
float filterGetNotchQ(float centerFrequencyHz, float cutoffFrequencyHz);
void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);

View file

@ -98,6 +98,22 @@ void globalFunctionsProcess(int8_t functionId) {
}
}
break;
case GLOBAL_FUNCTION_ACTION_SET_VTX_BAND:
if (conditionValue && !previousValue) {
vtxDeviceCapability_t vtxDeviceCapability;
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
vtxSettingsConfigMutable()->band = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND);
}
}
break;
case GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL:
if (conditionValue && !previousValue) {
vtxDeviceCapability_t vtxDeviceCapability;
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
vtxSettingsConfigMutable()->channel = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL);
}
}
break;
case GLOBAL_FUNCTION_ACTION_INVERT_ROLL:
if (conditionValue) {
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL);
@ -142,7 +158,7 @@ float NOINLINE getThrottleScale(float globalThrottleScale) {
}
}
int16_t FAST_CODE getRcCommandOverride(int16_t command[], uint8_t axis) {
int16_t getRcCommandOverride(int16_t command[], uint8_t axis) {
int16_t outputValue = command[axis];
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) {

View file

@ -29,14 +29,16 @@
#define MAX_GLOBAL_FUNCTIONS 8
typedef enum {
GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY = 0,
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE,
GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW,
GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL,
GLOBAL_FUNCTION_ACTION_INVERT_ROLL,
GLOBAL_FUNCTION_ACTION_INVERT_PITCH,
GLOBAL_FUNCTION_ACTION_INVERT_YAW,
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE,
GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY = 0, // 0
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE, // 1
GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW, // 2
GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL, // 3
GLOBAL_FUNCTION_ACTION_INVERT_ROLL, // 4
GLOBAL_FUNCTION_ACTION_INVERT_PITCH, // 5
GLOBAL_FUNCTION_ACTION_INVERT_YAW, // 6
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE, // 7
GLOBAL_FUNCTION_ACTION_SET_VTX_BAND, // 8
GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL, // 9
GLOBAL_FUNCTION_ACTION_LAST
} globalFunctionActions_e;

View file

@ -0,0 +1,72 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#include "platform.h"
FILE_COMPILE_FOR_SIZE
#ifdef USE_LOGIC_CONDITIONS
#include <stdint.h>
#include "config/config_reset.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "common/global_variables.h"
#include "common/maths.h"
#include "build/build_config.h"
static EXTENDED_FASTRAM int32_t globalVariableState[MAX_GLOBAL_VARIABLES];
PG_REGISTER_ARRAY_WITH_RESET_FN(globalVariableConfig_t, MAX_GLOBAL_VARIABLES, globalVariableConfigs, PG_GLOBAL_VARIABLE_CONFIG, 0);
void pgResetFn_globalVariableConfigs(globalVariableConfig_t *globalVariableConfigs)
{
for (int i = 0; i < MAX_GLOBAL_VARIABLES; i++) {
globalVariableConfigs[i].min = INT16_MIN;
globalVariableConfigs[i].max = INT16_MAX;
globalVariableConfigs[i].defaultValue = 0;
}
}
int32_t gvGet(uint8_t index) {
if (index < MAX_GLOBAL_VARIABLES) {
return globalVariableState[index];
} else {
return 0;
}
}
void gvSet(uint8_t index, int32_t value) {
if (index < MAX_GLOBAL_VARIABLES) {
globalVariableState[index] = constrain(value, globalVariableConfigs(index)->min, globalVariableConfigs(index)->max);
}
}
void gvInit(void) {
for (int i = 0; i < MAX_GLOBAL_VARIABLES; i++) {
globalVariableState[i] = globalVariableConfigs(i)->defaultValue;
}
}
#endif

View file

@ -0,0 +1,40 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#pragma once
#include "config/parameter_group.h"
#define MAX_GLOBAL_VARIABLES 4
typedef struct globalVariableConfig_s {
int32_t min;
int32_t max;
int32_t defaultValue;
} globalVariableConfig_t;
PG_DECLARE_ARRAY(globalVariableConfig_t, MAX_GLOBAL_VARIABLES, globalVariableConfigs);
int32_t gvGet(uint8_t index);
void gvSet(uint8_t index, int32_t value);
void gvInit(void);

View file

@ -29,6 +29,7 @@
#include "config/parameter_group_ids.h"
#include "common/logic_condition.h"
#include "common/global_variables.h"
#include "common/utils.h"
#include "rx/rx.h"
#include "maths.h"
@ -39,11 +40,32 @@
#include "sensors/battery.h"
#include "sensors/pitotmeter.h"
#include "flight/imu.h"
#include "flight/pid.h"
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
PG_REGISTER_ARRAY(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 0);
PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 1);
void pgResetFn_logicConditions(logicCondition_t *instance)
{
for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) {
RESET_CONFIG(logicCondition_t, &instance[i],
.enabled = 0,
.activatorId = -1,
.operation = 0,
.operandA = {
.type = LOGIC_CONDITION_OPERAND_TYPE_VALUE,
.value = 0
},
.operandB = {
.type = LOGIC_CONDITION_OPERAND_TYPE_VALUE,
.value = 0
},
.flags = 0
);
}
}
logicConditionState_t logicConditionStates[MAX_LOGIC_CONDITIONS];
@ -53,6 +75,7 @@ static int logicConditionCompute(
int operandA,
int operandB
) {
int temporaryValue;
switch (operation) {
case LOGIC_CONDITION_TRUE:
@ -121,6 +144,43 @@ static int logicConditionCompute(
return currentVaue;
break;
case LOGIC_CONDITION_GVAR_SET:
gvSet(operandA, operandB);
return operandB;
break;
case LOGIC_CONDITION_GVAR_INC:
temporaryValue = gvGet(operandA) + operandB;
gvSet(operandA, temporaryValue);
return temporaryValue;
break;
case LOGIC_CONDITION_GVAR_DEC:
temporaryValue = gvGet(operandA) - operandB;
gvSet(operandA, temporaryValue);
return temporaryValue;
break;
case LOGIC_CONDITION_ADD:
return constrain(operandA + operandB, INT16_MIN, INT16_MAX);
break;
case LOGIC_CONDITION_SUB:
return constrain(operandA - operandB, INT16_MIN, INT16_MAX);
break;
case LOGIC_CONDITION_MUL:
return constrain(operandA * operandB, INT16_MIN, INT16_MAX);
break;
case LOGIC_CONDITION_DIV:
if (operandB != 0) {
return constrain(operandA / operandB, INT16_MIN, INT16_MAX);
} else {
return operandA;
}
break;
default:
return false;
break;
@ -129,7 +189,9 @@ static int logicConditionCompute(
void logicConditionProcess(uint8_t i) {
if (logicConditions(i)->enabled) {
const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId);
if (logicConditions(i)->enabled && activatorValue) {
/*
* Process condition only when latch flag is not set
@ -164,15 +226,15 @@ static int logicConditionGetFlightOperandValue(int operand) {
switch (operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER: // in s
return constrain((uint32_t)getFlightTime(), 0, 32767);
return constrain((uint32_t)getFlightTime(), 0, INT16_MAX);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE: //in m
return constrain(GPS_distanceToHome, 0, 32767);
return constrain(GPS_distanceToHome, 0, INT16_MAX);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE: //in m
return constrain(getTotalTravelDistance() / 100, 0, 32767);
return constrain(getTotalTravelDistance() / 100, 0, INT16_MAX);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_RSSI:
@ -209,18 +271,18 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED: // cm/s
#ifdef USE_PITOT
return constrain(pitot.airSpeed, 0, 32767);
return constrain(pitot.airSpeed, 0, INT16_MAX);
#else
return false;
#endif
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE: // cm
return constrain(getEstimatedActualPosition(Z), -32678, 32767);
return constrain(getEstimatedActualPosition(Z), INT16_MIN, INT16_MAX);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED: // cm/s
return constrain(getEstimatedActualVelocity(Z), 0, 32767);
return constrain(getEstimatedActualVelocity(Z), 0, INT16_MAX);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS: // %
@ -271,6 +333,18 @@ static int logicConditionGetFlightOperandValue(int operand) {
return (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) ? 1 : 0;
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW: //
return axisPID[YAW];
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL: //
return axisPID[ROLL];
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH: //
return axisPID[PITCH];
break;
default:
return 0;
break;
@ -353,6 +427,12 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) {
}
break;
case LOGIC_CONDITION_OPERAND_TYPE_GVAR:
if (operand >= 0 && operand < MAX_GLOBAL_VARIABLES) {
retVal = gvGet(operand);
}
break;
default:
break;
}

View file

@ -43,6 +43,13 @@ typedef enum {
LOGIC_CONDITION_NOR, // 11
LOGIC_CONDITION_NOT, // 12
LOGIC_CONDITION_STICKY, // 13
LOGIC_CONDITION_ADD, // 14
LOGIC_CONDITION_SUB, // 15
LOGIC_CONDITION_MUL, // 16
LOGIC_CONDITION_DIV, // 17
LOGIC_CONDITION_GVAR_SET, // 18
LOGIC_CONDITION_GVAR_INC, // 19
LOGIC_CONDITION_GVAR_DEC, // 20
LOGIC_CONDITION_LAST
} logicOperation_e;
@ -52,6 +59,7 @@ typedef enum logicOperandType_s {
LOGIC_CONDITION_OPERAND_TYPE_FLIGHT,
LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE,
LOGIC_CONDITION_OPERAND_TYPE_LC, // Result of different LC and LC operand
LOGIC_CONDITION_OPERAND_TYPE_GVAR, // Value from a global variable
LOGIC_CONDITION_OPERAND_TYPE_LAST
} logicOperandType_e;
@ -82,6 +90,9 @@ typedef enum {
LOGIC_CONDITION_OPERAND_FLIGHT_IS_WP, // 0/1 // 23
LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING, // 0/1 // 24
LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE, // 0/1 // 25
LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL, // 26
LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH, // 27
LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW, // 28
} logicFlightOperands_e;
typedef enum {
@ -107,6 +118,7 @@ typedef struct logicOperand_s {
typedef struct logicCondition_s {
uint8_t enabled;
int8_t activatorId;
logicOperation_e operation;
logicOperand_t operandA;
logicOperand_t operandB;

View file

@ -25,6 +25,8 @@
#include "quaternion.h"
#include "platform.h"
FILE_COMPILE_FOR_SPEED
// http://lolengine.net/blog/2011/12/21/better-function-approximations
// Chebyshev http://stackoverflow.com/questions/345085/how-do-trigonometric-functions-work/345117#345117
// Thanks for ledvinap for making such accuracy possible! See: https://github.com/cleanflight/cleanflight/issues/940#issuecomment-110323384
@ -159,7 +161,7 @@ int constrain(int amt, int low, int high)
return amt;
}
float FAST_CODE NOINLINE constrainf(float amt, float low, float high)
float constrainf(float amt, float low, float high)
{
if (amt < low)
return low;
@ -473,7 +475,19 @@ static void sensorCalibration_SolveLGS(float A[4][4], float x[4], float b[4]) {
sensorCalibration_BackwardSubstitution(A, x, y);
}
void sensorCalibrationSolveForOffset(sensorCalibrationState_t * state, float result[3])
bool sensorCalibrationValidateResult(const float result[3])
{
// Validate that result is not INF and not NAN
for (int i = 0; i < 3; i++) {
if (isnan(result[i]) && isinf(result[i])) {
return false;
}
}
return true;
}
bool sensorCalibrationSolveForOffset(sensorCalibrationState_t * state, float result[3])
{
float beta[4];
sensorCalibration_SolveLGS(state->XtX, beta, state->XtY);
@ -481,9 +495,11 @@ void sensorCalibrationSolveForOffset(sensorCalibrationState_t * state, float res
for (int i = 0; i < 3; i++) {
result[i] = beta[i] / 2;
}
return sensorCalibrationValidateResult(result);
}
void sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float result[3])
bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float result[3])
{
float beta[4];
sensorCalibration_SolveLGS(state->XtX, beta, state->XtY);
@ -491,6 +507,8 @@ void sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
for (int i = 0; i < 3; i++) {
result[i] = sqrtf(beta[i]);
}
return sensorCalibrationValidateResult(result);
}
float bellCurve(const float x, const float curveWidth)

View file

@ -18,6 +18,7 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#ifndef sq
#define sq(x) ((x)*(x))
@ -59,6 +60,8 @@
#define CENTIMETERS_TO_FEET(cm) (cm * (328 / 10000.0))
#define CENTIMETERS_TO_METERS(cm) (cm / 100)
#define METERS_TO_CENTIMETERS(m) (m * 100)
// copied from https://code.google.com/p/cxutil/source/browse/include/cxutil/utility.h#70
#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \
( __extension__ ({ \
@ -122,8 +125,8 @@ typedef struct {
void sensorCalibrationResetState(sensorCalibrationState_t * state);
void sensorCalibrationPushSampleForOffsetCalculation(sensorCalibrationState_t * state, int32_t sample[3]);
void sensorCalibrationPushSampleForScaleCalculation(sensorCalibrationState_t * state, int axis, int32_t sample[3], int target);
void sensorCalibrationSolveForOffset(sensorCalibrationState_t * state, float result[3]);
void sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float result[3]);
bool sensorCalibrationSolveForOffset(sensorCalibrationState_t * state, float result[3]);
bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float result[3]);
int gcd(int num, int denom);
int32_t applyDeadband(int32_t value, int32_t deadband);

View file

@ -20,6 +20,8 @@
#include "build/build_config.h"
#include "maths.h"
#include "platform.h"
FILE_COMPILE_FOR_SPEED
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
@ -185,7 +187,7 @@ char *ftoa(float x, char *floatString)
dpLocation = strlen(intString2) - 3;
strncpy(floatString, intString2, dpLocation);
memcpy(floatString, intString2, dpLocation);
floatString[dpLocation] = '\0';
strcat(floatString, decimalPoint);
strcat(floatString, intString2 + dpLocation);

View file

@ -31,12 +31,13 @@ void latchActiveFeatures(void)
bool featureConfigured(uint32_t mask)
{
return featureConfig()->enabledFeatures & mask;
return (featureConfig()->enabledFeatures & mask) == mask;
}
bool FAST_CODE NOINLINE feature(uint32_t mask)
bool feature(uint32_t mask)
{
return activeFeaturesLatch & mask;
// Check for ALL masked features
return (activeFeaturesLatch & mask) == mask;
}
void featureSet(uint32_t mask)

View file

@ -110,7 +110,8 @@
#define PG_GLOBAL_FUNCTIONS 1020
#define PG_ESC_SENSOR_CONFIG 1021
#define PG_RPM_FILTER_CONFIG 1022
#define PG_INAV_END 1022
#define PG_GLOBAL_VARIABLE_CONFIG 1023
#define PG_INAV_END 1023
// OSD configuration (subject to change)
//#define PG_OSD_FONT_CONFIG 2047

View file

@ -28,7 +28,7 @@
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_adxl345.h"
#ifdef USE_ACC_ADXL345
#ifdef USE_IMU_ADXL345
// ADXL345, Alternative address mode 0x53
#define ADXL345_ADDRESS 0x53
@ -110,6 +110,7 @@ bool adxl345Detect(accDev_t *acc)
acc->initFn = adxl345Init;
acc->readFn = adxl345Read;
acc->accAlign = acc->busDev->param;
return true;
}

View file

@ -27,7 +27,7 @@
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_bma280.h"
#ifdef USE_ACC_BMA280
#ifdef USE_IMU_BMA280
// BMA280, default I2C address mode 0x18
#define BMA280_WHOAMI 0x00
@ -86,6 +86,7 @@ bool bma280Detect(accDev_t *acc)
acc->initFn = bma280Init;
acc->readFn = bma280Read;
acc->accAlign = acc->busDev->param;
return true;
}

View file

@ -42,7 +42,7 @@
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_bmi160.h"
#if defined(USE_GYRO_BMI160) || defined(USE_ACC_BMI160)
#if defined(USE_IMU_BMI160)
/* BMI160 Registers */
#define BMI160_REG_CHIPID 0x00
@ -270,6 +270,7 @@ bool bmi160GyroDetect(gyroDev_t *gyro)
gyro->intStatusFn = gyroCheckDataReady;
gyro->temperatureFn = NULL;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -27,7 +27,7 @@
#include "drivers/accgyro/accgyro_fake.h"
#ifdef USE_FAKE_GYRO
#ifdef USE_IMU_FAKE
static int16_t fakeGyroADC[XYZ_AXIS_COUNT];
@ -71,6 +71,7 @@ bool fakeGyroDetect(gyroDev_t *gyro)
gyro->readFn = fakeGyroRead;
gyro->temperatureFn = fakeGyroReadTemperature;
gyro->scale = 1.0f / 16.4f;
gyro->gyroAlign = 0;
return true;
}
#endif // USE_FAKE_GYRO
@ -104,6 +105,7 @@ bool fakeAccDetect(accDev_t *acc)
{
acc->initFn = fakeAccInit;
acc->readFn = fakeAccRead;
acc->accAlign = 0;
return true;
}
#endif // USE_FAKE_ACC

View file

@ -38,7 +38,7 @@
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_icm20689.h"
#if (defined(USE_GYRO_ICM20689) || defined(USE_ACC_ICM20689))
#if defined(USE_IMU_ICM20689)
static uint8_t icm20689DeviceDetect(const busDevice_t *busDev)
{
@ -82,6 +82,7 @@ bool icm20689AccDetect(accDev_t *acc)
acc->initFn = icm20689AccInit;
acc->readFn = mpuAccReadScratchpad;
acc->accAlign = acc->busDev->param;
return true;
}
@ -142,6 +143,7 @@ bool icm20689GyroDetect(gyroDev_t *gyro)
gyro->intStatusFn = gyroCheckDataReady;
gyro->temperatureFn = mpuTemperatureReadScratchpad;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -24,9 +24,5 @@
#define ICM20689_BIT_RESET (0x80)
#if (defined(USE_GYRO_ICM20689) || defined(USE_ACC_ICM20689))
bool icm20689AccDetect(accDev_t *acc);
bool icm20689GyroDetect(gyroDev_t *gyro);
#endif

View file

@ -139,6 +139,7 @@ bool l3g4200dDetect(gyroDev_t *gyro)
gyro->initFn = l3g4200dInit;
gyro->readFn = l3g4200dRead;
gyro->scale = 1.0f / 14.2857f; // 14.2857dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -32,7 +32,7 @@
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_l3gd20.h"
#ifdef USE_GYRO_L3GD20
#ifdef USE_IMU_L3GD20
#define READ_CMD ((uint8_t)0x80)
#define MULTIPLEBYTE_CMD ((uint8_t)0x40)
@ -116,6 +116,7 @@ bool l3gd20Detect(gyroDev_t *gyro)
// Page 9 in datasheet, So - Sensitivity, Full Scale = 2000, 70 mdps/digit
gyro->scale = 0.07f;
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -20,7 +20,7 @@
#include "platform.h"
#ifdef USE_ACC_LSM303DLHC
#ifdef USE_IMU_LSM303DLHC
#include "build/debug.h"
@ -163,6 +163,7 @@ bool lsm303dlhcAccDetect(accDev_t *acc)
acc->initFn = lsm303dlhcAccInit;
acc->readFn = lsm303dlhcAccRead;
acc->accAlign = acc->busDev->param;
return true;
}

View file

@ -139,5 +139,6 @@ bool mma8452Detect(accDev_t *acc)
acc->initFn = mma8452Init;
acc->readFn = mma8452Read;
acc->accAlign = acc->busDev->param;
return true;
}

View file

@ -33,7 +33,7 @@
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_mpu3050.h"
#ifdef USE_GYRO_MPU3050
#ifdef USE_IMU_MPU3050
// MPU3050, Standard address 0x68
#define MPU3050_ADDRESS 0x68
@ -131,6 +131,7 @@ bool mpu3050Detect(gyroDev_t *gyro)
gyro->readFn = mpu3050GyroRead;
gyro->intStatusFn = gyroCheckDataReady;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -42,7 +42,7 @@
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_mpu6000.h"
#if (defined(USE_GYRO_MPU6000) || defined(USE_ACC_MPU6000))
#if defined(USE_IMU_MPU6000)
// Bits
#define BIT_H_RESET 0x80
@ -150,6 +150,7 @@ bool mpu6000AccDetect(accDev_t *acc)
acc->initFn = mpu6000AccInit;
acc->readFn = mpuAccReadScratchpad;
acc->accAlign = acc->busDev->param;
return true;
}
@ -218,6 +219,7 @@ bool mpu6000GyroDetect(gyroDev_t *gyro)
gyro->intStatusFn = gyroCheckDataReady;
gyro->temperatureFn = mpuTemperatureReadScratchpad;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -42,7 +42,7 @@
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_mpu6050.h"
#if defined(USE_GYRO_MPU6050) || defined(USE_ACC_MPU6050)
#if defined(USE_IMU_MPU6050)
#define BIT_H_RESET 0x80
#define MPU_CLK_SEL_PLLGYROZ 0x03
@ -127,6 +127,7 @@ bool mpu6050AccDetect(accDev_t *acc)
if (ctx->chipMagicNumber == 0x6850 || ctx->chipMagicNumber == 0x6050) {
acc->initFn = mpu6050AccInit;
acc->readFn = mpuAccReadScratchpad;
acc->accAlign = acc->busDev->param;
return true;
}
@ -213,6 +214,7 @@ bool mpu6050GyroDetect(gyroDev_t *gyro)
gyro->intStatusFn = gyroCheckDataReady;
gyro->temperatureFn = mpuTemperatureReadScratchpad;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -33,7 +33,7 @@
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_mpu6500.h"
#if defined(USE_GYRO_MPU6500) || defined(USE_ACC_MPU6500)
#if defined(USE_IMU_MPU6500)
#define MPU6500_BIT_RESET (0x80)
#define MPU6500_BIT_INT_ANYRD_2CLEAR (1 << 4)
@ -60,6 +60,7 @@ bool mpu6500AccDetect(accDev_t *acc)
acc->initFn = mpu6500AccInit;
acc->readFn = mpuAccReadScratchpad;
acc->accAlign = acc->busDev->param;
return true;
}
@ -163,6 +164,7 @@ bool mpu6500GyroDetect(gyroDev_t *gyro)
gyro->intStatusFn = gyroCheckDataReady;
gyro->temperatureFn = mpuTemperatureReadScratchpad;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -33,7 +33,7 @@
#include "drivers/accgyro/accgyro_mpu.h"
#include "drivers/accgyro/accgyro_mpu9250.h"
#if defined(USE_GYRO_MPU9250) || defined(USE_ACC_MPU9250)
#if defined(USE_IMU_MPU9250)
#define MPU9250_BIT_RESET (0x80)
#define MPU9250_BIT_INT_ANYRD_2CLEAR (1 << 4)
@ -60,6 +60,7 @@ bool mpu9250AccDetect(accDev_t *acc)
acc->initFn = mpu9250AccInit;
acc->readFn = mpuAccReadScratchpad;
acc->accAlign = acc->busDev->param;
return true;
}
@ -163,6 +164,7 @@ bool mpu9250GyroDetect(gyroDev_t *gyro)
gyro->intStatusFn = gyroCheckDataReady;
gyro->temperatureFn = mpuTemperatureReadScratchpad;
gyro->scale = 1.0f / 16.4f; // 16.4 dps/lsb scalefactor
gyro->gyroAlign = gyro->busDev->param;
return true;
}

View file

@ -166,7 +166,7 @@ static bool deviceDetect(busDevice_t * busDev)
bool ack = busRead(busDev, BMP280_CHIP_ID_REG, &chipId);
if (ack && chipId == BMP280_DEFAULT_CHIP_ID) {
if ((ack && chipId == BMP280_DEFAULT_CHIP_ID) || (ack && chipId == BME280_DEFAULT_CHIP_ID)){
return true;
}
};

View file

@ -19,6 +19,7 @@
#define BMP280_I2C_ADDR (0x76)
#define BMP280_DEFAULT_CHIP_ID (0x58)
#define BME280_DEFAULT_CHIP_ID (0x60)
#define BMP280_CHIP_ID_REG (0xD0) /* Chip ID Register */
#define BMP280_RST_REG (0xE0) /* Softreset Register */

View file

@ -32,7 +32,7 @@
#include "drivers/bus.h"
#include "drivers/io.h"
#define BUSDEV_MAX_DEVICES 8
#define BUSDEV_MAX_DEVICES 16
#ifdef USE_SPI
static void busDevPreInit_SPI(const busDeviceDescriptor_t * descriptor)
@ -124,6 +124,7 @@ busDevice_t * busDeviceInit(busType_e bus, devHardwareType_e hw, uint8_t tag, re
dev->descriptorPtr = descriptor;
dev->busType = descriptor->busType;
dev->flags = descriptor->flags;
dev->param = descriptor->param;
switch (descriptor->busType) {
default:

View file

@ -143,11 +143,14 @@ typedef enum {
DEVHW_M25P16, // SPI NOR flash
DEVHW_UG2864, // I2C OLED display
DEVHW_SDCARD, // Generic SD-Card
DEVHW_IRLOCK, // IR-Lock visual positioning hardware
} devHardwareType_e;
typedef enum {
DEVFLAGS_NONE = 0,
DEVFLAGS_USE_RAW_REGISTERS = (1 << 0), // Don't manipulate MSB for R/W selection (SPI), allow using 0xFF register to raw i2c reads/writes
// SPI-only
DEVFLAGS_USE_MANUAL_DEVICE_SELECT = (1 << 1), // (SPI only) Don't automatically select/deselect device
DEVFLAGS_SPI_MODE_0 = (1 << 2), // (SPI only) Use CPOL=0/CPHA=0 (if unset MODE3 is used - CPOL=1/CPHA=1)
} deviceFlags_e;
@ -156,8 +159,9 @@ typedef struct busDeviceDescriptor_s {
void * devicePtr;
busType_e busType;
devHardwareType_e devHwType;
uint16_t flags;
uint8_t flags;
uint8_t tag;
uint8_t param; // Driver-specific parameter
union {
#ifdef USE_SPI
struct {
@ -179,6 +183,7 @@ typedef struct busDevice_s {
const busDeviceDescriptor_t * descriptorPtr;
busType_e busType; // Copy of busType to avoid additional pointer dereferencing
uint32_t flags; // Copy of flags
uint32_t param; // Copy of param
union {
#ifdef USE_SPI
struct {
@ -209,53 +214,55 @@ extern const busDeviceDescriptor_t __busdev_registry_end[];
#define BUSDEV_REGISTER_ATTRIBUTES __attribute__ ((section(".busdev_registry"), used, aligned(4)))
#endif
#define BUSDEV_REGISTER_SPI_F(_name, _devHw, _spiBus, _csnPin, _irqPin, _tag, _flags) \
extern const busDeviceDescriptor_t _name ## _registry; \
static busDevice_t _name ## _memory; \
const busDeviceDescriptor_t _name ## _registry BUSDEV_REGISTER_ATTRIBUTES = { \
.devicePtr = (void *) & _name ## _memory, \
.busType = BUSTYPE_SPI, \
.devHwType = _devHw, \
.flags = _flags, \
.tag = _tag, \
.busdev.spi = { \
.spiBus = _spiBus, \
.csnPin = IO_TAG(_csnPin) \
}, \
.irqPin = IO_TAG(_irqPin) \
}; \
struct _dummy \
#define BUSDEV_REGISTER_SPI_F(_name, _devHw, _spiBus, _csnPin, _irqPin, _tag, _flags, _param) \
extern const busDeviceDescriptor_t _name ## _registry; \
static busDevice_t _name ## _memory; \
const busDeviceDescriptor_t _name ## _registry BUSDEV_REGISTER_ATTRIBUTES = { \
.devicePtr = (void *) & _name ## _memory, \
.busType = BUSTYPE_SPI, \
.devHwType = _devHw, \
.flags = _flags, \
.tag = _tag, \
.param = _param, \
.busdev.spi = { \
.spiBus = _spiBus, \
.csnPin = IO_TAG(_csnPin) \
}, \
.irqPin = IO_TAG(_irqPin) \
}; \
struct _dummy \
/**/
#define BUSDEV_REGISTER_I2C_F(_name, _devHw, _i2cBus, _devAddr, _irqPin, _tag, _flags) \
extern const busDeviceDescriptor_t _name ## _registry; \
static busDevice_t _name ## _memory; \
const busDeviceDescriptor_t _name ## _registry BUSDEV_REGISTER_ATTRIBUTES = { \
.devicePtr = (void *) & _name ## _memory, \
.busType = BUSTYPE_I2C, \
.devHwType = _devHw, \
.flags = _flags, \
.tag = _tag, \
.busdev.i2c = { \
.i2cBus = _i2cBus, \
.address = _devAddr \
}, \
.irqPin = IO_TAG(_irqPin) \
}; \
struct _dummy \
#define BUSDEV_REGISTER_I2C_F(_name, _devHw, _i2cBus, _devAddr, _irqPin, _tag, _flags, _param) \
extern const busDeviceDescriptor_t _name ## _registry; \
static busDevice_t _name ## _memory; \
const busDeviceDescriptor_t _name ## _registry BUSDEV_REGISTER_ATTRIBUTES = { \
.devicePtr = (void *) & _name ## _memory, \
.busType = BUSTYPE_I2C, \
.devHwType = _devHw, \
.flags = _flags, \
.tag = _tag, \
.param = _param, \
.busdev.i2c = { \
.i2cBus = _i2cBus, \
.address = _devAddr \
}, \
.irqPin = IO_TAG(_irqPin) \
}; \
struct _dummy \
/**/
#define BUSDEV_REGISTER_SPI(_name, _devHw, _spiBus, _csnPin, _irqPin, _flags) \
BUSDEV_REGISTER_SPI_F(_name, _devHw, _spiBus, _csnPin, _irqPin, 0, _flags)
#define BUSDEV_REGISTER_SPI(_name, _devHw, _spiBus, _csnPin, _irqPin, _flags, _param) \
BUSDEV_REGISTER_SPI_F(_name, _devHw, _spiBus, _csnPin, _irqPin, 0, _flags, _param)
#define BUSDEV_REGISTER_SPI_TAG(_name, _devHw, _spiBus, _csnPin, _irqPin, _tag, _flags) \
BUSDEV_REGISTER_SPI_F(_name, _devHw, _spiBus, _csnPin, _irqPin, _tag, _flags)
#define BUSDEV_REGISTER_SPI_TAG(_name, _devHw, _spiBus, _csnPin, _irqPin, _tag, _flags, _param) \
BUSDEV_REGISTER_SPI_F(_name, _devHw, _spiBus, _csnPin, _irqPin, _tag, _flags, _param)
#define BUSDEV_REGISTER_I2C(_name, _devHw, _i2cBus, _devAddr, _irqPin, _flags) \
BUSDEV_REGISTER_I2C_F(_name, _devHw, _i2cBus, _devAddr, _irqPin, 0, _flags)
#define BUSDEV_REGISTER_I2C(_name, _devHw, _i2cBus, _devAddr, _irqPin, _flags, _param) \
BUSDEV_REGISTER_I2C_F(_name, _devHw, _i2cBus, _devAddr, _irqPin, 0, _flags, _param)
#define BUSDEV_REGISTER_I2C_TAG(_name, _devHw, _i2cBus, _devAddr, _irqPin, _tag, _flags) \
BUSDEV_REGISTER_I2C_F(_name, _devHw, _i2cBus, _devAddr, _irqPin, _tag, _flags)
#define BUSDEV_REGISTER_I2C_TAG(_name, _devHw, _i2cBus, _devAddr, _irqPin, _tag, _flags, _param)\
BUSDEV_REGISTER_I2C_F(_name, _devHw, _i2cBus, _devAddr, _irqPin, _tag, _flags, _param)
// busTransfer and busTransferMultiple are supported only on full-duplex SPI bus

View file

@ -317,9 +317,10 @@ void i2cInit(I2CDevice device)
/* Enable the Analog I2C Filter */
HAL_I2CEx_ConfigAnalogFilter(&i2cHandle[device].Handle,I2C_ANALOGFILTER_ENABLE);
HAL_NVIC_SetPriority(i2cHardwareMap[device].er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER));
HAL_NVIC_SetPriority(i2cHardwareMap[device].er_irq, NVIC_PRIO_I2C_ER, 0);
HAL_NVIC_EnableIRQ(i2cHardwareMap[device].er_irq);
HAL_NVIC_SetPriority(i2cHardwareMap[device].ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV));
HAL_NVIC_SetPriority(i2cHardwareMap[device].ev_irq, NVIC_PRIO_I2C_EV, 0);
HAL_NVIC_EnableIRQ(i2cHardwareMap[device].ev_irq);
state->initialised = true;
}

View file

@ -40,7 +40,7 @@
#include "drivers/compass/compass.h"
#include "drivers/compass/compass_mpu9250.h"
#if defined(USE_MAG_MPU9250) && defined(USE_GYRO_MPU9250)
#if defined(USE_MAG_MPU9250) && defined(USE_IMU_MPU9250)
// No separate hardware descriptor needed. Hardware descriptor initialization is handled by GYRO driver

View file

@ -192,9 +192,9 @@ int displayWriteCharWithAttr(displayPort_t *instance, uint8_t x, uint8_t y, uint
return -1;
}
if (displayAttributesRequireEmulation(instance, attr)) {
char ec;
if (displayEmulateTextAttributes(instance, &ec, 1, &attr)) {
c = ec;
char ec[2];
if (displayEmulateTextAttributes(instance, ec, 1, &attr)) {
c = ec[0];
}
}
instance->posX = x + 1;
@ -317,4 +317,3 @@ void displayInit(displayPort_t *instance, const displayPortVTable_t *vTable)
instance->maxChar = 0;
displayUpdateMaxChar(instance);
}

View file

@ -98,18 +98,13 @@ void dmaInit(DMA_t dma, resourceOwner_e owner, uint8_t resourceIndex)
void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
{
NVIC_InitTypeDef NVIC_InitStructure;
dmaEnableClock(dma);
dma->irqHandlerCallback = callback;
dma->userParam = userParam;
NVIC_InitStructure.NVIC_IRQChannel = dma->irqNumber;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(priority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(priority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(dma->irqNumber, priority);
NVIC_EnableIRQ(dma->irqNumber);
}
DMA_t dmaGetByRef(const DMA_Channel_TypeDef * ref)

View file

@ -106,18 +106,13 @@ void dmaInit(DMA_t dma, resourceOwner_e owner, uint8_t resourceIndex)
void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
{
NVIC_InitTypeDef NVIC_InitStructure;
dmaEnableClock(dma);
dma->irqHandlerCallback = callback;
dma->userParam = userParam;
NVIC_InitStructure.NVIC_IRQChannel = dma->irqNumber;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(priority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(priority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(dma->irqNumber, priority);
NVIC_EnableIRQ(dma->irqNumber);
}
uint32_t dmaGetChannelByTag(dmaTag_t tag)

View file

@ -110,7 +110,7 @@ void dmaSetHandler(DMA_t dma, dmaCallbackHandlerFuncPtr callback, uint32_t prior
dma->irqHandlerCallback = callback;
dma->userParam = userParam;
HAL_NVIC_SetPriority(dma->irqNumber, NVIC_PRIORITY_BASE(priority), NVIC_PRIORITY_SUB(priority));
HAL_NVIC_SetPriority(dma->irqNumber, priority, 0);
HAL_NVIC_EnableIRQ(dma->irqNumber);
}

View file

@ -90,7 +90,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf
if (extiGroupPriority[group] > irqPriority) {
extiGroupPriority[group] = irqPriority;
HAL_NVIC_SetPriority(extiGroupIRQn[group], NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
HAL_NVIC_SetPriority(extiGroupIRQn[group], irqPriority, 0);
HAL_NVIC_EnableIRQ(extiGroupIRQn[group]);
}
}
@ -131,12 +131,8 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
if (extiGroupPriority[group] > irqPriority) {
extiGroupPriority[group] = irqPriority;
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = extiGroupIRQn[group];
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(extiGroupIRQn[group], irqPriority);
NVIC_EnableIRQ(extiGroupIRQn[group]);
}
}
#endif

292
src/main/drivers/flash.c Normal file
View file

@ -0,0 +1,292 @@
/*
* This file is part of iNav.
*
* iNav is free software. You can redistribute
* this software and/or modify this software 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.
*
* iNav is distributed in the hope that it
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#include "build/debug.h"
#ifdef USE_FLASHFS
#include "flash.h"
#include "flash_m25p16.h"
#include "drivers/bus_spi.h"
#include "drivers/io.h"
#include "drivers/time.h"
static flashPartitionTable_t flashPartitionTable;
static int flashPartitions = 0;
#ifdef USE_SPI
static bool flashSpiInit(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_init(0);
#endif
return false;
}
#endif // USE_SPI
bool flashDeviceInit(void)
{
#ifdef USE_SPI
return flashSpiInit();
#endif
return false;
}
bool flashIsReady(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_isReady();
#endif
return false;
}
bool flashWaitForReady(uint32_t timeoutMillis)
{
#ifdef USE_FLASH_M25P16
return m25p16_waitForReady(timeoutMillis);
#endif
return false;
}
void flashEraseSector(uint32_t address)
{
#ifdef USE_FLASH_M25P16
return m25p16_eraseSector(address);
#endif
}
void flashEraseCompletely(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_eraseCompletely();
#endif
}
#if 0
void flashPageProgramBegin(uint32_t address)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgramBegin(address);
#endif
}
void flashPageProgramContinue(const uint8_t *data, int length)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgramContinue(data, length);
#endif
}
void flashPageProgramFinish(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgramFinish();
#endif
}
#endif
uint32_t flashPageProgram(uint32_t address, const uint8_t *data, int length)
{
#ifdef USE_FLASH_M25P16
return m25p16_pageProgram(address, data, length);
#endif
}
int flashReadBytes(uint32_t address, uint8_t *buffer, int length)
{
#ifdef USE_FLASH_M25P16
return m25p16_readBytes(address, buffer, length);
#endif
return 0;
}
void flashFlush(void)
{
}
const flashGeometry_t *flashGetGeometry(void)
{
#ifdef USE_FLASH_M25P16
return m25p16_getGeometry();
#endif
return NULL;
}
/*
* Flash partitioning
*
* Partition table is not currently stored on the flash, in-memory only.
*
* Partitions are required so that Badblock management (inc spare blocks), FlashFS (Blackbox Logging), Configuration and Firmware can be kept separate and tracked.
*
* XXX FIXME
* XXX Note that Flash FS must start at sector 0.
* XXX There is existing blackbox/flash FS code the relies on this!!!
* XXX This restriction can and will be fixed by creating a set of flash operation functions that take partition as an additional parameter.
*/
static __attribute__((unused)) void createPartition(flashPartitionType_e type, uint32_t size, flashSector_t *endSector)
{
const flashGeometry_t *flashGeometry = flashGetGeometry();
flashSector_t partitionSectors = (size / flashGeometry->sectorSize);
if (size % flashGeometry->sectorSize > 0) {
partitionSectors++; // needs a portion of a sector.
}
flashSector_t startSector = (*endSector + 1) - partitionSectors; // + 1 for inclusive
flashPartitionSet(type, startSector, *endSector);
*endSector = startSector - 1;
}
static void flashConfigurePartitions(void)
{
const flashGeometry_t *flashGeometry = flashGetGeometry();
if (flashGeometry->totalSize == 0) {
return;
}
flashSector_t startSector = 0;
flashSector_t endSector = flashGeometry->sectors - 1; // 0 based index
const flashPartition_t *badBlockPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT);
if (badBlockPartition) {
endSector = badBlockPartition->startSector - 1;
}
#if defined(FIRMWARE_SIZE)
createPartition(FLASH_PARTITION_TYPE_FIRMWARE, FIRMWARE_SIZE*1024, &endSector);
#endif
#if defined(MSP_FIRMWARE_UPDATE)
createPartition(FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META, flashGeometry->sectorSize, &endSector);
createPartition(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE, FLASH_SIZE*1024, &endSector);
createPartition(FLASH_PARTITION_TYPE_FULL_BACKUP, FLASH_SIZE*1024, &endSector);
#endif
#if defined(CONFIG_IN_EXTERNAL_FLASH)
createPartition(FLASH_PARTITION_TYPE_CONFIG, EEPROM_SIZE, &endSector);
#endif
#ifdef USE_FLASHFS
flashPartitionSet(FLASH_PARTITION_TYPE_FLASHFS, startSector, endSector);
#endif
}
flashPartition_t *flashPartitionFindByType(uint8_t type)
{
for (int index = 0; index < FLASH_MAX_PARTITIONS; index++) {
flashPartition_t *candidate = &flashPartitionTable.partitions[index];
if (candidate->type == type) {
return candidate;
}
}
return NULL;
}
const flashPartition_t *flashPartitionFindByIndex(uint8_t index)
{
if (index >= flashPartitions) {
return NULL;
}
return &flashPartitionTable.partitions[index];
}
void flashPartitionSet(uint8_t type, uint32_t startSector, uint32_t endSector)
{
flashPartition_t *entry = flashPartitionFindByType(type);
if (!entry) {
if (flashPartitions == FLASH_MAX_PARTITIONS - 1) {
return;
}
entry = &flashPartitionTable.partitions[flashPartitions++];
}
entry->type = type;
entry->startSector = startSector;
entry->endSector = endSector;
}
// Must be in sync with FLASH_PARTITION_TYPE
static const char *flashPartitionNames[] = {
"UNKNOWN ",
"PARTITION",
"FLASHFS ",
"BBMGMT ",
"FIRMWARE ",
"CONFIG ",
"FW UPDT ",
};
const char *flashPartitionGetTypeName(flashPartitionType_e type)
{
if (type < ARRAYLEN(flashPartitionNames)) {
return flashPartitionNames[type];
}
return NULL;
}
bool flashInit(void)
{
memset(&flashPartitionTable, 0x00, sizeof(flashPartitionTable));
bool haveFlash = flashDeviceInit();
flashConfigurePartitions();
return haveFlash;
}
int flashPartitionCount(void)
{
return flashPartitions;
}
uint32_t flashPartitionSize(flashPartition_t *partition)
{
const flashGeometry_t * const geometry = flashGetGeometry();
return (partition->endSector - partition->startSector + 1) * geometry->sectorSize;
}
void flashPartitionErase(flashPartition_t *partition)
{
const flashGeometry_t * const geometry = flashGetGeometry();
for (unsigned i = partition->startSector; i <= partition->endSector; i++) {
uint32_t flashAddress = geometry->sectorSize * i;
flashEraseSector(flashAddress);
flashWaitForReady(0);
}
}
#endif // USE_FLASH_CHIP

View file

@ -1,31 +1,94 @@
/*
* This file is part of Cleanflight.
* This file is part of iNav.
*
* 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.
* iNav is free software. You can redistribute
* this software and/or modify this software 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.
* iNav 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/>.
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
//#include "drivers/io.h"
//#ifdef USE_FLASHFS
typedef uint16_t flashSector_t;
typedef struct flashGeometry_s {
uint16_t sectors; // Count of the number of erasable blocks on the device
uint16_t pagesPerSector;
const uint16_t pageSize; // In bytes
flashSector_t sectors; // Count of the number of erasable blocks on the device
uint16_t pageSize; // In bytes
uint32_t sectorSize; // This is just pagesPerSector * pageSize
uint32_t totalSize; // This is just sectorSize * sectors
uint16_t pagesPerSector;
} flashGeometry_t;
bool flashInit(void);
bool flashIsReady(void);
bool flashWaitForReady(uint32_t timeoutMillis);
void flashEraseSector(uint32_t address);
void flashEraseCompletely(void);
#if 0
void flashPageProgramBegin(uint32_t address);
void flashPageProgramContinue(const uint8_t *data, int length);
void flashPageProgramFinish(void);
#endif
uint32_t flashPageProgram(uint32_t address, const uint8_t *data, int length);
int flashReadBytes(uint32_t address, uint8_t *buffer, int length);
void flashFlush(void);
const flashGeometry_t *flashGetGeometry(void);
//
// flash partitioning api
//
typedef struct flashPartition_s {
uint8_t type;
flashSector_t startSector;
flashSector_t endSector;
} flashPartition_t;
#define FLASH_PARTITION_SECTOR_COUNT(partition) (partition->endSector + 1 - partition->startSector) // + 1 for inclusive, start and end sector can be the same sector.
// Must be in sync with flashPartitionTypeNames[]
// Should not be deleted or reordered once the code is writing a table to a flash.
typedef enum {
FLASH_PARTITION_TYPE_UNKNOWN = 0,
FLASH_PARTITION_TYPE_PARTITION_TABLE,
FLASH_PARTITION_TYPE_FLASHFS,
FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
FLASH_PARTITION_TYPE_FIRMWARE,
FLASH_PARTITION_TYPE_CONFIG,
FLASH_PARTITION_TYPE_FULL_BACKUP,
FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META,
FLASH_PARTITION_TYPE_UPDATE_FIRMWARE,
FLASH_MAX_PARTITIONS
} flashPartitionType_e;
typedef struct flashPartitionTable_s {
flashPartition_t partitions[FLASH_MAX_PARTITIONS];
} flashPartitionTable_t;
void flashPartitionSet(uint8_t index, uint32_t startSector, uint32_t endSector);
flashPartition_t *flashPartitionFindByType(flashPartitionType_e type);
const flashPartition_t *flashPartitionFindByIndex(uint8_t index);
const char *flashPartitionGetTypeName(flashPartitionType_e type);
int flashPartitionCount(void);
uint32_t flashPartitionSize(flashPartition_t *partition);
void flashPartitionErase(flashPartition_t *partition);
//#endif [> USE_FLASHFS <]

View file

@ -118,7 +118,7 @@ bool m25p16_waitForReady(uint32_t timeoutMillis)
{
uint32_t time = millis();
while (!m25p16_isReady()) {
if (millis() - time > timeoutMillis) {
if (timeoutMillis && (millis() - time > timeoutMillis)) {
return false;
}
}

88
src/main/drivers/irlock.c Normal file
View file

@ -0,0 +1,88 @@
/*
* This file is part of iNav.
*
* iNav 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.
*
* iNav 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 iNav. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <math.h>
#include "platform.h"
#include "drivers/sensor.h"
#include "drivers/irlock.h"
#include "drivers/time.h"
#define IRLOCK_OBJECT_SYNC ((uint16_t)0xaa55)
#define IRLOCK_FRAME_SYNC ((uint32_t)(IRLOCK_OBJECT_SYNC | (IRLOCK_OBJECT_SYNC << 16)))
#if defined(USE_NAV) && defined(USE_IRLOCK)
static bool irlockHealthy = false;
static bool irlockFrameSync(irlockDev_t *irlockDev)
{
uint32_t sync_word = 0;
uint8_t count = 10;
while (count-- && sync_word != IRLOCK_FRAME_SYNC) {
uint8_t sync_byte;
irlockHealthy = busRead(irlockDev->busDev, 0xFF, &sync_byte);
if (!(irlockHealthy && sync_byte)) return false;
sync_word = (sync_word >> 8) | (((uint32_t)sync_byte) << 24);
}
return sync_word == IRLOCK_FRAME_SYNC;
}
static bool irlockRead(irlockDev_t *irlockDev, irlockData_t *irlockData)
{
if (irlockFrameSync(irlockDev) && busReadBuf(irlockDev->busDev, 0xFF, (void*)irlockData, sizeof(*irlockData))) {
uint16_t cksum = irlockData->signature + irlockData->posX + irlockData->posY + irlockData->sizeX + irlockData->sizeY;
if (irlockData->cksum == cksum) return true;
}
return false;
}
static bool deviceDetect(irlockDev_t *irlockDev)
{
uint8_t buf;
bool detected = busRead(irlockDev->busDev, 0xFF, &buf);
return !!detected;
}
bool irlockDetect(irlockDev_t *irlockDev)
{
irlockDev->busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_IRLOCK, 0, OWNER_IRLOCK);
if (irlockDev->busDev == NULL) {
return false;
}
if (!deviceDetect(irlockDev)) {
busDeviceDeInit(irlockDev->busDev);
return false;
}
irlockDev->read = irlockRead;
return true;
}
bool irlockIsHealthy(void)
{
return irlockHealthy;
}
#endif /* USE_IRLOCK */

45
src/main/drivers/irlock.h Normal file
View file

@ -0,0 +1,45 @@
/*
* This file is part of iNav.
*
* iNav 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.
*
* iNav 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 iNav. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "drivers/sensor.h"
#include "drivers/io_types.h"
#if defined(USE_NAV) && defined(USE_IRLOCK)
#define IRLOCK_RES_X 320
#define IRLOCK_RES_Y 200
typedef struct {
uint16_t cksum;
uint16_t signature;
uint16_t posX;
uint16_t posY;
uint16_t sizeX;
uint16_t sizeY;
} irlockData_t;
typedef struct irlockDev_s {
busDevice_t *busDev;
bool (*read)(struct irlockDev_s *irlockDev, irlockData_t *irlockData);
} irlockDev_t;
bool irlockDetect(irlockDev_t *irlockDev);
bool irlockIsHealthy(void);
#endif /* USE_IRLOCK */

View file

@ -2,43 +2,25 @@
#pragma once
// can't use 0
#define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1)
#define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_BARO_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_SONAR_EXTI NVIC_BUILD_PRIORITY(2, 0) // maybe increate slightly
#define NVIC_PRIO_TRANSPONDER_DMA NVIC_BUILD_PRIORITY(3, 0)
#define NVIC_PRIO_GYRO_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
#define NVIC_PRIO_SERIALUART1 NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART2 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART3 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART4 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART5 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART6 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART7 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART8 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_I2C_ER 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_WUP NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SONAR_ECHO NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MPU_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAX7456_DMA NVIC_BUILD_PRIORITY(3, 0)
// NVIC_SetPriority expects priority encoded according to priority grouping
// We allocate zero bits for sub-priority, therefore we have 16 priorities to use on STM32
// can't use 0
#define NVIC_PRIO_MAX 1
#define NVIC_PRIO_I2C_ER 2
#define NVIC_PRIO_I2C_EV 2
#define NVIC_PRIO_TIMER 3
#define NVIC_PRIO_TIMER_DMA 3
#define NVIC_PRIO_SDIO 3
#define NVIC_PRIO_GYRO_INT_EXTI 4
#define NVIC_PRIO_USB 5
#define NVIC_PRIO_SERIALUART 5
#define NVIC_PRIO_SONAR_EXTI 7
// Use all available bits for priority and zero bits to sub-priority
#ifdef USE_HAL_DRIVER
// utility macros to join/split priority
#define NVIC_PRIORITY_GROUPING NVIC_PRIORITYGROUP_2
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING)))))<<4)&0xf0)
#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING))))>>4)
#define NVIC_PRIORITY_SUB(prio) (((prio)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING))))>>4)
#define NVIC_PRIORITY_GROUPING NVIC_PRIORITYGROUP_4
#else
// utility macros to join/split priority
#define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_2
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4)&0xf0)
#define NVIC_PRIORITY_BASE(prio) (((prio)>>(4-(7-(NVIC_PRIORITY_GROUPING>>8))))>>4)
#define NVIC_PRIORITY_SUB(prio) (((prio)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8))))>>4)
#define NVIC_PRIORITY_GROUPING NVIC_PriorityGroup_4
#endif

View file

@ -56,12 +56,12 @@ static void osdGridBufferConstrainRect(int *x, int *y, int *w, int *h, int total
*y = 0;
}
int maxX = *x + *w;
int extraWidth = maxX - totalWidth;
int extraWidth = maxX - totalWidth + 1;
if (extraWidth > 0) {
*w -= extraWidth;
}
int maxY = *y + *h;
int extraHeight = maxY - totalHeight;
int extraHeight = maxY - totalHeight + 1;
if (extraHeight > 0) {
*h -= extraHeight;
}

View file

@ -117,7 +117,7 @@
#define SYM_3D_MPH 0x8A // 138 MPH 3D
#define SYM_RPM 0x8B // 139 RPM
// 0x8C // 140 -
#define SYM_WAYPOINT 0x8C // 140 Waypoint
// 0x8D // 141 -
// 0x8E // 142 -
// 0x8F // 143 -
@ -205,6 +205,7 @@
#define SYM_BARO_TEMP 0xF0 // 240
#define SYM_IMU_TEMP 0xF1 // 241
#define SYM_TEMP 0xF2 // 242
#define SYM_ESC_TEMP 0xF3 // 243
#define SYM_TEMP_SENSOR_FIRST 0xF2 // 242
#define SYM_TEMP_SENSOR_LAST 0xF7 // 247

View file

@ -0,0 +1,119 @@
/*
* This file is part of iNav.
*
* iNav free software. You can redistribute
* this software and/or modify this software 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.
*
* iNav distributed in the hope that it
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* An implementation of persistent data storage utilizing RTC backup data register.
* Retains values written across software resets and boot loader activities.
*/
#include <stdint.h>
#include "platform.h"
#include "drivers/persistent.h"
#include "drivers/system.h"
#define PERSISTENT_OBJECT_MAGIC_VALUE (('i' << 24)|('N' << 16)|('a' << 8)|('v' << 0))
#ifdef USE_HAL_DRIVER
uint32_t persistentObjectRead(persistentObjectId_e id)
{
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
uint32_t value = HAL_RTCEx_BKUPRead(&rtcHandle, id);
return value;
}
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
{
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
HAL_RTCEx_BKUPWrite(&rtcHandle, id, value);
}
void persistentObjectRTCEnable(void)
{
RTC_HandleTypeDef rtcHandle = { .Instance = RTC };
#if !defined(STM32H7)
__HAL_RCC_PWR_CLK_ENABLE(); // Enable Access to PWR
#endif
HAL_PWR_EnableBkUpAccess(); // Disable backup domain protection
#if defined(__HAL_RCC_RTC_CLK_ENABLE)
// For those MCUs with RTCAPBEN bit in RCC clock enable register, turn it on.
__HAL_RCC_RTC_CLK_ENABLE(); // Enable RTC module
#endif
// We don't need a clock source for RTC itself. Skip it.
__HAL_RTC_WRITEPROTECTION_ENABLE(&rtcHandle); // Reset sequence
__HAL_RTC_WRITEPROTECTION_DISABLE(&rtcHandle); // Apply sequence
}
#else
uint32_t persistentObjectRead(persistentObjectId_e id)
{
uint32_t value = RTC_ReadBackupRegister(id);
return value;
}
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
{
RTC_WriteBackupRegister(id, value);
}
void persistentObjectRTCEnable(void)
{
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE); // Enable Access to PWR
PWR_BackupAccessCmd(ENABLE); // Disable backup domain protection
// We don't need a clock source for RTC itself. Skip it.
RTC_WriteProtectionCmd(ENABLE); // Reset sequence
RTC_WriteProtectionCmd(DISABLE); // Apply sequence
}
#endif
void persistentObjectInit(void)
{
// Configure and enable RTC for backup register access
persistentObjectRTCEnable();
// XXX Magic value checking may be sufficient
uint32_t wasSoftReset;
#ifdef STM32H7
wasSoftReset = RCC->RSR & RCC_RSR_SFTRSTF;
#else
wasSoftReset = RCC->CSR & RCC_CSR_SFTRSTF;
#endif
if (!wasSoftReset || (persistentObjectRead(PERSISTENT_OBJECT_MAGIC) != PERSISTENT_OBJECT_MAGIC_VALUE)) {
for (int i = 1; i < PERSISTENT_OBJECT_COUNT; i++) {
persistentObjectWrite(i, 0);
}
persistentObjectWrite(PERSISTENT_OBJECT_MAGIC, PERSISTENT_OBJECT_MAGIC_VALUE);
}
}

View file

@ -0,0 +1,43 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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 and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <stdint.h>
// Available RTC backup registers (4-byte words) per MCU type
// F4: 20 words
// F7: 32 words
// H7: 32 words
typedef enum {
PERSISTENT_OBJECT_MAGIC = 0,
PERSISTENT_OBJECT_RESET_REASON,
PERSISTENT_OBJECT_COUNT,
} persistentObjectId_e;
// Values for PERSISTENT_OBJECT_RESET_REASON
#define RESET_NONE 0
#define RESET_BOOTLOADER_REQUEST_ROM 1
#define RESET_MSC_REQUEST 2 // MSC invocation was requested
void persistentObjectInit(void);
uint32_t persistentObjectRead(persistentObjectId_e id);
void persistentObjectWrite(persistentObjectId_e id, uint32_t value);

View file

@ -268,7 +268,7 @@ static bool motorsUseHardwareTimers(void)
static bool servosUseHardwareTimers(void)
{
return !feature(FEATURE_PWM_SERVO_DRIVER);
return servoConfig()->servo_protocol == SERVO_TYPE_PWM;
}
static void pwmInitMotors(timMotorServoHardware_t * timOutputs)

View file

@ -49,6 +49,12 @@ typedef enum {
PWM_TYPE_SERIALSHOT,
} motorPwmProtocolTypes_e;
typedef enum {
SERVO_TYPE_PWM = 0,
SERVO_TYPE_SERVO_DRIVER,
SERVO_TYPE_SBUS
} servoProtocolType_e;
typedef enum {
PWM_INIT_ERROR_NONE = 0,
PWM_INIT_ERROR_TOO_MANY_MOTORS,

View file

@ -22,6 +22,8 @@
#include "platform.h"
FILE_COMPILE_FOR_SPEED
#include "build/debug.h"
#include "common/log.h"
@ -35,6 +37,7 @@
#include "io/pwmdriver_i2c.h"
#include "io/esc_serialshot.h"
#include "io/servo_sbus.h"
#include "sensors/esc_sensor.h"
#include "config/feature.h"
@ -325,6 +328,10 @@ bool isMotorProtocolDigital(void)
void pwmRequestMotorTelemetry(int motorIndex)
{
if (!isMotorProtocolDigital()) {
return;
}
const int motorCount = getMotorCount();
for (int index = 0; index < motorCount; index++) {
if (motors[index].pwmPort && motors[index].pwmPort->configured && index == motorIndex) {
@ -343,10 +350,6 @@ void pwmCompleteMotorUpdate(void)
int motorCount = getMotorCount();
timeUs_t currentTimeUs = micros();
#ifdef USE_ESC_SENSOR
escSensorUpdate(currentTimeUs);
#endif
// Enforce motor update rate
if ((digitalMotorUpdateIntervalUs == 0) || ((currentTimeUs - digitalMotorLastUpdateUs) <= digitalMotorUpdateIntervalUs)) {
return;
@ -385,6 +388,15 @@ void pwmCompleteMotorUpdate(void)
}
#endif
}
#else // digital motor protocol
// This stub is needed to avoid ESC_SENSOR dependency on DSHOT
void pwmRequestMotorTelemetry(int motorIndex)
{
UNUSED(motorIndex);
}
#endif
void pwmMotorPreconfigure(void)
@ -415,10 +427,6 @@ void pwmMotorPreconfigure(void)
case PWM_TYPE_DSHOT600:
case PWM_TYPE_DSHOT300:
case PWM_TYPE_DSHOT150:
#ifdef USE_ESC_SENSOR
// DSHOT supports a dedicated wire ESC telemetry. Kick off the ESC-sensor receiver initialization
escSensorInitialize();
#endif
motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate);
motorWritePtr = pwmWriteDigital;
break;
@ -505,14 +513,27 @@ static void pwmServoWriteExternalDriver(uint8_t index, uint16_t value)
void pwmServoPreconfigure(void)
{
servoWritePtr = pwmServoWriteStandard;
// Protocol-specific configuration
switch (servoConfig()->servo_protocol) {
default:
case SERVO_TYPE_PWM:
servoWritePtr = pwmServoWriteStandard;
break;
#ifdef USE_PWM_SERVO_DRIVER
// If PCA9685 is enabled - switch the servo write function to external
if (feature(FEATURE_PWM_SERVO_DRIVER)) {
servoWritePtr = pwmServoWriteExternalDriver;
}
case SERVO_TYPE_SERVO_DRIVER:
pwmDriverInitialize();
servoWritePtr = pwmServoWriteExternalDriver;
break;
#endif
#ifdef USE_SERVO_SBUS
case SERVO_TYPE_SBUS:
sbusServoInitialize();
servoWritePtr = sbusServoUpdate;
break;
#endif
}
}
bool pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput)

View file

@ -22,7 +22,7 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
"RANGEFINDER", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD",
"BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER",
"NRF24", "VTX", "SPI_PREINIT", "COMPASS", "TEMPERATURE", "1-WIRE", "AIRSPEED", "OLED DISPLAY",
"PINIO"
"PINIO", "IRLOCK"
};
const char * const resourceNames[RESOURCE_TOTAL_COUNT] = {

View file

@ -56,6 +56,7 @@ typedef enum {
OWNER_AIRSPEED,
OWNER_OLED_DISPLAY,
OWNER_PINIO,
OWNER_IRLOCK,
OWNER_TOTAL_COUNT
} resourceOwner_e;

View file

@ -1411,12 +1411,8 @@ bool SD_Initialize_LL(DMA_Stream_TypeDef *dmaRef)
IOConfigGPIOAF(cmd, SDIO_CMD, GPIO_AF_SDIO);
// NVIC configuration for SDIO interrupts
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = SDIO_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(1);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(0);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(SDIO_IRQn, NVIC_PRIO_SDIO);
NVIC_EnableIRQ(SDIO_IRQn);
dma_stream = dmaRef;
RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;

View file

@ -1329,10 +1329,8 @@ bool SD_Initialize_LL(DMA_Stream_TypeDef * dmaRef)
IOInit(cmd, OWNER_SDCARD, RESOURCE_NONE, 0);
IOConfigGPIOAF(cmd, SDMMC_CMD, GPIO_AF12_SDMMC1);
uint32_t PriorityGroup = NVIC_GetPriorityGrouping();
// NVIC configuration for SDIO interrupts
NVIC_SetPriority(SDMMC1_IRQn, NVIC_EncodePriority(PriorityGroup, 1, 0));
NVIC_SetPriority(SDMMC1_IRQn, NVIC_PRIO_SDIO);
NVIC_EnableIRQ(SDMMC1_IRQn);
dma_stream = dmaRef;

View file

@ -169,7 +169,6 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui
#ifdef USE_UART1
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
{
NVIC_InitTypeDef NVIC_InitStructure;
uartPort_t *s;
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
@ -191,11 +190,8 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1);
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(USART1_IRQn, NVIC_PRIO_SERIALUART);
NVIC_EnableIRQ(USART1_IRQn);
return s;
}
@ -204,7 +200,6 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
#ifdef USE_UART2
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
{
NVIC_InitTypeDef NVIC_InitStructure;
uartPort_t *s;
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
@ -226,11 +221,8 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7, 2);
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(USART2_IRQn, NVIC_PRIO_SERIALUART);
NVIC_EnableIRQ(USART2_IRQn);
return s;
}
@ -239,7 +231,6 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
#ifdef USE_UART3
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
{
NVIC_InitTypeDef NVIC_InitStructure;
uartPort_t *s;
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
@ -261,11 +252,8 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7, 3);
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(USART3_IRQn, NVIC_PRIO_SERIALUART);
NVIC_EnableIRQ(USART3_IRQn);
return s;
}
@ -277,7 +265,6 @@ uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t option
uartPort_t *s;
static volatile uint8_t rx4Buffer[UART4_RX_BUFFER_SIZE];
static volatile uint8_t tx4Buffer[UART4_TX_BUFFER_SIZE];
NVIC_InitTypeDef NVIC_InitStructure;
s = &uartPort4;
s->port.vTable = uartVTable;
@ -295,11 +282,8 @@ uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t option
serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5, 4);
NVIC_InitStructure.NVIC_IRQChannel = UART4_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART4);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART4);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(UART4_IRQn, NVIC_PRIO_SERIALUART);
NVIC_EnableIRQ(UART4_IRQn);
return s;
}
@ -311,7 +295,6 @@ uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t option
uartPort_t *s;
static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE];
static volatile uint8_t tx5Buffer[UART5_TX_BUFFER_SIZE];
NVIC_InitTypeDef NVIC_InitStructure;
s = &uartPort5;
s->port.vTable = uartVTable;
@ -329,11 +312,8 @@ uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t option
serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5, 5);
NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART5);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(UART5_IRQn, NVIC_PRIO_SERIALUART);
NVIC_EnableIRQ(UART5_IRQn);
return s;
}

View file

@ -60,7 +60,7 @@ static uartDevice_t uart1 =
#endif
.rcc_apb2 = RCC_APB2(USART1),
.irq = USART1_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART1
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -76,7 +76,7 @@ static uartDevice_t uart2 =
#endif
.rcc_apb1 = RCC_APB1(USART2),
.irq = USART2_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART2
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -92,7 +92,7 @@ static uartDevice_t uart3 =
#endif
.rcc_apb1 = RCC_APB1(USART3),
.irq = USART3_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART3
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -108,7 +108,7 @@ static uartDevice_t uart4 =
#endif
.rcc_apb1 = RCC_APB1(UART4),
.irq = UART4_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART4
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -124,7 +124,7 @@ static uartDevice_t uart5 =
#endif
.rcc_apb1 = RCC_APB1(UART5),
.irq = UART5_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART5
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -140,7 +140,7 @@ static uartDevice_t uart6 =
#endif
.rcc_apb2 = RCC_APB2(USART6),
.irq = USART6_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART6
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -153,7 +153,7 @@ static uartDevice_t uart7 =
.af = GPIO_AF_UART7,
.rcc_apb1 = RCC_APB1(UART7),
.irq = UART7_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART7
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -166,7 +166,7 @@ static uartDevice_t uart8 =
.af = GPIO_AF_UART8,
.rcc_apb1 = RCC_APB1(UART8),
.irq = UART8_IRQn,
.irqPriority = NVIC_PRIO_SERIALUART8
.irqPriority = NVIC_PRIO_SERIALUART
};
#endif
@ -256,7 +256,6 @@ void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins)
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options)
{
uartPort_t *s;
NVIC_InitTypeDef NVIC_InitStructure;
uartDevice_t *uart = uartHardwareMap[device];
if (!uart) return NULL;
@ -304,11 +303,8 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode,
}
}
NVIC_InitStructure.NVIC_IRQChannel = uart->irq;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(uart->irqPriority);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(uart->irqPriority);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_SetPriority(uart->irq, uart->irqPriority);
NVIC_EnableIRQ(uart->irq);
return s;
}

Some files were not shown because too many files have changed in this diff Show more