Merge remote-tracking branch 'upstream/master' into VCM_motor_stop_fix

This commit is contained in:
Jenny 2015-03-16 14:58:57 +00:00
commit 3160677e1c
46 changed files with 466 additions and 175 deletions

View File

@ -2,7 +2,7 @@
Please remember the issue tracker on github is _not_ for user support. Please also do not email developers directly for support. Instead please use IRC or the forums first, then if the problem is confirmed create an issue that details how to repeat the problem so it can be investigated.
Issued created without steps to repeat are likely to be closed. E-mail requests for support will go un-answered.
Issues created without steps to repeat are likely to be closed. E-mail requests for support will go un-answered.
Remember that issues that are due to mis-configuration, wiring or failure to read documentation just takes time away from the developers and can often be solved without developer interaction by other users.
@ -47,4 +47,4 @@ Later, you can get the changes from the cleanflight repo into your `master` bran
You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual.

View File

@ -100,14 +100,14 @@ The virtual sensor uses the throttle position to calculate as estimated current
| Setting | Description |
| ----------------------------- | -------------------------------------------------------- |
| `current_meter_scale` | The throttle scaling factor [centiamps, i.e. 1/100th A] |
| `current_meter_offset` | The current at zero throttle (while armed) [centiamps, i.e. 1/100th A] |
| `current_meter_offset` | The current at zero throttle (while disarmed) [centiamps, i.e. 1/100th A] |
There are two simple methods to tune the parameters depending in whether it is possible to measure current draw for your craft.
#### Tuning Using Battery Charger Measurement
It may be difficult to adjust `current_meter_offset` using this method unless you can measure the actual current draw with the craft armed at minimum throttle. Adjust `current_meter_scale` until the mAh draw reported by Cleanflight matches the charging data given by your battery charger after the flight (if the mAh draw is lower than reported by your battery charger, increase `current_meter_scale`, and vice-versa).
It may be difficult to adjust `current_meter_offset` using this method unless you can measure the actual current draw with the craft disarmed. Adjust `current_meter_scale` until the mAh draw reported by Cleanflight matches the charging data given by your battery charger after the flight (if the mAh draw is lower than reported by your battery charger, increase `current_meter_scale`, and vice-versa).
#### Tuning Using Actual Current Measurements
If you know your crafts current draw at zero throttle while armed (Imin) and maximum throttle(Imax) you can calculate the scaling factors using the following formulas where Tmax is maximum throttle offset (i.e. for `max_throttle` = 1850, Tmax = 1850 - 1000 = 850):
If you know your crafts current draw while disarmed (Imin), and at maximum throttle while armed (Imax), you can calculate the scaling factors using the following formulas where Tmax is maximum throttle offset (i.e. for `max_throttle` = 1850, Tmax = 1850 - 1000 = 850):
```
current_meter_scale = (Imax - Imin) * 100000 / (Tmax + (Tmax * Tmax / 50))
current_meter_offset = Imin * 100

View File

@ -40,8 +40,10 @@ flight logs from other craft, and I can add support for them!)
Cleanflight's `looptime` setting will decide how many times per second an update is saved to the flight log. The
software was developed on a craft with a looptime of 2400. Any looptime smaller than this will put more strain on the
data rate. The default looptime on Cleanflight is 3500. If you're using a looptime of 2000 or smaller, you will probably
need to reduce the sampling rate in the Blackbox settings, see the later section on configuring the Blackbox feature for
data rate. The default looptime on Cleanflight is 3500.
If you're using a looptime of 2300 or smaller, you will probably need to reduce the sampling rate in the Blackbox
settings, or increase your logger's baudrate to 250000. See the later section on configuring the Blackbox feature for
details.
## Hardware
@ -53,9 +55,12 @@ compatible flight controller you can store the logs on the onboard dataflash sto
### OpenLog serial data logger
The OpenLog ships with standard OpenLog 3 firmware installed. However, in order to reduce the number of dropped frames,
it should be reflashed with the [OpenLog Light firmware][] or the special [OpenLog Blackbox firmware][] . The Blackbox
variant of the firmware ensures that the OpenLog is running at the correct baud-rate and does away for the need for a
`CONFIG.TXT` file to set up the OpenLog.
it should be reflashed with the [OpenLog Light firmware][] or the special [OpenLog Blackbox firmware][] (this needs to
be version 2.0 or higher to allow configuration of baud rates).
The Blackbox variant of the firmware ensures that the OpenLog is using the correct settings, and defaults to 115200
baud. If you are using a looptime of 2500 or smaller, you should set the baud rate to 250000 instead to eliminate
dropped frames.
You can find the Blackbox version of the OpenLog firmware [here](https://github.com/cleanflight/blackbox-firmware),
along with instructions for installing it onto your OpenLog.
@ -74,11 +79,13 @@ not a guarantee of better performance.
- Generic 4GB Class 4 microSDHC card - the rate of missing frames is about 1%, and is concentrated around the most
interesting parts of the log!
- Sandisk Ultra 32GB (unlike the smaller 16GB version, this version has poor write latency)
##### microSDHC cards known to have good performance
- Transcend 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%)
- Sandisk Extreme 16GB Class 10 UHS-I microSDHC (typical error rate < 0.1%)
- Sandisk Ultra 16GB (it performs only half as well as the Extreme in theory, but still very good)
You should format any card you use with the [SD Association's special formatting tool][] , as it will give the OpenLog
the best chance of writing at high speed. You must format it with either FAT, or with FAT32 (recommended).
@ -87,17 +94,23 @@ the best chance of writing at high speed. You must format it with either FAT, or
#### OpenLog configuration
This section applies only if you are using the OpenLog or OpenLog Light original firmware on the OpenLog. If you flashed
it with the special OpenLog Blackbox firmware, you don't need to configure it further.
Power up the OpenLog with a microSD card inside, wait 10 seconds or so, then power it down and plug the microSD card
into your computer. You should find a "CONFIG.TXT" file on the card. Edit it in a text editor to set the first number
(baud) to 115200. Set esc# to 0, mode to 0, and echo to 0. Save the file and put the card back into your OpenLog, it
should use those settings from now on.
into your computer. You should find a "CONFIG.TXT" file on the card. You should see the baud rate that the OpenLog has
been configured to. You probably want this to be set to either 115200 (the default) or 250000 (for craft with looptimes
smaller than 2500).
Save the file and put the card back into your OpenLog, it should use those settings from now on.
If your OpenLog didn't write a CONFIG.TXT file, create a CONFIG.TXT file with these contents and store it in the root
of the MicroSD card:
```
115200
baud
```
If you are using the official OpenLog Light firmware, use this configuration instead:
```
115200,26,0,0,1,0,1
baud,escape,esc#,mode,verb,echo,ignoreRX
@ -105,7 +118,7 @@ baud,escape,esc#,mode,verb,echo,ignoreRX
#### Serial port
A 115200 baud serial port is required to connect the OpenLog to your flight controller (such as `serial_port_1` on the
A hardware serial port is required to connect the OpenLog to your flight controller (such as `serial_port_1` on the
Naze32, the two-pin Tx/Rx header in the center of the board). The Blackbox can not be used with softserial ports as they
are too slow.
@ -145,16 +158,19 @@ Enter `set blackbox_device=1` to switch to logging to an onboard dataflash chip,
## Configuring the Blackbox
If you are using a short looptime like 2500 or smaller, try switching your OpenLog to 250000 baud (instead of the
default of 115200) and set that baud rate on the Blackbox's port in the Confgurator.
The Blackbox currently provides two settings (`blackbox_rate_num` and `blackbox_rate_denom`) that allow you to control
the rate at which data is logged. These two together form a fraction (`blackbox_rate_num / blackbox_rate_denom`) which
decides what portion of the flight controller's control loop iterations should be logged. The default is 1/1 which logs
every iteration.
If you are using a short looptime like 2000 or faster, or you're using a slower MicroSD card, you will need to reduce
this rate to reduce the number of corrupted logged frames that `blackbox_decode` complains about. A rate of 1/2 is likely
to work for most craft.
If you're using a slower MicroSD card, you may need to reduce your logging rate to reduce the number of corrupted
logged frames that `blackbox_decode` complains about. A rate of 1/2 is likely to work for most craft.
You can change these settings by entering the CLI tab in the [Cleanflight Configurator][] and using the `set` command, like so:
You can change the logging rate settings by entering the CLI tab in the [Cleanflight Configurator][] and using the `set`
command, like so:
```
set blackbox_rate_num = 1

View File

@ -122,3 +122,65 @@ remaining area of flash ram.
The OpenPilot bootloader code also allows the remaining section of flash to be reconfigured and re-flashed by the
OpenPilot Ground Station (GCS) via USB without requiring a USB to uart adapter.
# Restoring OpenPilot bootloader
If you have a JLink debugger, you can use JLinkExe to flash the open pilot bootloader.
1. Run JLinkExe `/Applications/SEGGER/JLink/JLinkExe`
2. `device STM32F103CB`
3. `r`
4. `h`
5. `loadbin opbl.bin, 0x08000000`
6. `q`
7. Re-plug CC3D.
Here's an example session:
```
$ /Applications/SEGGER/JLink/JLinkExe
SEGGER J-Link Commander V4.90c ('?' for help)
Compiled Aug 29 2014 09:52:38
DLL version V4.90c, compiled Aug 29 2014 09:52:33
Firmware: J-Link ARM-OB STM32 compiled Aug 22 2012 19:52:04
Hardware: V7.00
S/N: -1
Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull
VTarget = 3.300V
Info: Could not measure total IR len. TDO is constant high.
Info: Could not measure total IR len. TDO is constant high.
No devices found on JTAG chain. Trying to find device on SWD.
Info: Found SWD-DP with ID 0x1BA01477
Info: Found Cortex-M3 r1p1, Little endian.
Info: FPUnit: 6 code (BP) slots and 2 literal slots
Info: TPIU fitted.
Cortex-M3 identified.
Target interface speed: 100 kHz
J-Link>device STM32F103CB
Info: Device "STM32F103CB" selected (128 KB flash, 20 KB RAM).
Reconnecting to target...
Info: Found SWD-DP with ID 0x1BA01477
Info: Found SWD-DP with ID 0x1BA01477
Info: Found Cortex-M3 r1p1, Little endian.
Info: FPUnit: 6 code (BP) slots and 2 literal slots
Info: TPIU fitted.
J-Link>r
Reset delay: 0 ms
Reset type NORMAL: Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
J-Link>h
PC = 0800010C, CycleCnt = 00000000
R0 = 0000000C, R1 = 0000003F, R2 = 00000000, R3 = 00000008
R4 = 00003000, R5 = 023ACEFC, R6 = 200000F0, R7 = 20000304
R8 = 023B92BC, R9 = 00000000, R10= ED691105, R11= F626177C
R12= 000F0000
SP(R13)= 20000934, MSP= 20000934, PSP= 20000934, R14(LR) = FFFFFFFF
XPSR = 01000000: APSR = nzcvq, EPSR = 01000000, IPSR = 000 (NoException)
CFBP = 00000000, CONTROL = 00, FAULTMASK = 00, BASEPRI = 00, PRIMASK = 00
J-Link>loadbin opbl.bin, 0x08000000
Downloading file [opbl.bin]...
WARNING: CPU is running at low speed (8004 kHz).
Info: J-Link: Flash download: Flash download into internal flash skipped. Flash contents already match
Info: J-Link: Flash download: Total time needed: 0.898s (Prepare: 0.709s, Compare: 0.128s, Erase: 0.000s, Program: 0.000s, Verify: 0.000s, Restore: 0.059s)
O.K.
J-Link>q
$
```

View File

@ -118,7 +118,7 @@ Re-apply any new defaults as desired.
| disarm_kill_switch | Enabled by default. Disarms the motors independently of throttle value. Setting to 0 reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | 0 | 1 | 1 | Master | UINT8 |
| auto_disarm_delay | | 0 | 60 | 5 | Master | UINT8 |
| small_angle | If the copter tilt angle exceed this value the copter will refuse to arm. default is 25°. | 0 | 180 | 25 | Master | UINT8 |
| pid_at_min_throttle | If enabled, the copter will process the pid algorithm at minimum throttle. | 0 | 1 | 0 | Master | UINT8 |
| pid_at_min_throttle | If enabled, the copter will process the pid algorithm at minimum throttle. | 0 | 1 | 1 | Master | UINT8 |
| flaps_speed | | 0 | 100 | 0 | Master | UINT8 |
| fixedwing_althold_dir | | -1 | 1 | 1 | Master | INT8 |
| reboot_character | | 48 | 126 | 82 | Master | UINT8 |

View File

@ -2,8 +2,8 @@
There are two types of failsafe:
1. receiver based failsafe
2. flight controller based failsafe
1. Receiver based failsafe
2. Flight controller based failsafe
Receiver based failsafe is where you, from your transmitter and receiver, configure channels to output desired signals if your receiver detects signal loss.
The idea is that you set throttle and other controls so the aircraft descends in a controlled manner. See your receiver's documentation for this method.
@ -14,11 +14,11 @@ It is possible to use both types at the same time which may be desirable. Fligh
## Flight controller failsafe system
The failsafe system is not activated until 5 seconds after the flight controller boots up. This is to prevent failsafe from activating in the case of TX/RX gear with long bind procedures before they send out valid data.
The failsafe system is not activated until 5 seconds after the flight controller boots up. This is to prevent failsafe from activating, as in the case of TX/RX gear with long bind procedures, before the RX sends out valid data.
After the failsafe has forced a landing, the flight controller cannot be armed and has to be reset.
The failsafe system attempts to detect when your receiver loses signal. It then attempts to prevent your aircraft from flying away uncontrollably.
The failsafe system attempts to detect when your receiver loses signal. It then attempts to prevent your aircraft from flying away uncontrollably by enabling an auto-level mode and setting the throttle that should allow the craft to come to a safter landing.
The failsafe is activated when:
@ -30,7 +30,52 @@ b) the first 4 Parallel PWM/PPM channels do not have valid signals.
And when:
c) the failsafe guard time specified by `failsafe_delay` has elapsed.
c) the failsafe guard time specified by `failsafe_delay` has elapsed.
Note that:
d) The failsafe system will be activated regardless of current throttle position.
e) The craft may already be on the ground with motors stopped and that motors and props could spin again - the software does not currently detect if the craft is on the ground. Take care when using MOTOR_STOP feature.
### Testing
Bench test the failsafe system before flying - remove props while doing so.
1. Arm the craft.
1. Turn off transmitter or unplug RX.
1. Observe motors spin at configured throttle setting for configured duration.
1. Observe motors turn off after configured duration.
1. Ensure that when you turn on your TX again or reconnect the RX that you cannot re-arm once the motors have stopped.
1. Power cycle the FC.
1. Arm the craft.
1. Turn off transmitter or unplug RX.
1. Observe motors spin at configured throttle setting for configured duration.
1. Turn on TX or reconnect RX.
1. Ensure that your switch positions don't now cause the craft to disarm (otherwise it would fall out of the sky on regained signal).
1. Observe that normal flight behaviour is resumed.
1. Disarm.
Field test the failsafe system
1. Perform bench testing first!
1. On a calm day go to an un-populated area away from buildings or test indoors in a safe controlled environment - e.g. inside a big net.
1. Arm the craft.
1. Hover over something soft (long grass, ferns, heather, foam, etc).
1. Descend the craft and observe throttle position and record throttle value from your TX channel monitor. Ideally 1500 should be hover. So your value should be less than 1500.
1. Stop, disarm.
1. Set failsafe thottle to the recorded value.
1. Arm, hover over something soft again.
1. Turn off TX (!)
1. Observe craft descends and motors continue to spin for the configurated duration.
1. Observe FC disarms after the configured duration.
1. Remove flight battery.
If craft descends too quickly then increase failsafe throttle setting.
Ensure that the duration is long enough for your craft to land at the altitudes you normally fly at.
## Configuration

View File

@ -133,12 +133,5 @@ From the UBlox documentation:
## Hardware
There are many GPS receivers available on the market, people have reported success with the following receivers:
Ublox Neo-7M GPS with Compass and Pedestal Mount
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426
There are many GPS receivers available on the market.
See Gps_-_Tested_Hardware.md for a list of user tested hardware.

View File

@ -0,0 +1,13 @@
## User tested hardware
###Ublox
Ublox Neo-M8N GPS with Compass
Ublox Neo-7M GPS with Compass and Pedestal Mount
http://www.hobbyking.com/hobbyking/store/__55558__Ublox_Neo_7M_GPS_with_Compass_and_Pedestal_Mount.html
###Serial NMEA
RY825AI 18Hz UART USB interface GPS Glonass BeiDou QZSS antenna module flash
http://www.ebay.com/itm/RY825AI-18Hz-UART-USB-interface-GPS-Glonass-BeiDou-QZSS-antenna-module-flash/181566850426

View File

@ -69,3 +69,65 @@ One method for tuning the filter cutoff is as follows:
4. If the oscillations are dampened within roughly a second or are no longer present, then you are done. Be sure to run `save`.
## Custom Motor Mixing
Custom motor mixing allows for completely customized motor configurations. Each motor must be defined with a custom mixing table for that motor. The mix must reflect how close each motor is with reference to the CG (Center of Gravity) of the flight controller. A motor closer to the CG of the flight controller will need to travel less distance than a motor further away.
Steps to configure custom mixer in the CLI:
1. Use `mixer custom` to enable the custom mixing.
2. Use `cmix reset` to erase the any existing custom mixing.
3. Issue a cmix statement for each motor.
The cmix statement has the following syntax: `cmix n THROTTLE ROLL PITCH YAW`
| Mixing table parameter | Definition |
| ---------------------- | ---------- |
| n | Motor ordering number |
| THROTTLE | All motors that are used in this configuration are set to 1.0. Unused set to 0.0. |
| ROLL | Indicates how much roll authority this motor imparts to the roll of the flight controller. Accepts values nominally from 1.0 to -1.0. |
| PITCH | Indicates the pitch authority this motor has over the flight controller. Also accepts values nominally from 1.0 to -1.0. |
| YAW | Indicates the direction of the motor rotation in relationship with the flight controller. 1.0 = CCW -1.0 = CW. |
### Example 1: A KK2.0 wired motor setup
Here's an example of a X configuration quad, but the motors are still wired using the KK board motor numbering scheme.
```
KK2.0 Motor Layout
1CW 2CCW
\ /
KK
/ \
4CCW 3CW
```
1. Use `mixer custom`
2. Use `cmix reset`
3. Use `cmix 1 1.0, 1.0, -1.0, -1.0` for the Front Left motor. It tells the flight controller the #1 motor is used, provides positive roll, provides negative pitch and is turning CW.
4. Use `cmix 2 1.0, -1.0, -1.0, 1.0` for the Front Right motor. It still provides a negative pitch authority, but unlike the front left, it provides negative roll authority and turns CCW.
5. Use `cmix 3 1.0, -1.0, 1.0, -1.0` for the Rear Right motor. It has negative roll, provides positive pitch when the speed is increased and turns CW.
6. Use `cmix 4 1.0, 1.0, 1.0, 1.0` for the Rear Left motor. Increasing motor speed imparts positive roll, positive pitch and turns CCW.
### Example 2: A HEX-U Copter
Here is an example of a U-shaped hex; probably good for herding giraffes in the Sahara. Because the 1 and 6 motors are closer to the roll axis, they impart much more force than the motors mounted twice as far from the FC CG. The effect they have on pitch is the same as the forward motors because they are the same distance from the FC CG. The 2 and 5 motors do not contribute anything to pitch because speeding them up and slowing them down has no effect on the forward/back pitch of the FC.
```
HEX6-U
.4........3.
............
.5...FC...2.
............
...6....1...
```
|Command| Roll | Pitch | Yaw |
| ----- | ---- | ----- | --- |
| Use `cmix 1 1.0, -0.5, 1.0, -1.0` | half negative | full positive | CW |
| Use `cmix 2 1.0, -1.0, 0.0, 1.0` | full negative | none | CCW |
| Use `cmix 3 1.0, -1.0, -1.0, -1.0` | full negative | full negative | CW |
| Use `cmix 4 1.0, 1.0, -1.0, 1.0` | full positive | full negative | CCW |
| Use `cmix 5 1.0, 1.0, 0.0, -1.0` | full positive | none | CW |
| Use `cmix 6 1.0, 0.5, 1.0, 1.0` | half positive | full positive | CCW |

View File

@ -16,7 +16,7 @@ auxillary receiver channels and other events such as failsafe detection.
| 9 | 8 | CAMTRIG | |
| 10 | 9 | GPSHOME | Autonomous flight to HOME position |
| 11 | 10 | GPSHOLD | Maintain the same longitude/lattitude |
| 12 | 11 | PASSTHRU | |
| 12 | 11 | PASSTHRU | Pass roll, yaw, and pitch directly from rx to servos in airplane mix |
| 13 | 12 | BEEPERON | Enable beeping - useful for locating a crashed aircraft |
| 14 | 13 | LEDMAX | |
| 15 | 14 | LEDLOW | |

View File

@ -88,7 +88,7 @@ affecting yaw, roll or pitch rotation rates (which are tuned by the dedicated ro
settings).
In Angle mode, this controller uses the LEVEL "P" PID setting to decide how strong the auto-level correction should
be. Note that the default value for P_Level is 90. This is more than likely too high of a value for most, and will cause the model to be very unstable in Angle Mode, and could result in loss of control. It is recommended to change this value to 20 before using PID Controller 2 in Angle Mode.
be. Note that the default value for P_Level is 90. This is more than likely too high of a value for most, and will cause the model to be very unstable in Angle Mode, and could result in loss of control. It is recommended to change this value to 20 before using PID Controller 1 in Angle Mode.
In Horizon mode, this controller uses the LEVEL "I" PID setting to decide how much auto-level correction should be
applied. The default Cleanflight setting for "I" will result in virtually no auto-leveling being applied, so that will
@ -150,7 +150,7 @@ For the ALIENWII32 targets the gyroscale is removed for more yaw authority. This
PID Controller 5 is an port of the PID controller from the Harakiri firmware.
The algorithm is leveraging more floating point math. This PID controller also compensates for different looptimes on roll and pitch. It likely don<EFBFBD>t need retuning of the PID values when looptime is changing. Actually there are two settings hardcoded which are configurable via the GUI in Harakiri:
The algorithm is leveraging more floating point math. This PID controller also compensates for different looptimes on roll and pitch. It likely don't need retuning of the PID values when looptime is changing. Actually there are two settings hardcoded which are configurable via the GUI in Harakiri:
OLD_YAW 0 // [0/1] 0 = multiwii 2.3 yaw, 1 = older yaw.
MAIN_CUT_HZ 12.0f // (default 12Hz, Range 1-50Hz)

View File

@ -4,5 +4,14 @@ As many can attest, multirotors and RC models in general can be very dangerous,
* **NEVER** arm your model with propellers fitted unless you intend to fly!
* **Always** remove your propellers if you are setting up for the first time, flashing firmware, or if in any doubt.
## Before installing the Flight Controller in your craft
Please consult the Cli.md, Controls.md, Failsafe.md and Modes.md, documentations for further important information and familiarisation with CleanFlight's terminolgies.
You are highly advised to use the Receiver tab in CleanFlight Configurator, making sure your Rx channel values are centered at 1500 (1520 for Futaba RC) and Min/Max values are reached when controls are operated.
The referenced values for each channel, have marked impact on the operation of Flight Controller and its Flight Modes.
You may have to adjust your channel endpoints and trims/sub-trims, on your RC transmitter, to achieve the expected values.
## Feature MOTOR_STOP
The default Cleanflight configuration has the MOTOR_STOP feature DISABLED by default. What this means is that as soon as the controller is armed, the propellers *WILL* begin spinning at low speed. It is recommended that this setting be retained as it provides a good visual indication that the craft is armed. You can read more about arming and setting the MOTOR_STOP feature if desired in the relevant sections of the manual.

View File

@ -63,3 +63,5 @@ Each baud rate is assigned an identifier, they are as follows:
| 3 | 38400 |
| 4 | 57600 |
| 5 | 115200 |
| 6 | 230400 |
| 7 | 250000 |

View File

@ -47,10 +47,25 @@ For 2 and 3 use the CLI command as follows:
set telemetry_inversion = 1
```
### Precision setting for VFAS
Cleanflight can send VFAS (FrSky Ampere Sensor Voltage) in two ways:
```
set frsky_vfas_precision = 0
```
This is default setting which supports VFAS resolution of 0.2 volts and is supported on all FrSky hardware.
```
set frsky_vfas_precision = 1
```
This is new setting which supports VFAS resolution of 0.1 volts and is only supported by OpenTX radios (this method uses custom ID 0x39).
### Notes
RPM shows throttle output when armed.
RPM shows when diarmed.
RPM shows when disarmed.
TEMP2 shows Satellite Signal Quality when GPS is enabled.
RPM requires that the 'blades' setting is set to 12 on your receiver/display - tested with Taranis/OpenTX.

View File

@ -62,9 +62,6 @@
#ifdef BLACKBOX
#define BLACKBOX_BAUDRATE 115200
#define BLACKBOX_INITIAL_PORT_MODE MODE_TX
// How many bytes should we transmit per loop iteration?
uint8_t blackboxWriteChunkSize = 16;
@ -447,12 +444,29 @@ bool blackboxDeviceOpen(void)
case BLACKBOX_DEVICE_SERIAL:
{
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_BLACKBOX);
baudRate_e baudRateIndex;
portMode_t portMode;
if (!portConfig) {
return false;
}
blackboxPortSharing = determinePortSharing(portConfig, FUNCTION_BLACKBOX);
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, BLACKBOX_BAUDRATE, BLACKBOX_INITIAL_PORT_MODE, SERIAL_NOT_INVERTED);
blackboxPortSharing = determinePortSharing(portConfig, FUNCTION_BLACKBOX);
baudRateIndex = portConfig->blackbox_baudrateIndex;
portMode = MODE_TX;
if (baudRates[baudRateIndex] == 230400) {
/*
* OpenLog's 230400 baud rate is very inaccurate, so it requires a larger inter-character gap in
* order to maintain synchronization.
*/
portMode |= MODE_STOPBITS2;
}
blackboxPort = openSerialPort(portConfig->identifier, FUNCTION_BLACKBOX, NULL, baudRates[baudRateIndex],
portMode, SERIAL_NOT_INVERTED);
return blackboxPort != NULL;
}
break;

