1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00
Commit graph

2070 commits

Author SHA1 Message Date
Dominic Clifton
9d00fb6af4 Merge branch 'acro-external-I2C-baro' of
https://github.com/SteveAmor/cleanflight into
SteveAmor-acro-external-I2C-baro

Conflicts:
	src/main/drivers/barometer_bmp085.c
	src/main/drivers/barometer_bmp085.h
2015-09-09 20:33:02 +01:00
Dominic Clifton
5d5fd81b2e Fix bug where PPM rx stops working on sparky or CC3D when using motor
PWM rate > 500 (brushed motor mode).

Fix is the same as for OneShot since both brushed motors and oneshot use
an 8mhz timer.

Fixes #58
2015-09-09 19:25:08 +01:00
Dominic Clifton
b2f9e603df STM32F3Discovery - correct default sensor alignment, closes #1289
Also updated ChebuzzF3 variant.
2015-09-09 18:48:12 +01:00
Dominic Clifton
9208b8701a Merge pull request #1255 from ProDrone/pr1233_rxfail_mode_changes_1
Changed behavior of PR #1233 - solves issue #1254
2015-09-05 23:01:11 +01:00
Dominic Clifton
b6c504dc88 Merge pull request #1263 from ProDrone/prevent_arming_when_in_cli
Prevent arming when in CLI mode
2015-09-05 22:55:06 +01:00
Dominic Clifton
0caf8a65ba Merge pull request #852 from ProDrone/Failsafe_features_1
Failsafe - New failsafe functionality (Phase 1)
2015-09-05 22:50:34 +01:00
Dominic Clifton
cb147ec85e Fix CJMCU build, broken by df92691410 2015-09-05 20:34:40 +01:00
Dominic Clifton
564c131db5 Merge pull request #1283 from sppnk/patch-4
Fixing servo command parsing of "rate" field
2015-09-05 18:53:33 +01:00
Dominic Clifton
df05d599b5 Merge pull request #1258 from ProDrone/is1257_false_rx_loss_detection_1
Fix false RX loss detection on EEPROM read/write
2015-09-05 18:11:11 +01:00
Dominic Clifton
28aad588cb Fix vtail mixer defaults. Closes #988
Previously the vtail mixer was a copy of the atail mixer which was
incorrect.

The new defaults cater for frames like the Armattan Morphling Vtail.
2015-09-05 18:03:02 +01:00
Dominic Clifton
df92691410 update dump command to show per-profile servo reverse settings. See
#1140.
2015-09-05 18:01:36 +01:00
ProDrone
f0681de53d Updates and feature additions to failsafe system.
- Added failsafe flightmode and rc control box.

To make failsafe procedure a separate flight mode and make it possible
to trigger failsafe with an AUX switch.

- Failsafe mode is activated when failsafe is active.

RC link lost is simulated with the failsafe AUX switch.
When NOT armed: failsafe switch to failsafe mode is shown in GUI (mode
tab).

- Activate failsafe mode with AUX switch.

- Prevent arming when failsafe via AUX switch is active (safety issue).

- Make failsafe disarm if motors armed and throttle was LOW (2D & 3D)
for `failsafe_throttle_low_delay` time (__JustDisarmEvent__).

Applied code changes to effectively add pull request: Make failsafe
disarm if motors armed and throttle low #717.

- Use failsafeIsMonitoring() to actually start monitoring.

- Added `failsafe_kill_switch` to code.

When set to 1 (0 is default), the failsafe switch will instantly disarm
(__KillswitchEvent__) instead of executing the landings procedure.
Arming is NOT locked after
this, so the craft could be re-armed if needed.
This is intended for racing quads where damage and danger must be
minimized in case of a pilot error.

- Added `failsafe_throttle_low_delay`, adapted documentation.

Used to adjust the time throttle level must have been LOW
to _only disarm_ instead of _full failsafe procedure_
(__JustDisarmEvent__).

- Updated the failsafe documentation.

- Re-enable arming at end of failsafe procedure.

At the end of a handled failsafe event, that means: auto-landing,
__JustDisarmEvent__ or __KillswitchEvent__, the RX link is monitored for
valid data.
Monitoring is a part of the failsafe handling, which means the craft is
still in failsafe mode while this is done.
Arming is re-enabled (allowed) when there is a valid RX link for more
then XX seconds, where XX depends on the handled event like this:
1. XX = 30 seconds after auto landing.
2. XX = 3 seconds after __JustDisarmEvent__.
3. XX = 0 seconds after __KillswitchEvent__.

NOTE: When armed via an AUX switch, you will have to switch to the
disarmed position at the very end to be able to re-arm.
The failsafe mode will not end until you do.

