Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/development' into development
Browse files Browse the repository at this point in the history
  • Loading branch information
ted-rcnet committed Apr 2, 2018
2 parents 0166261 + af55401 commit a299fd5
Show file tree
Hide file tree
Showing 12 changed files with 133 additions and 96 deletions.
15 changes: 8 additions & 7 deletions docs/Battery.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ When dealing with batteries **ALWAYS CHECK POLARITY!**
Measure expected voltages **first** and then connect to the flight controller. Powering the flight controller with
incorrect voltage or reversed polarity will likely fry your flight controller. Ensure your flight controller
has a voltage divider capable of measuring your particular battery voltage.
On the first battery connection is always advisable to use a current limiter device to limit damages if something is wrong in the setup.

### Naze32

Expand Down Expand Up @@ -53,19 +54,19 @@ Configure min/max cell voltages using the following CLI setting:

`vbat_scale` - Adjust this to match actual measured battery voltage to reported value.

`vbat_max_cell_voltage` - Maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, i.e. 43 = 4.3V
`vbat_max_cell_voltage` - Maximum voltage per cell, used for auto-detecting battery voltage in 0.01V units, i.e. 430 = 4.30V

`set vbat_warning_cell_voltage` - Warning voltage per cell; this triggers battery-out alarms, in 0.1V units, i.e. 34 = 3.4V
`set vbat_warning_cell_voltage` - Warning voltage per cell; this triggers battery-out alarms, in 0.01V units, i.e. 340 = 3.40V

`vbat_min_cell_voltage` - Minimum voltage per cell; this triggers battery-out alarms, in 0.1V units, i.e. 33 = 3.3V
`vbat_min_cell_voltage` - Minimum voltage per cell; this triggers battery-out alarms, in 0.01V units, i.e. 330 = 3.30V

e.g.

```
set vbat_scale = 110
set vbat_max_cell_voltage = 43
set vbat_warning_cell_voltage = 34
set vbat_min_cell_voltage = 33
set vbat_scale = 1100
set vbat_max_cell_voltage = 430
set vbat_warning_cell_voltage = 340
set vbat_min_cell_voltage = 330
```

# Current Monitoring
Expand Down
4 changes: 4 additions & 0 deletions docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,9 @@ Re-apply any new defaults as desired.
| align_board_roll | 0 | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc |
| align_board_pitch | 0 | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc |
| align_board_yaw | 0 | Arbitrary board rotation in degrees, to allow mounting it sideways / upside down / rotated etc |
| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. |
| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. |
| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. |
| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. |
| moron_threshold | 32 | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. |
| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements |
Expand Down Expand Up @@ -397,6 +400,7 @@ Re-apply any new defaults as desired.
| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% |
| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. |
| tpa_breakpoint | 1500 | See tpa_rate. |
| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups |
| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot |
| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot |
| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection |
Expand Down
139 changes: 63 additions & 76 deletions docs/development/Building in Ubuntu.md
100755 → 100644
Original file line number Diff line number Diff line change
@@ -1,123 +1,110 @@
# Building in Ubuntu

Building for Ubuntu platform is remarkably easy. The only trick to understand is that the Ubuntu toolchain,
which they are downstreaming from Debian, is not compatible with INAV. We suggest that you take an
alternative PPA from Terry Guo, found here:
https://launchpad.net/~terry.guo/+archive/ubuntu/gcc-arm-embedded
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.

This PPA has several compiler versions and platforms available. For many hardware platforms (notably Naze)
the 4.9.3 compiler will work fine. For some, older compiler 4.8 (notably Sparky) is more appropriate. We
suggest you build with 4.9.3 first, and try to see if you can connect to the CLI or run the Configurator.
If you cannot, please see the section below for further hints on what you might do.
As of March 2018, the recommendation for Ubuntu releases is:

## Setup GNU ARM Toolchain
| 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 distro compiler (6.3+) |

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