View File

@ -226,6 +226,7 @@ void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
telemetryConfig->gpsNoFixLongitude = 0;
telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
telemetryConfig->frsky_vfas_precision = 0;
}
void resetBatteryConfig(batteryConfig_t *batteryConfig)

View File

@ -35,6 +35,7 @@ typedef struct adc_config_t {
} adc_config_t;
typedef struct drv_adc_config_t {
bool enableVBat;
bool enableRSSI;
bool enableCurrentMeter;
bool enableExternal1;

View File

@ -42,7 +42,6 @@
//
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
//
// CC3D Only one ADC channel supported currently, for battery on S5_IN/PA0
void adcInit(drv_adc_config_t *init)
@ -64,12 +63,14 @@ void adcInit(drv_adc_config_t *init)
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
#ifdef VBAT_ADC_GPIO
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_BATTERY].enabled = true;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
if (init->enableVBat) {
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
adcConfig[ADC_BATTERY].enabled = true;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
}
#endif
#ifdef EXTERNAL1_ADC_GPIO

View File

@ -52,14 +52,16 @@ void adcInit(drv_adc_config_t *init)
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL ;
#ifdef VBAT_ADC_GPIO
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
if (init->enableVBat) {
GPIO_InitStructure.GPIO_Pin = VBAT_ADC_GPIO_PIN;
GPIO_Init(VBAT_ADC_GPIO, &GPIO_InitStructure);
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_BATTERY].enabled = true;
adcChannelCount++;
adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
adcConfig[ADC_BATTERY].dmaIndex = adcChannelCount;
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_601Cycles5;
adcConfig[ADC_BATTERY].enabled = true;
adcChannelCount++;
}
#endif
#ifdef CURRENT_METER_ADC_GPIO