- __KillswitchEvent__ has now priority over __JustDisarmEvent__

- Apply rxfail values instantly when failsafe switch is ON

- Added missing cases to display.c

Show M when failsafe is monitoring for RX recovery (AND disarming when
armed with a switch).

===

Reworked the code from counter-based to time-based.

- AUX failsafe switch now has identical behavior to RX loss.

- Added RX failure and RX recovery timing.

- __KillswitchEvent__ skips RX failure detection delay (direct disarm).

===

[UNIT TESTS]

Adapted failsafe related unittests from counter-based to time-based

- Added failsafeOnValidDataFailed() to some tests

- Removed duplicate test setup from rc_controls_unittest.cc

- Removed magic numbers from rx_ranges_unittest.cc and rx_rx_unittest.cc

- Reworked all test-cases for flight_failsafe_unittest.cc
2015-09-04 16:55:40 +02:00
ProDrone
3a13edfdad Fix false RX loss detection on EEPROM read/write
The problem is caused by hardware counters (timekeeping and PPM/PWM
measurement) that keep running while the firmware is frozen. The result
is misinterpretation of received data.

EEPROM read & write now call a suspend and resume function to make RX
ignore incoming wrong data during reads/writes (and flush the wrong data
on resume).

Fixes issue #1257

(+1 squashed commit)
- Moved the check for skipSamples to the right place.

As commented by hydra
2015-09-04 16:54:25 +02:00
ProDrone
a46832fd85 Changed behavior of PR #1233 and doc update
Stick channels only have AUTO and HOLD mode.
AUX channels only have SET and HOLD mode.
Added check to parameter in CLI.
Modified rx.md to reflect changes (and more).

+1 squashed commit:

- A cleaner approach for the same functionality

Basically addressing all comments from Hydra
2015-09-04 16:51:19 +02:00
ProDrone
3b9cd37a57 Prevent arming when in CLI mode 2015-09-04 16:46:03 +02:00
Nicholas Sherlock
f7530df974 Fix 1 millisecond backwards time leap in time measured by micros()
This race condition caused periodic flight instability when micros() was
called precisely on a 1000 nanosecond boundary.
2015-09-04 23:44:41 +12:00
sppnk
45d31f2290 Fixing servo command bug
The limits for RATE were bad, so we had a "Parse error" when changing rate values other than 100.
2015-09-03 16:47:00 +02:00
Nicholas Sherlock
1a15e5aa08 Blackbox: Fix slow frames were not logged when logging rate was 1/32 2015-08-30 21:53:33 +12:00
Nicholas Sherlock
2b356a47dc Improve Blackbox header writing reliability 2015-08-30 02:33:16 +12:00
Nicholas Sherlock
f29b9dd329 Blackbox: Use rx getters instead of importing private state directly 2015-08-28 21:26:11 +12:00
Nicholas Sherlock
b6a75cb3f1 Add Blackbox logging of rx loss state flags
Closes #1266
2015-08-28 17:26:45 +12:00
Dominic Clifton
c49bd407bf Fix PORT103R and EUSTM32F103RC builds broken by
1f127905f7
2015-08-20 21:56:48 +01:00
Dominic Clifton
7adfeffafb Cleanup SPI initialisation. Relocate mpu6500 spi configuration from
Colibri race specific code into the mpu6500 driver.
2015-08-20 21:39:02 +01:00
Larry (TBS)
3b1f423c49 COLIBRI RACE support 2015-08-20 19:18:10 +01:00
Nicholas Sherlock
c5a7914fe8 Fix upper bound clamping of FP PID settings upon MSP read 2015-08-20 16:10:18 +12:00
Dominic Clifton
718729504e Allow FC to reverse input channels by using rxrange.
Just reverse the min/max arguments.

Unit tested.

Fixes #1132.
2015-08-20 02:46:03 +01:00
Dominic Clifton
3f8363f908 Merge pull request #1233 from cleanflight/rxfail-auto-mode
Failsafe - Add rxfail `auto` mode.
2015-08-20 02:05:51 +01:00
Dominic Clifton
2c79b9777e Large code re-organization which separates some key tasks in the rx
code.

