Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master' into dzikuvx-rework-7804
Browse files Browse the repository at this point in the history
  • Loading branch information
DzikuVx committed Feb 22, 2022
2 parents b920d73 + 864fd42 commit b3a8cc2
Show file tree
Hide file tree
Showing 53 changed files with 1,420 additions and 132 deletions.
11 changes: 9 additions & 2 deletions build.sh
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
#!/usr/bin/env bash
set -e

if [[ $# == 0 ]]; then
Expand All @@ -6,9 +7,15 @@ Usage syntax: ./build.sh <TARGET>
Notes:
* You can specify multiple targets.
* If no targets are specified, *all* of them will be built.
./build.sh <TARGET_1> <TARGET_2> <TARGET_N>
* To get a list of all targets use \"help\". Hint: pipe the output through a pager.
./build.sh help | less
* To build all targets use \"all\"
./build.sh all
* To clean a target prefix it with \"clean_\".
* To clean all targets just use \"clean\"."
./build.sh clean_MATEKF405SE
* To clean all targets just use \"clean\".
./build.sh clean"
exit 1
fi

Expand Down
20 changes: 19 additions & 1 deletion docs/Battery.md
Original file line number Diff line number Diff line change
Expand Up @@ -195,7 +195,25 @@ Note that in this example even though your warning capacity (`battery_capacity_w

## Battery profiles

Up to 3 battery profiles are supported. You can select the battery profile from the GUI, OSD menu, [stick commands](Controls.md) and CLI command `battery_profile n`. Battery profiles store the following settings (see above for an explanation of each setting): `bat_cells`, `vbat_cell_detect_voltage`, `vbat_max_cell_voltage`, `vbat_warning_cell_voltage`, `vbat_min_cell_voltage`, `battery_capacity_unit`, `battery_capacity`, `battery_capacity_warning`, `battery_capacity_critical`
Up to 3 battery profiles are supported. You can select the battery profile from the GUI, OSD menu, [stick commands](Controls.md) and CLI command `battery_profile n`. Battery profiles store the following settings (see above for an explanation of each setting):
- `bat_cells`
- `vbat_cell_detect_voltage`
- `vbat_max_cell_voltage`
- `vbat_warning_cell_voltage`
- `vbat_min_cell_voltage`
- `battery_capacity_unit`
- `battery_capacity`
- `battery_capacity_warning`
- `battery_capacity_critical`
- `throttle_idle`
- `fw_min_throttle_down_pitch`
- `nav_fw_cruise_thr`
- `nav_fw_min_thr`
- `nav_fw_pitch2thr`
- `nav_fw_launch_thr`
- `nav_fw_launch_idle_thr`
- `failsafe_throttle`
- `nav_mc_hover_thr`

To enable the automatic battery profile switching based on battery voltage enable the `BAT_PROF_AUTOSWITCH` feature. For a profile to be automatically selected the number of cells of the battery needs to be specified (>0).

Expand Down
2 changes: 2 additions & 0 deletions docs/Programming Framework.md
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,8 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 40 | MOD | Divide `Operand A` by `Operand B` and returns the remainder |
| 41 | LOITER_RADIUS_OVERRIDE | Sets the loiter radius to `Operand A` [`0` : `100000`] in cm. If the value is lower than the loiter radius set in the **Advanced Tuning**, that will be used. |
| 42 | SET_PROFILE | Sets the active config profile (PIDFF/Rates/Filters/etc) to `Operand A`. `Operand A` must be a valid profile number, currently from 1 to 3. If not, the profile will not change |
| 43 | MIN | Finds the lowest value of `Operand A` and `Operand B` |
| 44 | MAX | Finds the highest value of `Operand A` and `Operand B` |

### Operands

Expand Down
78 changes: 74 additions & 4 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THR

| Default | Min | Max |
| --- | --- | --- |
| 1300 | 1000 | 2000 |
| 1150 | 1000 | 2000 |

---

Expand Down Expand Up @@ -1602,6 +1602,36 @@ Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro

---

### gyro_zero_x

Calculated gyro zero calibration of axis X

| Default | Min | Max |
| --- | --- | --- |
| 0 | -32768 | 32767 |

---

### gyro_zero_y

Calculated gyro zero calibration of axis Y

| Default | Min | Max |
| --- | --- | --- |
| 0 | -32768 | 32767 |

---

### gyro_zero_z

Calculated gyro zero calibration of axis Z

| Default | Min | Max |
| --- | --- | --- |
| 0 | -32768 | 32767 |

---

### has_flaps

Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot
Expand Down Expand Up @@ -2102,6 +2132,26 @@ _// TODO_

---

### init_gyro_cal

If defined to 'OFF', it will ignore the gyroscope calibration done at each startup. Instead, the gyroscope last calibration from when you calibrated will be used. It also means you don't have to keep the UAV stationary during a startup.

| Default | Min | Max |
| --- | --- | --- |
| ON | OFF | ON |

---

### ins_gravity_cmss

Calculated 1G of Acc axis Z to use in INS

| Default | Min | Max |
| --- | --- | --- |
| 0.0 | 0 | 1000 |

---

### iterm_windup

Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)
Expand Down Expand Up @@ -2818,7 +2868,7 @@ Craft name

| Default | Min | Max |
| --- | --- | --- |
| _empty_ | | |
| _empty_ | | MAX_NAME_LENGTH |

---

Expand Down Expand Up @@ -3852,6 +3902,16 @@ Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: AT

---

### nav_wp_enforce_altitude

Forces craft to achieve the set WP altitude as well as position before moving to next WP. Position is held and altitude adjusted as required before moving on.

| Default | Min | Max |
| --- | --- | --- |
| OFF | OFF | ON |

---

### nav_wp_load_on_boot

If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup.
Expand Down Expand Up @@ -4582,6 +4642,16 @@ Auto swap display time interval between disarm stats pages (seconds). Reverts to

---

### osd_system_msg_display_time

System message display cycle time for multiple messages (milliseconds).

| Default | Min | Max |
| --- | --- | --- |
| 1000 | 500 | 5000 |

---

### osd_telemetry

To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`
Expand Down Expand Up @@ -4624,7 +4694,7 @@ IMPERIAL, METRIC, UK

### osd_video_system

Video system used. Possible values are `AUTO`, `PAL` and `NTSC`
Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, and `HD`

| Default | Min | Max |
| --- | --- | --- |
Expand Down Expand Up @@ -5404,7 +5474,7 @@ Total flight distance [in meters]. The value is updated on every disarm when "st

### stats_total_energy

_// TODO_
Total energy consumption [in mWh]. The value is updated on every disarm when "stats" are enabled.

| Default | Min | Max |
| --- | --- | --- |
Expand Down
6 changes: 6 additions & 0 deletions docs/development/Building in Docker.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,12 @@ Where `<TARGET>` must be replaced with the name of the target that you want to b
./build.sh MATEKF405SE
```

Run the script with no arguments to get more details on its usage:

```
./build.sh
```

## Windows 10

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` .
Expand Down
2 changes: 2 additions & 0 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -496,6 +496,8 @@ main_sources(COMMON_SRC
io/displayport_msp.h
io/displayport_oled.c
io/displayport_oled.h
io/displayport_hdzero_osd.c
io/displayport_hdzero_osd.h
io/displayport_srxl.c
io/displayport_srxl.h
io/displayport_hott.c
Expand Down
1 change: 1 addition & 0 deletions src/main/cms/cms_menu_navigation.c
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,7 @@ static const OSD_Entry cmsx_menuMissionSettingsEntries[] =
OSD_SETTING_ENTRY("MISSION FAILSAFE", SETTING_FAILSAFE_MISSION),
OSD_SETTING_ENTRY("WP LOAD ON BOOT", SETTING_NAV_WP_LOAD_ON_BOOT),
OSD_SETTING_ENTRY("WP REACHED RADIUS", SETTING_NAV_WP_RADIUS),
OSD_SETTING_ENTRY("WP ENFORCE ALTITUDE", SETTING_NAV_WP_ENFORCE_ALTITUDE),
OSD_SETTING_ENTRY("WP SAFE DISTANCE", SETTING_NAV_WP_SAFE_DISTANCE),
#ifdef USE_MULTI_MISSION
OSD_SETTING_ENTRY("MULTI MISSION NUMBER", SETTING_NAV_WP_MULTI_MISSION_INDEX),
Expand Down
2 changes: 2 additions & 0 deletions src/main/common/maths.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@
#define CMSEC_TO_CENTIKPH(cms) (cms * 3.6)
#define CMSEC_TO_CENTIKNOTS(cms) (cms * 1.943845)

#define C_TO_KELVIN(temp) (temp + 273.15f)

// copied from https://code.google.com/p/cxutil/source/browse/include/cxutil/utility.h#70
#define _CHOOSE2(binoper, lexpr, lvar, rexpr, rvar) \
( __extension__ ({ \
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/io_port_expander.c
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ void ioPortExpanderSync(void)
{
if (ioPortExpanderState.active && ioPortExpanderState.shouldSync) {
pcf8574Write(ioPortExpanderState.state);
ioPortExpanderState.shouldSync = false;;
ioPortExpanderState.shouldSync = false;
}
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/pitotmeter/pitotmeter_ms4525.c
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ static void ms4525_calculate(pitotDev_t * pitot, float *pressure, float *tempera
//float dP = ctx->ms4525_up * 10.0f * 0.1052120688f;
const float dP_psi = -((ctx->ms4525_up - 0.1f * 16383) * (P_max - P_min) / (0.8f * 16383) + P_min);
float dP = dP_psi * PSI_to_Pa;
float T = (float)(200.0f * (int32_t)ctx->ms4525_ut) / 2047.0f - 50.0f + 273.15f;
float T = C_TO_KELVIN((float)(200.0f * (int32_t)ctx->ms4525_ut) / 2047.0f - 50.0f);

if (pressure) {
*pressure = dP; // Pa
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/serial_softserial.c
Original file line number Diff line number Diff line change
Expand Up @@ -572,7 +572,7 @@ uint32_t softSerialTxBytesFree(const serialPort_t *instance)

softSerial_t *s = (softSerial_t *)instance;

uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
uint32_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);

return (s->port.txBufferSize - 1) - bytesUsed;
}
Expand Down
16 changes: 16 additions & 0 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -2248,6 +2248,11 @@ static void cliFlashInfo(char *cmdline)
UNUSED(cmdline);

const flashGeometry_t *layout = flashGetGeometry();

if (layout->totalSize == 0) {
cliPrintLine("Flash not available");
return;
}

cliPrintLinef("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u",
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize);
Expand Down Expand Up @@ -2277,6 +2282,13 @@ static void cliFlashErase(char *cmdline)
{
UNUSED(cmdline);

const flashGeometry_t *layout = flashGetGeometry();

if (layout->totalSize == 0) {
cliPrintLine("Flash not available");
return;
}

cliPrintLine("Erasing...");
flashfsEraseCompletely();

Expand Down Expand Up @@ -3344,7 +3356,11 @@ static void cliStatus(char *cmdline)
hardwareSensorStatusNames[getHwRangefinderStatus()],
hardwareSensorStatusNames[getHwOpticalFlowStatus()],
hardwareSensorStatusNames[getHwGPSStatus()],
#ifdef USE_SECONDARY_IMU
hardwareSensorStatusNames[getHwSecondaryImuStatus()]
#else
hardwareSensorStatusNames[0]
#endif
);

#ifdef USE_ESC_SENSOR
Expand Down
16 changes: 16 additions & 0 deletions src/main/fc/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -459,6 +459,22 @@ void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex)
beeperConfirmationBeeps(profileIndex + 1);
}

void setGyroCalibrationAndWriteEEPROM(int16_t getGyroZero[XYZ_AXIS_COUNT]) {
gyroConfigMutable()->gyro_zero_cal[X] = getGyroZero[X];
gyroConfigMutable()->gyro_zero_cal[Y] = getGyroZero[Y];
gyroConfigMutable()->gyro_zero_cal[Z] = getGyroZero[Z];
// save the calibration
writeEEPROM();
readEEPROM();
}

void setGravityCalibrationAndWriteEEPROM(float getGravity) {
gyroConfigMutable()->gravity_cmss_cal = getGravity;
// save the calibration
writeEEPROM();
readEEPROM();
}

void beeperOffSet(uint32_t mask)
{
beeperConfigMutable()->beeper_off_flags |= mask;
Expand Down
5 changes: 5 additions & 0 deletions src/main/fc/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

#include <stdint.h>
#include <stdbool.h>
#include "common/axis.h"
#include "common/time.h"
#include "config/parameter_group.h"
#include "drivers/adc.h"
Expand All @@ -29,6 +30,7 @@
#define MAX_NAME_LENGTH 16

#define TASK_GYRO_LOOPTIME 250 // Task gyro always runs at 4kHz

typedef enum {
FEATURE_THR_VBAT_COMP = 1 << 0,
FEATURE_VBAT = 1 << 1,
Expand Down Expand Up @@ -130,6 +132,9 @@ uint8_t getConfigBatteryProfile(void);
bool setConfigBatteryProfile(uint8_t profileIndex);
void setConfigBatteryProfileAndWriteEEPROM(uint8_t profileIndex);

void setGyroCalibrationAndWriteEEPROM(int16_t getGyroZero[XYZ_AXIS_COUNT]);
void setGravityCalibrationAndWriteEEPROM(float getGravity);

bool canSoftwareSerialBeUsed(void);
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch);

Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/fc_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -978,12 +978,12 @@ void taskUpdateRxMain(timeUs_t currentTimeUs)
// returns seconds
float getFlightTime()
{
return (float)(flightTime / 1000) / 1000;
return US2S(flightTime);
}

float getArmTime()
{
return (float)(armTime / 1000) / 1000;
return US2S(armTime);
}

void fcReboot(bool bootLoader)
Expand Down
6 changes: 6 additions & 0 deletions src/main/fc/fc_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@
#include "io/displayport_frsky_osd.h"
#include "io/displayport_msp.h"
#include "io/displayport_max7456.h"
#include "io/displayport_hdzero_osd.h"
#include "io/displayport_srxl.h"
#include "io/flashfs.h"
#include "io/gps.h"
Expand Down Expand Up @@ -553,6 +554,11 @@ void init(void)
osdDisplayPort = frskyOSDDisplayPortInit(osdConfig()->video_system);
}
#endif
#ifdef USE_HDZERO_OSD
if (!osdDisplayPort) {
osdDisplayPort = hdzeroOsdDisplayPortInit();
}
#endif
#if defined(USE_MAX7456)
// If there is a max7456 chip for the OSD and we have no
// external OSD initialized, use it.
Expand Down
4 changes: 4 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,11 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU8(dst, getHwRangefinderStatus());
sbufWriteU8(dst, getHwPitotmeterStatus());
sbufWriteU8(dst, getHwOpticalFlowStatus());
#ifdef USE_SECONDARY_IMU
sbufWriteU8(dst, getHwSecondaryImuStatus());
#else
sbufWriteU8(dst, 0);
#endif
break;

case MSP_ACTIVEBOXES:
Expand Down
Loading

0 comments on commit b3a8cc2

Please sign in to comment.