Note specifically the last paragraph of Terry's PPA documentation -- Ubuntu carries its own package for
`gcc-arm-none-eabi`, so you'll have to remove it, and then pin the one from the PPA.
For your release, you should first remove any older pacakges (from Debian or Ubuntu directly), introduce
Terry's PPA, and update:
```
sudo apt-get remove binutils-arm-none-eabi gcc-arm-none-eabi
sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded
sudo apt-get update
$ apt show gcc-arm-none-eabi
...
Version: 15:4.9.3+svn231177-1
```

For Linux Mint 18 (Ubuntu 16, 2016-09-11)
```
sudo apt install git
sudo apt install gcc
sudo apt install gcc-arm-none-eabi
This 4.9.3 and will not build iNav, so we need the PPA.

## Installer commands

sudo apt-get install libnewlib-arm-none-eabi
Older versions of Debian / Ubuntu and derivatives use the `apt-get` command; newer versions use `apt`. Use the appropriate command for your release.

cd src
git clone https://github.com/iNavFlight/inav.git
cd inav
make TARGET=NAZE
```
# Prerequisites

For Ubuntu 14.10 (current release, called Utopic Unicorn), you should pin:
```
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0utopic12
```
Regardless of the cross-compiler version, it is necessary to install some other tools:

For Ubuntu 14.04 (an LTS as of Q1'2015, called Trusty Tahr), you should pin:
```
sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0trusty12
sudo apt install git
sudo apt install gcc
sudo apt install ruby
```

For Ubuntu 12.04 (previous LTS, called Precise Penguin), you should pin:
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 install gcc-arm-none-eabi=4.9.3.2014q4-0precise12
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
```

## Install Ruby
# Using the Distro compiler

Install the Ruby package for your distribution. On Debian based distributions, you should
install the ruby package
For Releases after 17.10 is is recommended to use the distro provided compiler, at least until it proves to be too old.
```
sudo apt-get install ruby
sudo apt install gcc-arm-none-eabi
```

## Installing Ruby 2.4
# Using the PPA compiler

Since in some cases apt-get will install ruby 1.9 which does not work, you can force ruby 2.4 by
For releases prior to (and perhaps including) 17.10, the PPA compiler is used. This can be used on releases post 17.10 if you really wish to have a newer compiler than the distro default.

```
sudo apt-get remove ruby
sudo apt-add-repository ppa:brightbox/ruby-ng
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
apt-get install ruby2.4 ruby2.4-dev
sudo apt-get install gcc-arm-embedded
```

## Building on Ubuntu
After these steps, on Ubuntu 16.04, (at least of March 2018) you should now have:

After the ARM toolchain from Terry is installed, you should be able to build from source.
```
cd src
git clone git@github.com:iNavFlight/inav.git
cd inav
make TARGET=NAZE
$ arm-none-eabi-gcc -dumpversion
7.2.1
```

You'll see a set of files being compiled, and finally linked, yielding both an ELF and then a HEX:
```
...
arm-none-eabi-size ./obj/main/inav_NAZE.elf
text data bss dec hex filename
97164 320 11080 108564 1a814 ./obj/main/inav_NAZE.elf
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/inav_NAZE.elf obj/inav_NAZE.hex
$ ls -la obj/inav_NAZE.hex
-rw-rw-r-- 1 pim pim 274258 Jan 12 21:45 obj/inav_NAZE.hex
```
Which is more than adequate for our purposes.

# Building from the Github repository

You can use the INAV-Configurator to flash the ```obj/inav_NAZE.hex``` file.
After the ARM cross-compiler toolchain from is installed, you should be able to build from source.

## Bricked/Bad build?
```
mkdir src
cd src
git clone https://github.com/iNavFlight/inav.git
cd inav
make
```

Users have reported that the 4.9.3 compiler for ARM produces bad builds, for example on the Sparky hardware platform.
It is very likely that using an older compiler would be fine -- Terry happens to have also a 4.8 2014q2 build in his
PPA - to install this, you can fetch the `.deb` directly:
http://ppa.launchpad.net/terry.guo/gcc-arm-embedded/ubuntu/pool/main/g/gcc-arm-none-eabi/
If you have a github account with registered ssh key you can replace the `git clone` command with `git clone https://github.com/iNavFlight/inav.git` instead of the https link.

and use `dpkg` to install:
By default, this builds the SPRACINGF3 target, to build another target, specify the target name to the make command, for example:
```
sudo dpkg -i gcc-arm-none-eabi_4-8-2014q2-0saucy9_amd64.deb
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.

https://github.com/fiam/msp-tool and https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh provide / describe helper tools for command line flashing.

Make sure to remove `obj/` and `make clean`, before building again.
# Updating and rebuilding

## Updating and rebuilding
In order to update your local firmware build:

Navigate to the local INAV repository and use the following steps to pull the latest changes and rebuild your version of INAV:
* 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 reset --hard
git pull
make clean TARGET=NAZE
make
make TARGET=<TARGET>
```

Credit goes to K.C. Budd, AKfreak for testing, and pulsar for doing the long legwork that yielded this very short document.
16 changes: 14 additions & 2 deletions src/main/common/filter.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,18 +38,30 @@ float nullFilterApply(void *filter, float input)
// PT1 Low Pass filter

// f_cut = cutoff frequency
void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT)
void pt1FilterInitRC(pt1Filter_t *filter, float tau, float dT)
{
filter->RC = 1.0f / ( 2.0f * M_PIf * f_cut );
filter->RC = tau;
filter->dT = dT;
}