Tested with X8R in SBus and PWM, and Spek Sat, GR-24 PPM, PWM and SUMD,
Spek PPM
2015-08-20 01:46:29 +01:00
Dominic Clifton
a030d4dd9e Failsafe - Add rxfail auto mode. Allow rxfail to be used for all
channels, not just aux channel.
2015-08-20 01:37:29 +01:00
Dominic Clifton
5142ff032a HoTT - Apply quick workaround to allow HoTT to work on hardware serial
ports, previously only softserial was working. - See #1021
2015-08-19 17:55:01 +01:00
Dominic Clifton
3878a7ea2c make the rollover pattern tests less verbose 2015-08-18 19:08:37 +01:00
Dominic Clifton
94c243c279 Merge branch 'rx_sumd_added_crc_check' of https://github.com/ProDrone/cleanflight into ProDrone-rx_sumd_added_crc_check
Conflicts:
	src/main/rx/sumd.c
2015-08-12 01:10:31 +01:00
Dominic Clifton
f510fe88b7 Merge pull request #1190 from ProDrone/pr995_modifications_1
RX - Corrections to RX fail detection, hold and preset, when using a PWM connection
2015-08-12 00:31:55 +01:00
ProDrone
d2c40076db PPM and PWM now have their own ___ReadRawRC functions.
Because a required change for PWM disturbed the PPM mode.
2015-08-12 00:58:44 +02:00
Dominic Clifton
cb92878fd0 Merge pull request #1172 from digitalentity/magzero-cli
Add ability to get/set mag calibration data
2015-08-11 22:16:45 +01:00
Dominic Clifton
e0d8f3bb1c Merge pull request #1185 from EvilBadger/MFNBFC-Battery
Modified VBatt functionality to enable better precision.
2015-08-11 21:52:36 +01:00
ProDrone
f26af1d844 Added CRC check to SUMD handler
Officially the CRC check is part of the SUMD protocol.

Framing errors are already covered and i expect these to occur around
the same time as CRC errors, so i am not sure if someone will ever
notice the difference...
2015-08-08 11:35:30 +02:00
ProDrone
95840ae512 rcData[] is keeping the right values now.
Logic for valid flightchannel detection is inverted in order to detect
the first flightchannel failure instead of waiting to check them all.

Clear PWM channel capture on read.

This invalidates the control channels on read. They are validated by
receiving a good value BEFORE the aux channels are received. This is
done because control channels configures to go OFF on failsafe are
detected with a PWM capture time-out. Time-out took so long that all aux
channels where overwritten by their RX configured failsafe values BEFORE
the invalid (=OFF) control channel was detected.
2015-08-08 10:45:03 +02:00
ProDrone
aaa7c7c5d3 SUMD channels are received as 16 bit values instead of 32
Preserve 32 bytes of RAM.
2015-08-08 10:20:37 +02:00
Andre Bernet
03a4a594d3 GPS speed was 10x too big on frsky telemetry 2015-08-06 18:12:20 +02:00
EvilBadger
3879b6c566 Modified VBatt functionality to enable better precision. 2015-08-05 21:34:44 +01:00
Dominic Clifton
402f90cc71 OLED - Use less verbose welcome page. 2015-08-05 04:53:09 +01:00
Dominic Clifton
56010f2da7 Fix incorrect DMA index for RSSI and Current.
The result was that RSSI and Current were transposed when both were used
together.
2015-08-05 04:52:19 +01:00
Dominic Clifton
463437fb45 Ensure battery status strings are stored in the flash. 2015-08-04 03:10:34 +01:00
Dominic Clifton
7202ad7524 Cleanup vbat time rollover. Cleanup whitespace. Code formatting.
Rename VBAT_DETECT to VBATT_PRESENT_THRESHOLD_MV.

Add two tests that show the two timing patterns that are in use in the
codebase.
2015-08-04 03:04:54 +01:00
DarkVegetableMatter
942c89237e Battery auto-detect and LPF for battery monitoring 2015-08-04 03:04:12 +01:00
Dominic Clifton
9d3276b222 Code and documentation cleanup of rc calibration.
Note: since it didn't actually calibrate anything it has been renamed to
rxrange.

Added ability to reset rxranges using `rxrange reset` - this follows the
same pattern as other cli commands.
2015-08-04 01:13:28 +01:00
Dominic Clifton
27f8223de7 Merge branch 'rc-calibration' of
https://github.com/digitalentity/cleanflight into
digitalentity-rc-calibration

Conflicts:
	docs/Rx.md
	src/main/io/serial_cli.c
	src/main/rx/rx.c
	src/main/rx/rx.h
2015-08-04 00:06:12 +01:00
Dominic Clifton
ae0c29125d Merge pull request #1157 from cleanflight/blackbox-pause
Add pause/resume switch support to Blackbox
2015-08-03 21:26:36 +01:00
Dominic Clifton
c1cb0d8864 CC3D - Display OLED DISPLAY on OPBL builds. 2015-08-03 21:19:20 +01:00