View File

@ -28,6 +28,7 @@ typedef enum portMode_t {
MODE_RXTX = MODE_RX | MODE_TX,
MODE_SBUS = 1 << 2,
MODE_BIDIR = 1 << 3,
MODE_STOPBITS2 = 1 << 4,
} portMode_t;
typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app

View File

@ -76,7 +76,11 @@ static void uartReconfigure(uartPort_t *uartPort)
USART_InitStructure.USART_StopBits = USART_StopBits_2;
USART_InitStructure.USART_Parity = USART_Parity_Even;
} else {
USART_InitStructure.USART_StopBits = USART_StopBits_1;
if (uartPort->port.mode & MODE_STOPBITS2)
USART_InitStructure.USART_StopBits = USART_StopBits_2;
else
USART_InitStructure.USART_StopBits = USART_StopBits_1;
USART_InitStructure.USART_Parity = USART_Parity_No;
}
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;

View File

@ -50,7 +50,7 @@ typedef struct imuRuntimeConfig_s {
uint8_t acc_unarmedcal;
float gyro_cmpf_factor;
float gyro_cmpfm_factor;
int8_t small_angle;
uint8_t small_angle;
} imuRuntimeConfig_t;
void imuConfigure(

View File

@ -68,7 +68,7 @@ serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = {
#endif
};
uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200}; // see baudRate_e
uint32_t baudRates[] = {0, 9600, 19200, 38400, 57600, 115200, 230400, 250000}; // see baudRate_e
#define BAUD_RATE_COUNT (sizeof(baudRates) / sizeof(baudRates[0]))