void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT)
{
pt1FilterInitRC(filter, 1.0f / (2.0f * M_PIf * f_cut), dT);
}

float pt1FilterApply(pt1Filter_t *filter, float input)
{
filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state);
return filter->state;
}

float pt1FilterApply3(pt1Filter_t *filter, float input, float dT)
{
filter->dT = dT;
filter->state = filter->state + dT / (filter->RC + dT) * (input - filter->state);
return filter->state;
}

float pt1FilterApply4(pt1Filter_t *filter, float input, uint16_t f_cut, float dT)
{
// Pre calculate and store RC
Expand Down
3 changes: 3 additions & 0 deletions src/main/common/filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,10 @@ typedef float (*filterApplyFnPtr)(void *filter, float input);

float nullFilterApply(void *filter, float input);

void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT);
void pt1FilterInitRC(pt1Filter_t *filter, float tau, float dT);
float pt1FilterApply(pt1Filter_t *filter, float input);
float pt1FilterApply3(pt1Filter_t *filter, float input, float dT);
float pt1FilterApply4(pt1Filter_t *filter, float input, uint16_t f_cut, float dt);
void pt1FilterReset(pt1Filter_t *filter, float input);

Expand Down
5 changes: 3 additions & 2 deletions src/main/fc/controlrate_profile.c
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
const controlRateConfig_t *currentControlRateProfile;


PG_REGISTER_ARRAY_WITH_RESET_FN(controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles, PG_CONTROL_RATE_PROFILES, 1);
PG_REGISTER_ARRAY_WITH_RESET_FN(controlRateConfig_t, MAX_CONTROL_RATE_PROFILE_COUNT, controlRateProfiles, PG_CONTROL_RATE_PROFILES, 2);

void pgResetFn_controlRateProfiles(controlRateConfig_t *instance)
{
Expand All @@ -43,7 +43,8 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance)
.rcMid8 = 50,
.rcExpo8 = 0,
.dynPID = 0,
.pa_breakpoint = 1500
.pa_breakpoint = 1500,
.fixedWingTauMs = 0
},

.stabilized = {
Expand Down
1 change: 1 addition & 0 deletions src/main/fc/controlrate_profile.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ typedef struct controlRateConfig_s {
uint8_t rcExpo8;
uint8_t dynPID;
uint16_t pa_breakpoint; // Breakpoint where TPA is activated
uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter
} throttle;

struct {
Expand Down
4 changes: 4 additions & 0 deletions src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -613,6 +613,10 @@ groups:
field: throttle.pa_breakpoint
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: fw_tpa_time_constant
field: throttle.fixedWingTauMs
min: 0
max: 5000
- name: rc_expo
field: stabilized.rcExpo8
min: 0
Expand Down
Loading

0 comments on commit a299fd5

Please sign in to comment.