View File

@ -25,14 +25,14 @@ typedef enum {
typedef enum {
FUNCTION_NONE = 0,
FUNCTION_MSP = (1 << 0),
FUNCTION_GPS = (1 << 1),
FUNCTION_TELEMETRY_FRSKY = (1 << 2),
FUNCTION_TELEMETRY_HOTT = (1 << 3),
FUNCTION_TELEMETRY_MSP = (1 << 4),
FUNCTION_TELEMETRY_SMARTPORT = (1 << 5),
FUNCTION_RX_SERIAL = (1 << 6),
FUNCTION_BLACKBOX = (1 << 7)
FUNCTION_MSP = (1 << 0), // 1
FUNCTION_GPS = (1 << 1), // 2
FUNCTION_TELEMETRY_FRSKY = (1 << 2), // 4
FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8
FUNCTION_TELEMETRY_MSP = (1 << 4), // 16
FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32
FUNCTION_RX_SERIAL = (1 << 6), // 64
FUNCTION_BLACKBOX = (1 << 7) // 128
} serialPortFunction_e;
typedef enum {
@ -41,7 +41,9 @@ typedef enum {
BAUD_19200,
BAUD_38400,
BAUD_57600,
BAUD_115200
BAUD_115200,
BAUD_230400,
BAUD_250000,
} baudRate_e;
extern uint32_t baudRates[];

View File

@ -72,6 +72,7 @@
#include "flight/failsafe.h"
#include "telemetry/telemetry.h"
#include "telemetry/frsky.h"
#include "config/runtime_config.h"
#include "config/config.h"
@ -346,6 +347,7 @@ const clivalue_t valueTable[] = {
{ "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, -180.0, 180.0 },
{ "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, 0, FRSKY_FORMAT_NMEA },
{ "frsky_unit", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_unit, 0, FRSKY_UNIT_IMPERIALS },
{ "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH },
{ "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, 0, 20000 },
{ "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, VBAT_SCALE_MIN, VBAT_SCALE_MAX },

View File

@ -131,7 +131,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 6 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_MINOR 7 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_LENGTH 2
@ -882,7 +882,7 @@ static bool processOutCommand(uint8_t cmdMSP)
case MSP_ANALOG:
headSerialReply(7);
serialize8((uint8_t)constrain(vbat, 0, 255));
serialize16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamphours drawn from battery
serialize16((uint16_t)constrain(mAhDrawn, 0, 0xFFFF)); // milliamp hours drawn from battery
serialize16(rssi);
if(masterConfig.batteryConfig.multiwiiCurrentMeterOutput) {
serialize16((uint16_t)constrain(amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps. Negative range is truncated to zero
@ -890,7 +890,7 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16((int16_t)constrain(amperage, -0x8000, 0x7FFF)); // send amperage in 0.01 A steps, range is -320A to 320A
break;
case MSP_RC_TUNING:
headSerialReply(8);
headSerialReply(10);
serialize8(currentControlRateProfile->rcRate8);
serialize8(currentControlRateProfile->rcExpo8);
for (i = 0 ; i < 3; i++) {
@ -899,6 +899,7 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize8(currentControlRateProfile->dynThrPID);
serialize8(currentControlRateProfile->thrMid8);
serialize8(currentControlRateProfile->thrExpo8);
serialize16(currentControlRateProfile->tpa_breakpoint);
break;
case MSP_PID:
headSerialReply(3 * PID_ITEM_COUNT);
@ -1326,7 +1327,7 @@ static bool processInCommand(void)
break;
case MSP_SET_RC_TUNING:
if (currentPort->dataSize == 8) {
if (currentPort->dataSize == 10) {//allow for tpa_breakpoint
currentControlRateProfile->rcRate8 = read8();
currentControlRateProfile->rcExpo8 = read8();
for (i = 0; i < 3; i++) {
@ -1335,6 +1336,7 @@ static bool processInCommand(void)
currentControlRateProfile->dynThrPID = read8();
currentControlRateProfile->thrMid8 = read8();
currentControlRateProfile->thrExpo8 = read8();
currentControlRateProfile->tpa_breakpoint = read16();
} else {
headSerialError(0);
}

View File

@ -290,6 +290,7 @@ void init(void)
#ifdef USE_ADC
drv_adc_config_t adc_params;
adc_params.enableVBat = feature(FEATURE_VBAT);
adc_params.enableRSSI = feature(FEATURE_RSSI_ADC);
adc_params.enableCurrentMeter = feature(FEATURE_CURRENT_METER);
adc_params.enableExternal1 = false;

View File

@ -46,11 +46,12 @@ void rxMspFrameRecieve(void)
bool rxMspFrameComplete(void)
{
if (rxMspFrameDone) {
rxMspFrameDone = false;
return true;
if (!rxMspFrameDone) {
return false;
}
return false;
rxMspFrameDone = false;
return true;
}
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)

View File

@ -143,32 +143,32 @@ void serialRxInit(rxConfig_t *rxConfig)
}
}
bool isSerialRxFrameComplete(rxConfig_t *rxConfig)
uint8_t serialRxFrameStatus(rxConfig_t *rxConfig)
{
/**
* FIXME: Each of the xxxxFrameComplete() methods MUST be able to survive being called without the
* FIXME: Each of the xxxxFrameStatus() methods MUST be able to survive being called without the
* corresponding xxxInit() method having been called first.
*
* This situation arises when the cli or the msp changes the value of rxConfig->serialrx_provider
*
* A solution is for the ___Init() to configure the serialRxFrameComplete function pointer which
* A solution is for the ___Init() to configure the serialRxFrameStatus function pointer which
* should be used instead of the switch statement below.
*/
switch (rxConfig->serialrx_provider) {
case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048:
return spektrumFrameComplete();
return spektrumFrameStatus();
case SERIALRX_SBUS:
return sbusFrameComplete();
return sbusFrameStatus();
case SERIALRX_SUMD:
return sumdFrameComplete();
return sumdFrameStatus();
case SERIALRX_SUMH:
return sumhFrameComplete();
return sumhFrameStatus();
case SERIALRX_XBUS_MODE_B:
case SERIALRX_XBUS_MODE_B_RJ01:
return xBusFrameComplete();
return xBusFrameStatus();
}
return false;
return SERIAL_RX_FRAME_PENDING;
}
#endif
@ -181,6 +181,7 @@ uint8_t calculateChannelRemapping(uint8_t *channelMap, uint8_t channelMapEntryCo
}
static bool rcDataReceived = false;
static uint32_t rxUpdateAt = 0;
@ -189,18 +190,21 @@ void updateRx(void)
rcDataReceived = false;
#ifdef SERIAL_RX
// calculate rc stuff from serial-based receivers (spek/sbus)
if (feature(FEATURE_RX_SERIAL)) {
rcDataReceived = isSerialRxFrameComplete(rxConfig);
uint8_t frameStatus = serialRxFrameStatus(rxConfig);
if (frameStatus & SERIAL_RX_FRAME_COMPLETE) {
rcDataReceived = true;
if ((frameStatus & SERIAL_RX_FRAME_FAILSAFE) == 0 && feature(FEATURE_FAILSAFE)) {
failsafeReset();
}
}
}
#endif
if (feature(FEATURE_RX_MSP)) {
rcDataReceived = rxMspFrameComplete();
}
if (rcDataReceived) {
if (feature(FEATURE_FAILSAFE)) {
if (rcDataReceived && feature(FEATURE_FAILSAFE)) {
failsafeReset();
}
}
@ -217,7 +221,7 @@ static bool isRxDataDriven(void) {
static uint8_t rcSampleIndex = 0;
uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
static uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
{
static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT];
static int16_t rcDataMean[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT];
@ -245,7 +249,7 @@ uint16_t calculateNonDataDrivenChannel(uint8_t chan, uint16_t sample)
return rcDataMean[chan] / PPM_AND_PWM_SAMPLE_COUNT;
}
void processRxChannels(void)
static void processRxChannels(void)
{
uint8_t chan;
@ -255,9 +259,13 @@ void processRxChannels(void)
bool shouldCheckPulse = true;
if (feature(FEATURE_FAILSAFE) && feature(FEATURE_RX_PPM)) {
shouldCheckPulse = isPPMDataBeingReceived();
resetPPMDataReceivedState();
if (feature(FEATURE_FAILSAFE)) {
if (feature(FEATURE_RX_PPM)) {
shouldCheckPulse = isPPMDataBeingReceived();
resetPPMDataReceivedState();
} else {
shouldCheckPulse = !isRxDataDriven();
}
}
for (chan = 0; chan < rxRuntimeConfig.channelCount; chan++) {
@ -288,18 +296,12 @@ void processRxChannels(void)
}
}
void processDataDrivenRx(void)
static void processDataDrivenRx(void)
{
if (rcDataReceived) {
failsafeReset();
}
processRxChannels();
rcDataReceived = false;
}
void processNonDataDrivenRx(void)
static void processNonDataDrivenRx(void)
{
rcSampleIndex++;

View File

@ -26,6 +26,12 @@
#define DEFAULT_SERVO_MIDDLE 1500
#define DEFAULT_SERVO_MAX 2000
typedef enum {
SERIAL_RX_FRAME_PENDING = 0,
SERIAL_RX_FRAME_COMPLETE = (1 << 0),
SERIAL_RX_FRAME_FAILSAFE = (1 << 1)
} serialrxFrameState_t;
typedef enum {
SERIALRX_SPEKTRUM1024 = 0,
SERIALRX_SPEKTRUM2048 = 1,
@ -93,6 +99,6 @@ bool shouldProcessRx(uint32_t currentTime);
void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime);
void parseRcChannels(const char *input, rxConfig_t *rxConfig);
bool isSerialRxFrameComplete(rxConfig_t *rxConfig);
uint8_t serialRxFrameStatus(rxConfig_t *rxConfig);
void updateRSSI(uint32_t currentTime);

View File

@ -168,10 +168,10 @@ static void sbusDataReceive(uint16_t c)
}
}
bool sbusFrameComplete(void)
uint8_t sbusFrameStatus(void)
{
if (!sbusFrameDone) {
return false;
return SERIAL_RX_FRAME_PENDING;
}
sbusFrameDone = false;
@ -222,13 +222,13 @@ bool sbusFrameComplete(void)
debug[0] = sbusStateFlags;
#endif
// RX *should* still be sending valid channel data, so use it.
return false;
return SERIAL_RX_FRAME_COMPLETE | SERIAL_RX_FRAME_FAILSAFE;
}
#ifdef DEBUG_SBUS_PACKETS
debug[0] = sbusStateFlags;
#endif
return true;
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View File

@ -17,4 +17,4 @@
#pragma once
bool sbusFrameComplete(void);
uint8_t sbusFrameStatus(void);

View File

@ -49,15 +49,18 @@ static uint8_t spek_chan_shift;
static uint8_t spek_chan_mask;
static bool rcFrameComplete = false;
static bool spekHiRes = false;
static bool spekDataIncoming = false;
static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
static void spektrumDataReceive(uint16_t c);
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
rxRuntimeConfigPtr = rxRuntimeConfig;
switch (rxConfig->serialrx_provider) {
case SERIALRX_SPEKTRUM2048:
// 11 bit frames
@ -95,7 +98,6 @@ static void spektrumDataReceive(uint16_t c)
static uint32_t spekTimeLast, spekTimeInterval;
static uint8_t spekFramePosition;
spekDataIncoming = true;
spekTime = micros();
spekTimeInterval = spekTime - spekTimeLast;
spekTimeLast = spekTime;
@ -109,27 +111,33 @@ static void spektrumDataReceive(uint16_t c)
}
}
bool spektrumFrameComplete(void)
static uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
uint8_t spektrumFrameStatus(void)
{
return rcFrameComplete;
uint8_t b;
if (!rcFrameComplete) {
return SERIAL_RX_FRAME_PENDING;
}
rcFrameComplete = false;
for (b = 3; b < SPEK_FRAME_SIZE; b += 2) {
uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift);
if (spekChannel < rxRuntimeConfigPtr->channelCount && spekChannel < SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT) {
spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b];
}
}
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
uint16_t data;
static uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
uint8_t b;
if (rcFrameComplete) {
for (b = 3; b < SPEK_FRAME_SIZE; b += 2) {
uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift);
if (spekChannel < rxRuntimeConfig->channelCount && spekChannel < SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT)
spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b];
}
rcFrameComplete = false;
}
if (chan >= rxRuntimeConfig->channelCount || !spekDataIncoming) {
if (chan >= rxRuntimeConfig->channelCount) {
return 0;
}

View File

@ -20,4 +20,4 @@
#define SPEKTRUM_SAT_BIND_DISABLED 0
#define SPEKTRUM_SAT_BIND_MAX 10
bool spektrumFrameComplete(void);
uint8_t spektrumFrameStatus(void);

View File

@ -104,18 +104,31 @@ static void sumdDataReceive(uint16_t c)
#define SUMD_BYTES_PER_CHANNEL 2
bool sumdFrameComplete(void)
#define SUMD_FRAME_STATE_OK 0x01
#define SUMD_FRAME_STATE_FAILSAFE 0x81
uint8_t sumdFrameStatus(void)
{
uint8_t channelIndex;
uint8_t frameStatus = SERIAL_RX_FRAME_PENDING;
if (!sumdFrameDone) {
return false;
return frameStatus;
}
sumdFrameDone = false;
if (sumd[1] != 0x01) {
return false;
switch (sumd[1]) {
case SUMD_FRAME_STATE_FAILSAFE:
frameStatus = SERIAL_RX_FRAME_COMPLETE | SERIAL_RX_FRAME_FAILSAFE;
break;
case SUMD_FRAME_STATE_OK:
frameStatus = SERIAL_RX_FRAME_COMPLETE;
break;
default:
return frameStatus;
}
if (sumdChannelCount > SUMD_MAX_CHANNEL)
@ -127,7 +140,7 @@ bool sumdFrameComplete(void)
sumd[SUMD_BYTES_PER_CHANNEL * channelIndex + SUMD_OFFSET_CHANNEL_1_LOW]
);
}
return true;
return frameStatus;
}
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View File

@ -17,4 +17,4 @@
#pragma once
bool sumdFrameComplete(void);
uint8_t sumdFrameStatus(void);

View File

@ -97,18 +97,18 @@ static void sumhDataReceive(uint16_t c)
}
}
bool sumhFrameComplete(void)
uint8_t sumhFrameStatus(void)
{
uint8_t channelIndex;
if (!sumhFrameDone) {
return false;
return SERIAL_RX_FRAME_PENDING;
}
sumhFrameDone = false;
if (!((sumhFrame[0] == 0xA8) && (sumhFrame[SUMH_FRAME_SIZE - 2] == 0))) {
return false;
return SERIAL_RX_FRAME_PENDING;
}
for (channelIndex = 0; channelIndex < SUMH_MAX_CHANNEL_COUNT; channelIndex++) {
@ -116,7 +116,7 @@ bool sumhFrameComplete(void)
sumhChannels[channelIndex] = (((uint32_t)(sumhFrame[(channelIndex << 1) + 3]) << 8)
+ sumhFrame[(channelIndex << 1) + 4]) / 6.4 - 375;
}
return true;
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View File

@ -17,4 +17,4 @@
#pragma once
bool sumhFrameComplete(void);
uint8_t sumhFrameStatus(void);

View File

@ -292,20 +292,21 @@ static void xBusDataReceive(uint16_t c)
}
// Indicate time to read a frame from the data...
bool xBusFrameComplete(void)
uint8_t xBusFrameStatus(void)
{
return xBusFrameReceived;
if (!xBusFrameReceived) {
return SERIAL_RX_FRAME_PENDING;
}
xBusFrameReceived = false;
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
uint16_t data;
// Mark frame as read
if (xBusFrameReceived) {
xBusFrameReceived = false;
}
// Deliver the data wanted
if (chan >= rxRuntimeConfig->channelCount) {
return 0;

View File

@ -20,4 +20,4 @@
#include "rx/rx.h"
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
bool xBusFrameComplete(void);
uint8_t xBusFrameStatus(void);

View File

@ -50,7 +50,7 @@ uint16_t batteryAdcToVoltage(uint16_t src)
{
// calculate battery voltage based on ADC reading
// result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 0xFFF = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V
return (((src) * 3.3f) / 0xFFF) * batteryConfig->vbatscale;
return ((uint32_t)src * batteryConfig->vbatscale * 33 + (0xFFF * 5)) / (0xFFF * 10);
}
#define BATTERY_SAMPLE_COUNT 8

View File

@ -374,7 +374,7 @@ retry:
}
// Found anything? Check if error or ACC is really missing.
if (accHardwareToUse != ACC_DEFAULT && accHardware == ACC_NONE) {
if (accHardware == ACC_NONE && accHardwareToUse != ACC_DEFAULT && accHardwareToUse != ACC_NONE) {
// Nothing was found and we have a forced sensor that isn't present.
accHardwareToUse = ACC_DEFAULT;
goto retry;
@ -526,7 +526,7 @@ retry:
break;
}
if (magHardwareToUse != MAG_DEFAULT && magHardware == MAG_NONE) {
if (magHardware == MAG_NONE && magHardwareToUse != MAG_DEFAULT && magHardwareToUse != MAG_NONE) {
// Nothing was found and we have a forced sensor that isn't present.
magHardwareToUse = MAG_DEFAULT;
goto retry;

View File

@ -109,6 +109,7 @@ extern int16_t telemTemperature1; // FIXME dependency on mw.c
#define ID_ACC_X 0x24
#define ID_ACC_Y 0x25
#define ID_ACC_Z 0x26
#define ID_VOLTAGE_AMP 0x39
#define ID_VOLTAGE_AMP_BP 0x3A
#define ID_VOLTAGE_AMP_AP 0x3B
#define ID_CURRENT 0x28
@ -334,7 +335,6 @@ static void sendVario(void)
static void sendVoltage(void)
{
static uint16_t currentCell = 0;
uint16_t cellNumber;
uint32_t cellVoltage;
uint16_t payload;
@ -345,16 +345,14 @@ static void sendVoltage(void)
* l: Low voltage bits
* h: High voltage bits
* c: Cell number (starting at 0)
*
* The actual value sent for cell voltage has resolution of 0.002 volts
* Since vbat has resolution of 0.1 volts it has to be multiplied by 50
*/
cellVoltage = vbat / batteryCellCount;
// Map to 12 bit range
cellVoltage = (cellVoltage * 2100) / 42;
cellNumber = currentCell % batteryCellCount;
cellVoltage = ((uint32_t)vbat * 100 + batteryCellCount) / (batteryCellCount * 2);
// Cell number is at bit 9-12
payload = (cellNumber << 4);
payload = (currentCell << 4);
// Lower voltage bits are at bit 0-8
payload |= ((cellVoltage & 0x0ff) << 8);
@ -374,12 +372,20 @@ static void sendVoltage(void)
*/
static void sendVoltageAmp(void)
{
uint16_t voltage = (vbat * 110) / 21;
if (telemetryConfig->frsky_vfas_precision == FRSKY_VFAS_PRECISION_HIGH) {
/*
* Use new ID 0x39 to send voltage directly in 0.1 volts resolution
*/
sendDataHead(ID_VOLTAGE_AMP);
serialize16(vbat);
} else {
uint16_t voltage = (vbat * 110) / 21;
sendDataHead(ID_VOLTAGE_AMP_BP);
serialize16(voltage / 100);
sendDataHead(ID_VOLTAGE_AMP_AP);
serialize16(((voltage % 100) + 5) / 10);
sendDataHead(ID_VOLTAGE_AMP_BP);
serialize16(voltage / 100);
sendDataHead(ID_VOLTAGE_AMP_AP);
serialize16(((voltage % 100) + 5) / 10);
}
}
static void sendAmperage(void)

View File

@ -18,6 +18,11 @@
#ifndef TELEMETRY_FRSKY_H_
#define TELEMETRY_FRSKY_H_
typedef enum {
FRSKY_VFAS_PRECISION_LOW = 0,
FRSKY_VFAS_PRECISION_HIGH
} frskyVFasPrecision_e;
void handleFrSkyTelemetry(void);
void checkFrSkyTelemetryState(void);

View File

@ -41,7 +41,8 @@ typedef struct telemetryConfig_s {
float gpsNoFixLatitude;
float gpsNoFixLongitude;
frskyGpsCoordFormat_e frsky_coordinate_format;
frskyUnit_e frsky_unit;
frskyUnit_e frsky_unit;
uint8_t frsky_vfas_precision;
} telemetryConfig_t;
void checkTelemetryState(void);

View File

@ -53,14 +53,14 @@ TEST(BatteryTest, BatteryADCToVoltage)
batteryInit(&batteryConfig);
batteryAdcToVoltageExpectation_t batteryAdcToVoltageExpectations[] = {
{1420, 125, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1430, 126, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1440, 127, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1890, 167, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1900, 168, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1910, 169, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{ 0, 0, VBAT_SCALE_MAX},
{4096, 841, VBAT_SCALE_MAX}
{1420, 126 /*125.88*/, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1430, 127 /*126.76*/, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1440, 128 /*127.65*/, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1890, 168 /*167.54*/, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1900, 168 /*168.42*/, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{1910, 169 /*169.31*/, ELEVEN_TO_ONE_VOLTAGE_DIVIDER},
{ 0, 0 /* 0.00*/, VBAT_SCALE_MAX},
{4096, 842 /*841.71*/, VBAT_SCALE_MAX}
};
uint8_t testIterationCount = sizeof(batteryAdcToVoltageExpectations) / sizeof(batteryAdcToVoltageExpectation_t);
@ -77,7 +77,7 @@ TEST(BatteryTest, BatteryADCToVoltage)
#endif
uint16_t pointOneVoltSteps = batteryAdcToVoltage(batteryAdcToVoltageExpectation->adcReading);
EXPECT_EQ(pointOneVoltSteps, batteryAdcToVoltageExpectation->expectedVoltageInDeciVoltSteps);
EXPECT_EQ(batteryAdcToVoltageExpectation->expectedVoltageInDeciVoltSteps, pointOneVoltSteps);
}
}