From 8375831f427de9c22e6fbd8d57437cb4ef47911b Mon Sep 17 00:00:00 2001 From: Dustin Date: Mon, 29 Dec 2014 19:58:09 -0700 Subject: [PATCH 01/41] Added failsafe explanation and fixed minor errors Fixed grammar, typos, and adjusted formatting. Added additional explanation on items, and added a step by step instruction to setting up failsafe for the first time. --- docs/Failsafe.md | 39 ++++++++++++++++++++++++++++++--------- 1 file changed, 30 insertions(+), 9 deletions(-) diff --git a/docs/Failsafe.md b/docs/Failsafe.md index a5fafa4b60..382ba04bad 100644 --- a/docs/Failsafe.md +++ b/docs/Failsafe.md @@ -6,51 +6,72 @@ There are two types of 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. +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. Flight controller based failsafe is where the flight controller attempts to detect signal loss from your receiver. -It is possible to use both types at the same time and may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect. +It is possible to use both types at the same time which may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect. ## 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. -After the failsafe has been forced a landing, the flight controller cannot be armed and has to be reset. +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 looses signal. It then attempts to prevent your aircraft from flying away uncontrollably. The failsafe is activated when: Either: -a) no valid channel data from the RX via Serial RX. + +a) no valid channel data from the RX is received via Serial RX. + b) the first 4 Parallel PWM/PPM channels do not have valid signals. And: + c) the failsafe guard time specified by `failsafe_delay` has elapsed. ## Configuration -There are a few settings for it, as below. +When configuring the flight controller failsafe, use the following steps: + +1. Configure your receiver to do one of the following: + +a) Upon signal loss, send no signal/pulses over the channels + +b) Send an invalid signal over the channels (for example, send values lower than 'failsafe_min_usec') + +See your receiver's documentation for direction on how to accomplish one of these. + +2. Set 'failsafe_off_delay' to an appropriate value based on how high you fly + +3. Set 'failsafe_throttle' to a value that allows the aircraft to descend at approximately one meter per second. + + +These are the basic steps for flight controller failsafe configuration, see Failsafe Settings below for additional settings that may be changed. + +##Failsafe Settings Failsafe delays are configured in 0.1 second steps. 1 step = 0.1sec + 1 second = 10 steps ### `failsafe_delay` -Guard time for failsafe activation after signal lost. +Guard time for failsafe activation after signal lost. This is the amount of time the flight controller waits to see if it begins receiving a valid signal again before activating failsafe. ### `failsafe_off_delay` -Delay after failsafe activates before motors finally turn off. If you fly high you may need more time. +Delay after failsafe activates before motors finally turn off. This is the amount of time 'failsafe_throttle' is active. If you fly at higher altitudes you may need more time to descend safely. ### `failsafe_throttle` Throttle level used for landing. Specify a value that causes the aircraft to descend at about 1M/sec. -Use standard RX usec values. See Rx documentation. +Use standard RX usec values. See RX documentation. ### `failsafe_min_usec` @@ -64,7 +85,7 @@ The longest PWM/PPM pulse considered valid. Only valid when using Parallel PWM or PPM receivers. -This setting helps catch when your RX stops sending any data when the RX looses signal. +This setting helps detect when your RX stops sending any data when the RX looses signal. With a Graupner GR-24 configured for PWM output with failsafe on channels 1-4 set to OFF in the receiver settings then this setting, at it's default value, will allow failsafe to be activated. From 152cec5e3b0a8fe670c5e5c17af861da083f2f23 Mon Sep 17 00:00:00 2001 From: Dave Pitman Date: Thu, 1 Jan 2015 13:55:18 -0800 Subject: [PATCH 02/41] Update Battery.md --- docs/Battery.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/docs/Battery.md b/docs/Battery.md index 8c02b1cb35..979193f129 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -46,6 +46,8 @@ Configure min/max cell voltages using the following CLI setting: `vbat_max_cell_voltage` - maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, i.e. 43 = 4.3V +`set vbat_warning_cell_voltage` - warning voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 34 = 3.4V + `vbat_min_cell_voltage` - minimum voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 33 = 3.3V e.g. @@ -53,6 +55,7 @@ e.g. ``` set vbat_scale = 110 set vbat_max_cell_voltage = 43 +set vbat_warning_cell_voltage = 34 set vbat_min_cell_voltage = 33 ``` From b8b2e369ba89db74a99fceeb7bfa83f6f61df127 Mon Sep 17 00:00:00 2001 From: Velyks Date: Wed, 7 Jan 2015 01:06:21 +0000 Subject: [PATCH 03/41] Update Board - CJMCU.md Clarified how to identify the difference between CJMCU revisions. --- docs/Board - CJMCU.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md index d321e90493..99e40dd9b2 100644 --- a/docs/Board - CJMCU.md +++ b/docs/Board - CJMCU.md @@ -9,8 +9,8 @@ This board does not have an onboard USB-Serial converter, so an external adapter | Revision | Notes | | -------- | ----- | -| 1 | no boot jumper at the edge of the board. | -| 2 | identified by no boot jumper pads at the edge of the board. | +| 1 | No boot jumper pads by LED1. | +| 2 | Boot jumper pads presoldered with pins and a jumper by LED1. | Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlier versions to version 2 boards. From 70d482e8e07c13ac11645852d3404095a6c9482a Mon Sep 17 00:00:00 2001 From: Velyks Date: Wed, 7 Jan 2015 10:52:09 +0000 Subject: [PATCH 04/41] Update Board - CJMCU.md Added information on how to charge a battery using the onboard TP4056. Added clarification and notes to the RX Connections section about the VCC pin. --- docs/Board - CJMCU.md | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md index 99e40dd9b2..058c5c4e79 100644 --- a/docs/Board - CJMCU.md +++ b/docs/Board - CJMCU.md @@ -24,9 +24,11 @@ Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlie | PA1 | RC Channel 2 | | PA2 | RC Channel 3 / USART2 TX | | PA3 | RC Channel 4 / USART2 RX | -| VCC | Power +3.3v | +| VCC | Power (See note) | | GND | Ground | +NOTE: The VCC RX Pin is not regulated and will supply what ever voltage is provided to the board, this will mean it'll provide 5v if a 5v serial connection is used. Be careful if you are using a voltage sensitive RX. A regulated 3.3v supply can be found on the top pin of column 1, just below the RX GND pin. + ## Serial Connections USART1 (along with power) is on the following pins. @@ -112,6 +114,26 @@ To flash the board: boot, if anything goes wrong, simply unsolder these pins and the bootloader will start, allowing you to reflash. You cannot overwrite the bootloader. +# Charging + +The CJMCU has on it a TP4056 Lithium battery charging IC that can charge a 1S battery at 1A using a provided 5v supply attached to the 5v serial pin. + +To charge an attached battery: + * Set the power switch to OFF + * Set the charge switch to CHG + * Plug in a 1S battery to the battery pins + * Plug in a 5v supply to the 5v serial pins + +The two nearby LEDs will show the status of charging: + +| Status | Green LED | Red LED | +|--------------------|-----------|-----------| +| Charging | On | Off | +| Finished | Off | On | +| 5v not connected | Off | Off | +| Batt not connected | Flashing | On | + + # Helpful Hints * If you are only using a 4 channel RX, in the auxiliary configuration tab, you can add a "Horizon" mode range around 1500 From e1dff63017d72624050e65ff00bf5dde2ba8b44b Mon Sep 17 00:00:00 2001 From: Velyks Date: Wed, 7 Jan 2015 10:54:23 +0000 Subject: [PATCH 05/41] Update Board - CJMCU.md Added information on when the TP4056 will stop charging. --- docs/Board - CJMCU.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md index 058c5c4e79..00fac2b847 100644 --- a/docs/Board - CJMCU.md +++ b/docs/Board - CJMCU.md @@ -124,6 +124,8 @@ To charge an attached battery: * Plug in a 1S battery to the battery pins * Plug in a 5v supply to the 5v serial pins +The charger will finish when either the battery reaches 4.2v, or the battery's voltage is greater than the charger's input voltage. + The two nearby LEDs will show the status of charging: | Status | Green LED | Red LED | From 540268ec180461973b388ece49f28ed6e4e89b90 Mon Sep 17 00:00:00 2001 From: Velyks Date: Wed, 7 Jan 2015 11:07:20 +0000 Subject: [PATCH 06/41] Update Board - CJMCU.md Clarified the Flashing section with instructions on how to bypass the bootloader on both revisions. --- docs/Board - CJMCU.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md index 00fac2b847..058fb0870c 100644 --- a/docs/Board - CJMCU.md +++ b/docs/Board - CJMCU.md @@ -110,8 +110,8 @@ To flash the board: * Click "Flash Firmware" * You should see "Programming: SUCCESSFUL" in the log box * Click "Connect" -> This should open the "Initial Setup" tab and you should see sensor data from the quad shown - * Unplug the quad and solder across the 2 "BOOT0" pins - This prevents the board from going into bootloader mode on next - boot, if anything goes wrong, simply unsolder these pins and the bootloader will start, allowing you to reflash. You cannot + * Unplug the quad and short the 2 "BOOT0" pins. Revision 1 boards require this to be soldered, revision 2 boards can connect the included jumper to the two pre-soldered pins - This prevents the board from going into bootloader mode on next + boot, if anything goes wrong, simply disconnect these two pins and the bootloader will start, allowing you to reflash. You cannot overwrite the bootloader. # Charging From 4e17eca2e5e4e6917e6e203f3911b3cdff2e45ac Mon Sep 17 00:00:00 2001 From: idefixsin Date: Thu, 8 Jan 2015 11:21:30 +0800 Subject: [PATCH 07/41] Update Board - Sparky.md Added Device Firmware Upload (DFU, USB) instructions for Windows --- docs/Board - Sparky.md | 50 +++++++++++++++++++++++++++++++++++++++++- 1 file changed, 49 insertions(+), 1 deletion(-) diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index c0616c598f..af8c89bc79 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -27,7 +27,55 @@ Tested with revision 1 board. # Flashing -## Via Device Firmware Upload (DFU, USB) +## Via Device Firmware Upload (DFU, USB) - Windows + +These instructions are for flashing the Sparky board under Windows using DfuSE. +Credits go to Thomas Shue (Full video of the below steps can be found here: https://www.youtube.com/watch?v=I4yHiRVRY94) + +Required Software: +DfuSE Version 3.0.2 (latest version 3.0.4 causes errors): http://code.google.com/p/multipilot32/downloads/detail?name=DfuSe.rar +STM VCP Driver 1.4.0: http://www.st.com/web/en/catalog/tools/PF257938 + +A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows. + +``` +Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive +Download the latest Sparky release (cleanflight_SPARKY.hex) from: https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive + +In your DfuSE folder go to BIN and start DfuFileMgr.exe +Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK +Press: "S19 or Hex.." +Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open (you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file +Press: "Generate" and select the .dfu output file and location +If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!" +``` + +Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led. + +Check the windows device manager to make sure the board is recognized correctly. +It should show up as "STM Device in DFU mode" under Universal Serial Bus Controllers + +If it shows up as "STMicroelectronics Virtual COM" under Ports (COM & LPT) instead then the board is not in DFU mode. Disconnect the board, short the bootloader pins again while connecting the board. + +If the board shows up as "STM 32 Bootloader" device in the device manager, the drivers need to be updated manually. +Select the device in the device manager, press "update drivers", select "manual update drivers" and choose the location where you extracted the STM VCP Drivers, select "let me choose which driver to install". You shoud now be able to select either the STM32 Bootloader driver or the STM in DFU mode driver. Select the later and install. + + +Then flash the binary as below. + +``` +In your DfuSE folder go to BIN and start DfuSeDemo.exe +Select the Sparky Board (STM in DFU Mode) from the Available DFU and compatible HID Devices drop down list +Press "Choose.." at the bootom of the window and select the .dfu file created in the previous step +"File correctly loaded" should appear in the status bar +Press "Upgrade" and confirm with "Yes" +The status bar will show the upload progress and confirm that the upload is complete at the end +``` + +Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal + + +## Via Device Firmware Upload (DFU, USB) - Mac OS X These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project. From b8aed188583b67f13332b73ade2b656f3abc4721 Mon Sep 17 00:00:00 2001 From: idefixsin Date: Thu, 8 Jan 2015 11:22:46 +0800 Subject: [PATCH 08/41] Update Board - Sparky.md --- docs/Board - Sparky.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index af8c89bc79..22e0f492be 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -48,6 +48,7 @@ Press: "S19 or Hex.." Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open (you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file Press: "Generate" and select the .dfu output file and location If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!" + ``` Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led. @@ -70,6 +71,7 @@ Press "Choose.." at the bootom of the window and select the .dfu file created in "File correctly loaded" should appear in the status bar Press "Upgrade" and confirm with "Yes" The status bar will show the upload progress and confirm that the upload is complete at the end + ``` Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal From cd8d63995b349f74447b403fce2983a4090c7c28 Mon Sep 17 00:00:00 2001 From: idefixsin Date: Thu, 8 Jan 2015 11:24:41 +0800 Subject: [PATCH 09/41] Update Board - Sparky.md Added Device Firmware Upload (DFU, USB) instructions for Windows --- docs/Board - Sparky.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index 22e0f492be..9501b5912e 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -40,12 +40,14 @@ A binary file is required for DFU, not a .hex file. If one is not included in t ``` Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive -Download the latest Sparky release (cleanflight_SPARKY.hex) from: https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive +Download the latest Sparky release (cleanflight_SPARKY.hex) from: +https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive In your DfuSE folder go to BIN and start DfuFileMgr.exe Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK Press: "S19 or Hex.." -Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open (you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file +Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open +(you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file) Press: "Generate" and select the .dfu output file and location If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!" From adb3ec9bcbd5c4ebc13138ff6d30cc6853baa604 Mon Sep 17 00:00:00 2001 From: Velyks Date: Thu, 8 Jan 2015 11:13:11 +0000 Subject: [PATCH 10/41] Added more revision differences. Added to the revision differences to detail the different LEDs. --- docs/Board - CJMCU.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Board - CJMCU.md b/docs/Board - CJMCU.md index 058fb0870c..a377206101 100644 --- a/docs/Board - CJMCU.md +++ b/docs/Board - CJMCU.md @@ -9,8 +9,8 @@ This board does not have an onboard USB-Serial converter, so an external adapter | Revision | Notes | | -------- | ----- | -| 1 | No boot jumper pads by LED1. | -| 2 | Boot jumper pads presoldered with pins and a jumper by LED1. | +| 1 | No boot jumper pads by LED1. Uses blue and red LEDs | +| 2 | Boot jumper pads presoldered with pins and a jumper by LED1. Uses green and red LEDs. | Version 2 boards are supported from firmware v1.4.0 onwards, do NOT flash earlier versions to version 2 boards. From 9729c59cb0dca1060f093ed71eba7d4f6fcc7772 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Thu, 8 Jan 2015 22:47:28 +0000 Subject: [PATCH 11/41] Fix MSP_LED_STRIP_CONFIG length. --- src/main/io/serial_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 8e5382aafa..46dd9bc5a4 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1097,7 +1097,7 @@ static bool processOutCommand(uint8_t cmdMSP) break; case MSP_LED_STRIP_CONFIG: - headSerialReply(MAX_LED_STRIP_LENGTH * 4); + headSerialReply(MAX_LED_STRIP_LENGTH * 6); for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; serialize16((ledConfig->flags & LED_DIRECTION_MASK) >> LED_DIRECTION_BIT_OFFSET); From ce49dcee31bc6af8ffd9ae505d3858d28e3c8c52 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Thu, 8 Jan 2015 23:19:57 +0000 Subject: [PATCH 12/41] Bump MSP api version. Ensure the the number of LEDs in the MSP_SET_LED_STRIP_CONFIG packet is validated. --- src/main/io/serial_msp.c | 35 +++++++++++++++++++++-------------- 1 file changed, 21 insertions(+), 14 deletions(-) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 46dd9bc5a4..8943c4453d 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -121,7 +121,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 1 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR +#define API_VERSION_MINOR 2 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR #define API_VERSION_LENGTH 2 @@ -1441,22 +1441,29 @@ static bool processInCommand(void) break; case MSP_SET_LED_STRIP_CONFIG: - for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { - ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; - uint16_t mask; - // currently we're storing directions and functions in a uint16 (flags) - // the msp uses 2 x uint16_t to cater for future expansion - mask = read16(); - ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK; + { + uint8_t ledCount = currentPort->dataSize / 6; + if (ledCount != MAX_LED_STRIP_LENGTH) { + headSerialError(0); + break; + } + for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) { + ledConfig_t *ledConfig = &masterConfig.ledConfigs[i]; + uint16_t mask; + // currently we're storing directions and functions in a uint16 (flags) + // the msp uses 2 x uint16_t to cater for future expansion + mask = read16(); + ledConfig->flags = (mask << LED_DIRECTION_BIT_OFFSET) & LED_DIRECTION_MASK; - mask = read16(); - ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK; + mask = read16(); + ledConfig->flags |= (mask << LED_FUNCTION_BIT_OFFSET) & LED_FUNCTION_MASK; - mask = read8(); - ledConfig->xy = CALCULATE_LED_X(mask); + mask = read8(); + ledConfig->xy = CALCULATE_LED_X(mask); - mask = read8(); - ledConfig->xy |= CALCULATE_LED_Y(mask); + mask = read8(); + ledConfig->xy |= CALCULATE_LED_Y(mask); + } } break; #endif From 6b5f1fc38bec05a020f2302bf757465760da3e85 Mon Sep 17 00:00:00 2001 From: Petr Ledvina Date: Fri, 9 Jan 2015 09:04:00 +0100 Subject: [PATCH 13/41] fix index overflow in channel mapping --- src/main/rx/rx.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 648305731d..8e4bda1e85 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -345,7 +345,7 @@ void parseRcChannels(const char *input, rxConfig_t *rxConfig) for (c = input; *c; c++) { s = strchr(rcChannelLetters, *c); - if (s) + if (s && (s < rcChannelLetters + MAX_MAPPABLE_RX_INPUTS)) rxConfig->rcmap[s - rcChannelLetters] = c - input; } } From 20837a135346bd6458c90c222e4846f194849be4 Mon Sep 17 00:00:00 2001 From: Joel Fuster Date: Fri, 2 Jan 2015 20:27:57 -0500 Subject: [PATCH 14/41] Mixer and SBUS documenation updates --- docs/Mixer.md | 58 +++++++++++++++++++++++++++++++++++++++++++++++++++ docs/Rx.md | 6 +++++- 2 files changed, 63 insertions(+), 1 deletion(-) create mode 100644 docs/Mixer.md diff --git a/docs/Mixer.md b/docs/Mixer.md new file mode 100644 index 0000000000..777cae38d1 --- /dev/null +++ b/docs/Mixer.md @@ -0,0 +1,58 @@ +# Mixer + +Cleanflight supports a number of mixing configurations as well as custom mixing. Mixer configurations determine how the servos and motors work together to control the aircraft. + +## Configuration + +To use a built-in mixing configuration, you can use the Chrome configuration GUI. It includes images of the various mixer types to assist in making the proper connections. See the Configuration section of the documentation for more information on the GUI. + +You can also use the Command Line Interface (CLI) to set the mixer type: + +1. Use `mixer list` to see a list of supported mixes +2. Select a mixer. For example, to select TRI, use `mixer TRI` +3. You must use `save` to preserve your changes + +## Supported Mixer Types + +| Name | Description | Motors | Servos | +| ------------- | ------------------------- | -------------- | ---------------- | +| TRI | Tricopter | M1-M3 | S1 | +| QUADP | Quadcopter-Plus | M1-M4 | None | +| QUADX | Quadcopter-X | M1-M4 | None | +| BI | Bicopter (left/right) | M1-M2 | S1, S2 | +| GIMBAL | Gimbal control | N/A | S1, S2 | +| Y6 | Y6-copter | M1-M6 | None | +| HEX6 | Hexacopter-Plus | M1-M6 | None | +| FLYING_WING | Fixed wing; elevons | M1 | S1, S2 | +| Y4 | Y4-copter | M1-M4 | None | +| HEX6X | Hexacopter-X | M1-M6 | None | +| OCTOX8 | Octocopter-X (over/under) | M1-M8 | None | +| OCTOFLATP | Octocopter-FlatPlus | M1-M8 | None | +| OCTOFLATX | Octocopter-FlatX | M1-M8 | None | +| AIRPLANE | Fixed wing; Ax2, R, E | M1 | S1, S2, S3, S4 | +| HELI_120_CCPM | | | | +| HELI_90_DEG | | | | +| VTAIL4 | Quadcopter with V-Tail | M1-M4 | N/A | +| HEX6H | Hexacopter-H | M1-M6 | None | +| PPM_TO_SERVO | | | | +| DUALCOPTER | Dualcopter | M1-M2 | S1, S2 | +| SINGLECOPTER | Conventional helicopter | M1 | S1 | +| ATAIL4 | Quadcopter with A-Tail | M1-M4 | N/A | +| CUSTOM | User-defined | | | + + +## Servo filtering + +A low-pass filter can be enabled for the servos. It may be useful for avoiding structural modes in the airframe, for example. Currently it can only be configured via the CLI: + +1. Use `set servo_lowpass_freq_idx = nn` to select the cutoff frequency. Valid values range from 0 to 99. +2. Use `set servo_lowpass_enable = 1` to enable filtering. + +The actual cutoff frequency is determined by the value of the `looptime` variable and the selected index. +The formula is: +`Frequency = 1000000 * (servo_lowpass_freq_idx + 1)*0.0025 / looptime )` + + +For example, if `servo_lowpass_freq_idx` is set to 40, and looptime is set to the default of 3500 us (0.0035 s), the cutoff frequency will be 29.3 Hz. + + diff --git a/docs/Rx.md b/docs/Rx.md index 96c3340675..361916ce19 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -47,7 +47,11 @@ http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118 ### S.BUS -16 channels via serial currently supported. +16 channels via serial currently supported. See the Serial chapter in the documentation for a configuration example. + +* In most cases you will need an inverter between the receiver output and the flight controller hardware. +* Softserial ports cannot be used with SBUS because it runs at too high of a bitrate (1Mbps). Refer to the chapter specific to your board to determine which port(s) may be used. +* You will need to configure the channel mapping in the GUI (Receiver tab) or CLI (`map` command). These receivers are reported working: From 77bfd1f708a275a31fcc52c18fab47d0888db356 Mon Sep 17 00:00:00 2001 From: idefixsin Date: Thu, 8 Jan 2015 11:21:30 +0800 Subject: [PATCH 15/41] Update Board - Sparky.md Added Device Firmware Upload (DFU, USB) instructions for Windows --- docs/Board - Sparky.md | 50 +++++++++++++++++++++++++++++++++++++++++- 1 file changed, 49 insertions(+), 1 deletion(-) diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index c0616c598f..af8c89bc79 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -27,7 +27,55 @@ Tested with revision 1 board. # Flashing -## Via Device Firmware Upload (DFU, USB) +## Via Device Firmware Upload (DFU, USB) - Windows + +These instructions are for flashing the Sparky board under Windows using DfuSE. +Credits go to Thomas Shue (Full video of the below steps can be found here: https://www.youtube.com/watch?v=I4yHiRVRY94) + +Required Software: +DfuSE Version 3.0.2 (latest version 3.0.4 causes errors): http://code.google.com/p/multipilot32/downloads/detail?name=DfuSe.rar +STM VCP Driver 1.4.0: http://www.st.com/web/en/catalog/tools/PF257938 + +A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows. + +``` +Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive +Download the latest Sparky release (cleanflight_SPARKY.hex) from: https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive + +In your DfuSE folder go to BIN and start DfuFileMgr.exe +Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK +Press: "S19 or Hex.." +Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open (you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file +Press: "Generate" and select the .dfu output file and location +If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!" +``` + +Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led. + +Check the windows device manager to make sure the board is recognized correctly. +It should show up as "STM Device in DFU mode" under Universal Serial Bus Controllers + +If it shows up as "STMicroelectronics Virtual COM" under Ports (COM & LPT) instead then the board is not in DFU mode. Disconnect the board, short the bootloader pins again while connecting the board. + +If the board shows up as "STM 32 Bootloader" device in the device manager, the drivers need to be updated manually. +Select the device in the device manager, press "update drivers", select "manual update drivers" and choose the location where you extracted the STM VCP Drivers, select "let me choose which driver to install". You shoud now be able to select either the STM32 Bootloader driver or the STM in DFU mode driver. Select the later and install. + + +Then flash the binary as below. + +``` +In your DfuSE folder go to BIN and start DfuSeDemo.exe +Select the Sparky Board (STM in DFU Mode) from the Available DFU and compatible HID Devices drop down list +Press "Choose.." at the bootom of the window and select the .dfu file created in the previous step +"File correctly loaded" should appear in the status bar +Press "Upgrade" and confirm with "Yes" +The status bar will show the upload progress and confirm that the upload is complete at the end +``` + +Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal + + +## Via Device Firmware Upload (DFU, USB) - Mac OS X These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project. From 08cc4b38e3a6bcf0483f8e3d4531812132a3fc84 Mon Sep 17 00:00:00 2001 From: idefixsin Date: Thu, 8 Jan 2015 11:22:46 +0800 Subject: [PATCH 16/41] Update Board - Sparky.md --- docs/Board - Sparky.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index af8c89bc79..22e0f492be 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -48,6 +48,7 @@ Press: "S19 or Hex.." Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open (you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file Press: "Generate" and select the .dfu output file and location If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!" + ``` Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led. @@ -70,6 +71,7 @@ Press "Choose.." at the bootom of the window and select the .dfu file created in "File correctly loaded" should appear in the status bar Press "Upgrade" and confirm with "Yes" The status bar will show the upload progress and confirm that the upload is complete at the end + ``` Disconnect and reconnect the board from USB and continue to configure it via the Cleanflight configurator as per normal From 94e4a0208f1f14064e867c39c4f5a4950a5e3f2f Mon Sep 17 00:00:00 2001 From: idefixsin Date: Thu, 8 Jan 2015 11:24:41 +0800 Subject: [PATCH 17/41] Update Board - Sparky.md Added Device Firmware Upload (DFU, USB) instructions for Windows --- docs/Board - Sparky.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/docs/Board - Sparky.md b/docs/Board - Sparky.md index 22e0f492be..9501b5912e 100644 --- a/docs/Board - Sparky.md +++ b/docs/Board - Sparky.md @@ -40,12 +40,14 @@ A binary file is required for DFU, not a .hex file. If one is not included in t ``` Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive -Download the latest Sparky release (cleanflight_SPARKY.hex) from: https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive +Download the latest Sparky release (cleanflight_SPARKY.hex) from: +https://github.com/cleanflight/cleanflight/releases and store it on your Hardrive In your DfuSE folder go to BIN and start DfuFileMgr.exe Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK Press: "S19 or Hex.." -Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open (you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file +Go to the folder where you saved the cleanflight_SPARKY.hex file, select it and press open +(you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file) Press: "Generate" and select the .dfu output file and location If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!" From b22f30500a6be2baa49b7cf87434359c65bc3306 Mon Sep 17 00:00:00 2001 From: Joel Fuster Date: Fri, 2 Jan 2015 20:27:57 -0500 Subject: [PATCH 18/41] Mixer and SBUS documenation updates --- docs/Mixer.md | 58 +++++++++++++++++++++++++++++++++++++++++++++++++++ docs/Rx.md | 6 +++++- 2 files changed, 63 insertions(+), 1 deletion(-) create mode 100644 docs/Mixer.md diff --git a/docs/Mixer.md b/docs/Mixer.md new file mode 100644 index 0000000000..777cae38d1 --- /dev/null +++ b/docs/Mixer.md @@ -0,0 +1,58 @@ +# Mixer + +Cleanflight supports a number of mixing configurations as well as custom mixing. Mixer configurations determine how the servos and motors work together to control the aircraft. + +## Configuration + +To use a built-in mixing configuration, you can use the Chrome configuration GUI. It includes images of the various mixer types to assist in making the proper connections. See the Configuration section of the documentation for more information on the GUI. + +You can also use the Command Line Interface (CLI) to set the mixer type: + +1. Use `mixer list` to see a list of supported mixes +2. Select a mixer. For example, to select TRI, use `mixer TRI` +3. You must use `save` to preserve your changes + +## Supported Mixer Types + +| Name | Description | Motors | Servos | +| ------------- | ------------------------- | -------------- | ---------------- | +| TRI | Tricopter | M1-M3 | S1 | +| QUADP | Quadcopter-Plus | M1-M4 | None | +| QUADX | Quadcopter-X | M1-M4 | None | +| BI | Bicopter (left/right) | M1-M2 | S1, S2 | +| GIMBAL | Gimbal control | N/A | S1, S2 | +| Y6 | Y6-copter | M1-M6 | None | +| HEX6 | Hexacopter-Plus | M1-M6 | None | +| FLYING_WING | Fixed wing; elevons | M1 | S1, S2 | +| Y4 | Y4-copter | M1-M4 | None | +| HEX6X | Hexacopter-X | M1-M6 | None | +| OCTOX8 | Octocopter-X (over/under) | M1-M8 | None | +| OCTOFLATP | Octocopter-FlatPlus | M1-M8 | None | +| OCTOFLATX | Octocopter-FlatX | M1-M8 | None | +| AIRPLANE | Fixed wing; Ax2, R, E | M1 | S1, S2, S3, S4 | +| HELI_120_CCPM | | | | +| HELI_90_DEG | | | | +| VTAIL4 | Quadcopter with V-Tail | M1-M4 | N/A | +| HEX6H | Hexacopter-H | M1-M6 | None | +| PPM_TO_SERVO | | | | +| DUALCOPTER | Dualcopter | M1-M2 | S1, S2 | +| SINGLECOPTER | Conventional helicopter | M1 | S1 | +| ATAIL4 | Quadcopter with A-Tail | M1-M4 | N/A | +| CUSTOM | User-defined | | | + + +## Servo filtering + +A low-pass filter can be enabled for the servos. It may be useful for avoiding structural modes in the airframe, for example. Currently it can only be configured via the CLI: + +1. Use `set servo_lowpass_freq_idx = nn` to select the cutoff frequency. Valid values range from 0 to 99. +2. Use `set servo_lowpass_enable = 1` to enable filtering. + +The actual cutoff frequency is determined by the value of the `looptime` variable and the selected index. +The formula is: +`Frequency = 1000000 * (servo_lowpass_freq_idx + 1)*0.0025 / looptime )` + + +For example, if `servo_lowpass_freq_idx` is set to 40, and looptime is set to the default of 3500 us (0.0035 s), the cutoff frequency will be 29.3 Hz. + + diff --git a/docs/Rx.md b/docs/Rx.md index 96c3340675..361916ce19 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -47,7 +47,11 @@ http://www.lemon-rx.com/shop/index.php?route=product/product&product_id=118 ### S.BUS -16 channels via serial currently supported. +16 channels via serial currently supported. See the Serial chapter in the documentation for a configuration example. + +* In most cases you will need an inverter between the receiver output and the flight controller hardware. +* Softserial ports cannot be used with SBUS because it runs at too high of a bitrate (1Mbps). Refer to the chapter specific to your board to determine which port(s) may be used. +* You will need to configure the channel mapping in the GUI (Receiver tab) or CLI (`map` command). These receivers are reported working: From 61b08502e826ff36e52ecb20ba7f9c6b75490d43 Mon Sep 17 00:00:00 2001 From: Dustin Date: Mon, 29 Dec 2014 19:58:09 -0700 Subject: [PATCH 19/41] Added failsafe explanation and fixed minor errors Fixed grammar, typos, and adjusted formatting. Added additional explanation on items, and added a step by step instruction to setting up failsafe for the first time. --- docs/Failsafe.md | 39 ++++++++++++++++++++++++++++++--------- 1 file changed, 30 insertions(+), 9 deletions(-) diff --git a/docs/Failsafe.md b/docs/Failsafe.md index afeedf96be..358bbcbb38 100644 --- a/docs/Failsafe.md +++ b/docs/Failsafe.md @@ -6,51 +6,72 @@ There are two types of 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. +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. Flight controller based failsafe is where the flight controller attempts to detect signal loss from your receiver. -It is possible to use both types at the same time and may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect. +It is possible to use both types at the same time which may be desirable. Flight controller failsafe can even help if your receiver signal wires come loose, get damaged or your receiver malfunctions in a way the receiver itself cannot detect. ## 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. -After the failsafe has been forced a landing, the flight controller cannot be armed and has to be reset. +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 is activated when: Either: -a) no valid channel data from the RX via Serial RX. + +a) no valid channel data from the RX is received via Serial RX. + b) the first 4 Parallel PWM/PPM channels do not have valid signals. And: + c) the failsafe guard time specified by `failsafe_delay` has elapsed. ## Configuration -There are a few settings for it, as below. +When configuring the flight controller failsafe, use the following steps: + +1. Configure your receiver to do one of the following: + +a) Upon signal loss, send no signal/pulses over the channels + +b) Send an invalid signal over the channels (for example, send values lower than 'failsafe_min_usec') + +See your receiver's documentation for direction on how to accomplish one of these. + +2. Set 'failsafe_off_delay' to an appropriate value based on how high you fly + +3. Set 'failsafe_throttle' to a value that allows the aircraft to descend at approximately one meter per second. + + +These are the basic steps for flight controller failsafe configuration, see Failsafe Settings below for additional settings that may be changed. + +##Failsafe Settings Failsafe delays are configured in 0.1 second steps. 1 step = 0.1sec + 1 second = 10 steps ### `failsafe_delay` -Guard time for failsafe activation after signal lost. +Guard time for failsafe activation after signal lost. This is the amount of time the flight controller waits to see if it begins receiving a valid signal again before activating failsafe. ### `failsafe_off_delay` -Delay after failsafe activates before motors finally turn off. If you fly high you may need more time. +Delay after failsafe activates before motors finally turn off. This is the amount of time 'failsafe_throttle' is active. If you fly at higher altitudes you may need more time to descend safely. ### `failsafe_throttle` Throttle level used for landing. Specify a value that causes the aircraft to descend at about 1M/sec. -Use standard RX usec values. See Rx documentation. +Use standard RX usec values. See RX documentation. ### `failsafe_min_usec` @@ -64,7 +85,7 @@ The longest PWM/PPM pulse considered valid. Only valid when using Parallel PWM or PPM receivers. -This setting helps catch when your RX stops sending any data when the RX looses signal. +This setting helps detect when your RX stops sending any data when the RX looses signal. With a Graupner GR-24 configured for PWM output with failsafe on channels 1-4 set to OFF in the receiver settings then this setting, at its default value, will allow failsafe to be activated. From e4277de822b19e5bc7beb166459ab5f0b2ee6b51 Mon Sep 17 00:00:00 2001 From: Dave Pitman Date: Thu, 1 Jan 2015 13:55:18 -0800 Subject: [PATCH 20/41] Update Battery.md --- docs/Battery.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/docs/Battery.md b/docs/Battery.md index 99cb492b8e..40dad080b4 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -47,6 +47,8 @@ Configure min/max cell voltages using the following CLI setting: `vbat_max_cell_voltage` - maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, i.e. 43 = 4.3V +`set vbat_warning_cell_voltage` - warning voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 34 = 3.4V + `vbat_min_cell_voltage` - minimum voltage per cell, this triggers battery out alarms, in 0.1V units, i.e. 33 = 3.3V e.g. @@ -54,6 +56,7 @@ e.g. ``` set vbat_scale = 110 set vbat_max_cell_voltage = 43 +set vbat_warning_cell_voltage = 34 set vbat_min_cell_voltage = 33 ``` From bfc348b349ee7f40b0ab0a87d3f251b68a62d76f Mon Sep 17 00:00:00 2001 From: Dave Pitman Date: Wed, 31 Dec 2014 12:41:47 -0800 Subject: [PATCH 21/41] Update Controls.md Include link to a Multiwii TX stick command pdf file This File is licensed under the Creative Commons Attribution-NonCommercial-ShareAlike 3.0 Unported License. To view a copy of this license, visit http://creativecommons.org/licenses/by-nc-sa/3.0/ or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA. --- docs/Controls.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/Controls.md b/docs/Controls.md index 0171c85596..c2b6e14dff 100644 --- a/docs/Controls.md +++ b/docs/Controls.md @@ -30,3 +30,5 @@ HIGH - the channel value for the mapped channel input is around 2000 | Trim Acc Backwards | HIGH | CENTER | LOW | CENTER | | Save setting | LOW | LOW | LOW | HIGH | + +##### Download a graphic [pdf cheat-sheet](https://multiwii.googlecode.com/svn/branches/Hamburger/MultiWii-StickConfiguration-23_v0-5772156649.pdf) with TX stick commands. From ac3d35d971886c52b3b9ec82ee1112d1e4b0dbbb Mon Sep 17 00:00:00 2001 From: Dave Pitman Date: Sat, 3 Jan 2015 12:01:26 -0800 Subject: [PATCH 22/41] Update Controls.md --- docs/Controls.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/Controls.md b/docs/Controls.md index c2b6e14dff..57e5578221 100644 --- a/docs/Controls.md +++ b/docs/Controls.md @@ -32,3 +32,5 @@ HIGH - the channel value for the mapped channel input is around 2000 ##### Download a graphic [pdf cheat-sheet](https://multiwii.googlecode.com/svn/branches/Hamburger/MultiWii-StickConfiguration-23_v0-5772156649.pdf) with TX stick commands. + +The Latest version of this pdf can always be found [Here](https://code.google.com/p/multiwii/source/browse/#svn%2Fbranches%2FHamburger) From 8310a9760508e999d3260842e6d9eb8dae98016a Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Fri, 9 Jan 2015 11:30:21 +0000 Subject: [PATCH 23/41] Updaing receiver documentation. --- docs/Rx.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/docs/Rx.md b/docs/Rx.md index 361916ce19..1d99c394fb 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -58,6 +58,9 @@ These receivers are reported working: FrSky X4RSB 3/16ch Telemetry Receiver http://www.frsky-rc.com/product/pro.php?pro_id=135 +FrSky X8R 8/16ch Telemetry Receiver +http://www.frsky-rc.com/product/pro.php?pro_id=105 + #### OpenTX S.BUS configuration If using OpenTX set the transmitter module to D16 mode and select CH1-16 on the transmitter before binding to allow reception @@ -116,7 +119,7 @@ Only one receiver feature can be enabled at a time. ### Serial RX -See the Configuration document some some RX configuration examples. +See the Serial chapter for some some RX configuration examples. For Serial RX enable `RX_SERIAL` and set the `serialrx_provider` CLI setting as follows. From 0c9c69736dc1c537be12a0d10442e7b3e8288db3 Mon Sep 17 00:00:00 2001 From: Malaquitte Date: Fri, 9 Jan 2015 14:49:48 +0100 Subject: [PATCH 24/41] Update Battery.md Minor text correction --- docs/Battery.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Battery.md b/docs/Battery.md index 40dad080b4..c233c11947 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -78,7 +78,7 @@ Configure capacity using the `battery_capacity` setting, which takes a value in The current meter may need to be configured so that the value read at the ADC input matches actual current draw. Just like you need a voltmeter to correctly calibrate your voltage reading you also need an ammeter to calibrate your current sensor. -Use the following settings to adjust calibrtion. +Use the following settings to adjust calibration. `current_meter_scale` `current_meter_offset` From c8d4743ba04c1ff83b85096f44c430f009d36357 Mon Sep 17 00:00:00 2001 From: JBFUK Date: Fri, 9 Jan 2015 19:22:44 +0000 Subject: [PATCH 25/41] Update LedStrip.md --- docs/LedStrip.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/LedStrip.md b/docs/LedStrip.md index c0ea55ee43..0b6f28fd98 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -51,11 +51,11 @@ uses. e.g. ESC1/BEC1 -> FC, ESC2/BEC2 -> LED strip. It's also possible to pow from another BEC. Just ensure that the GROUND is the same for all BEC outputs and LEDs. -| Target | Pin | LED Strip | Signal | -| --------------------- | --- | --------- | -------| -| Naze/Olimexino | RC5 | Data In | PA6 | -| CC3D | ??? | Data In | PB4 | -| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 | +| Target | Pin | LED Strip | Signal | +| --------------------- | ---- | --------- | -------| +| Naze/Olimexino | RC5 | Data In | PA6 | +| CC3D | RCO5 | Data In | PB4 | +| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 | Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time. From 3e6646ec450b68e79ec8256de878df439a6c67bb Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sat, 10 Jan 2015 22:54:04 +0000 Subject: [PATCH 26/41] STM32F3 - Fix LED Strip timer initialisation. --- src/main/drivers/light_ws2811strip_stm32f30x.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 49e8eae128..8d285b4675 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -68,7 +68,7 @@ void ws2811LedStripHardwareInit(void) TIM_OCInitStructure.TIM_Pulse = 0; TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; TIM_OC1Init(TIM16, &TIM_OCInitStructure); - TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable); + TIM_OC1PreloadConfig(TIM16, TIM_OCPreload_Enable); TIM_CtrlPWMOutputs(TIM16, ENABLE); From 5a07194d620dc15d623939be76c583519c189db4 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sat, 10 Jan 2015 23:33:19 +0000 Subject: [PATCH 27/41] LedStrip - Fix missing GPIO Output type configuration. --- src/main/drivers/light_ws2811strip_stm32f30x.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 8d285b4675..7288a22e6a 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -44,9 +44,10 @@ void ws2811LedStripHardwareInit(void) GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_1); - /* GPIOA Configuration: TIM16 Channel 1 as alternate function push-pull */ + /* Configuration alternate function push-pull */ GPIO_InitStructure.GPIO_Pin = WS2811_PIN; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; + GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_Init(WS2811_GPIO, &GPIO_InitStructure); From 5d8e39f2d9d02f79f7e0232fbf5afcff2765fb4a Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sat, 10 Jan 2015 22:55:22 +0000 Subject: [PATCH 28/41] SPARKY - Add LED STRIP support. Update PWM mapping to avoid PWM/LedStrip clash on Motor output pin 5. --- .../drivers/light_ws2811strip_stm32f30x.c | 66 ++++++++++++------- src/main/drivers/pwm_mapping.c | 11 +++- src/main/drivers/serial_uart_stm32f30x.c | 2 + src/main/target/SPARKY/target.h | 30 +++++++++ 4 files changed, 82 insertions(+), 27 deletions(-) diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 7288a22e6a..8908dda081 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -26,10 +26,16 @@ #include "common/color.h" #include "drivers/light_ws2811strip.h" -#define WS2811_GPIO GPIOB -#define WS2811_PIN Pin_8 // TIM16_CH1 -#define WS2811_PERIPHERAL RCC_AHBPeriph_GPIOB - +#ifndef WS2811_GPIO +#define WS2811_GPIO GPIOB +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB +#define WS2811_PIN Pin_8 // TIM16_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM16 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 +#define WS2811_DMA_CHANNEL DMA1_Channel3 +#define WS2811_IRQ DMA1_Channel3_IRQn +#endif void ws2811LedStripHardwareInit(void) { @@ -40,9 +46,9 @@ void ws2811LedStripHardwareInit(void) uint16_t prescalerValue; - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE); + RCC_AHBPeriphClockCmd(WS2811_GPIO_AHB_PERIPHERAL, ENABLE); - GPIO_PinAFConfig(GPIOB, GPIO_PinSource8, GPIO_AF_1); + GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, GPIO_AF_1); /* Configuration alternate function push-pull */ GPIO_InitStructure.GPIO_Pin = WS2811_PIN; @@ -53,7 +59,7 @@ void ws2811LedStripHardwareInit(void) GPIO_Init(WS2811_GPIO, &GPIO_InitStructure); - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM16, ENABLE); + RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE); /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ @@ -61,27 +67,27 @@ void ws2811LedStripHardwareInit(void) TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(TIM16, &TIM_TimeBaseStructure); + TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure); - /* PWM1 Mode configuration: Channel1 */ + /* PWM1 Mode configuration */ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_Pulse = 0; TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High; - TIM_OC1Init(TIM16, &TIM_OCInitStructure); - TIM_OC1PreloadConfig(TIM16, TIM_OCPreload_Enable); + TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure); + TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - TIM_CtrlPWMOutputs(TIM16, ENABLE); + TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); /* configure DMA */ /* DMA clock enable */ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); /* DMA1 Channel Config */ - DMA_DeInit(DMA1_Channel3); + DMA_DeInit(WS2811_DMA_CHANNEL); - DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM16->CCR1; + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE; @@ -93,16 +99,15 @@ void ws2811LedStripHardwareInit(void) DMA_InitStructure.DMA_Priority = DMA_Priority_High; DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; - DMA_Init(DMA1_Channel3, &DMA_InitStructure); + DMA_Init(WS2811_DMA_CHANNEL, &DMA_InitStructure); - /* TIM16 CC1 DMA Request enable */ - TIM_DMACmd(TIM16, TIM_DMA_CC1, ENABLE); + TIM_DMACmd(WS2811_TIMER, TIM_DMA_CC1, ENABLE); - DMA_ITConfig(DMA1_Channel3, DMA_IT_TC, ENABLE); + DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE); NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel3_IRQn; + NVIC_InitStructure.NVIC_IRQChannel = WS2811_IRQ; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA); NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; @@ -116,17 +121,28 @@ void DMA1_Channel3_IRQHandler(void) { if (DMA_GetFlagStatus(DMA1_FLAG_TC3)) { ws2811LedDataTransferInProgress = 0; - DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel 6 - DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel 6 transfer complete flag + DMA_Cmd(DMA1_Channel3, DISABLE); // disable DMA channel + DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel transfer complete flag } } +#if 0 +void DMA1_Channel7_IRQHandler(void) +{ + if (DMA_GetFlagStatus(DMA1_FLAG_TC7)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(DMA1_Channel7, DISABLE); // disable DMA channel + DMA_ClearFlag(DMA1_FLAG_TC7); // clear DMA1 Channel transfer complete flag + } +} +#endif + void ws2811LedStripDMAEnable(void) { - DMA_SetCurrDataCounter(DMA1_Channel3, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred - TIM_SetCounter(TIM16, 0); - TIM_Cmd(TIM16, ENABLE); - DMA_Cmd(DMA1_Channel3, ENABLE); + DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred + TIM_SetCounter(WS2811_TIMER, 0); + TIM_Cmd(WS2811_TIMER, ENABLE); + DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE); } diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 85bbe09dbf..67a01b2b47 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -334,8 +334,15 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #ifdef LED_STRIP_TIMER // skip LED Strip output - if (init->useLEDStrip && timerHardwarePtr->tim == LED_STRIP_TIMER) - continue; + if (init->useLEDStrip) { + if (timerHardwarePtr->tim == LED_STRIP_TIMER) + continue; +#if defined(WS2811_GPIO) && defined(WS2811_PIN) + if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->pin == WS2811_PIN) + continue; +#endif + } + #endif #ifdef STM32F10X diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index d32119d926..354ce06dd3 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -326,6 +326,7 @@ void DMA1_Channel4_IRQHandler(void) handleUsartTxDma(s); } +#ifdef USE_USART2_TX_DMA // USART2 Tx DMA Handler void DMA1_Channel7_IRQHandler(void) { @@ -334,6 +335,7 @@ void DMA1_Channel7_IRQHandler(void) DMA_Cmd(DMA1_Channel7, DISABLE); handleUsartTxDma(s); } +#endif // USART3 Tx DMA Handler void DMA1_Channel2_IRQHandler(void) diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 62e691a584..26cf2f709c 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -92,6 +92,36 @@ #define GPS #define DISPLAY +#define LED_STRIP +#if 1 +// LED strip configuration using PWM motor output pin 5. +#define LED_STRIP_TIMER TIM16 + +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_PIN Pin_6 // TIM16_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource6 +#define WS2811_TIMER TIM16 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 +#define WS2811_DMA_CHANNEL DMA1_Channel3 +#define WS2811_IRQ DMA1_Channel3_IRQn +#endif + +#if 0 +// Alternate LED strip pin - FIXME for some reason the DMA IRQ Transfer Complete is never called. +#define LED_STRIP_TIMER TIM17 + +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_PIN Pin_7 // TIM17_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource7 +#define WS2811_TIMER TIM17 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17 +#define WS2811_DMA_CHANNEL DMA1_Channel7 +#define WS2811_IRQ DMA1_Channel7_IRQn +#endif + + #define SPEKTRUM_BIND // USART2, PA3 #define BIND_PORT GPIOA From a43ae266f5928787405249fd04df52942bdce9fc Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Sun, 11 Jan 2015 14:35:53 +1300 Subject: [PATCH 29/41] Transmit blackbox header slower on faster looptimes to avoid errors --- src/main/blackbox/blackbox.c | 195 ++++++++++++++++++++++------------- 1 file changed, 121 insertions(+), 74 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 43f9fba6fd..574b33d4dc 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -248,13 +248,23 @@ extern uint8_t motorCount; //From mw.c: extern uint32_t currentTime; -static const int SERIAL_CHUNK_SIZE = 16; +// How many bytes should we transmit per loop iteration? +static uint8_t serialChunkSize = 16; static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED; -static uint32_t startTime; -static unsigned int headerXmitIndex; -static int fieldXmitIndex; +static struct { + uint32_t headerIndex; + + /* Since these fields are used during different blackbox states (never simultaneously) we can + * overlap them to save on RAM + */ + union { + int fieldIndex; + int serialBudget; + uint32_t startTime; + } u; +} xmitState; static uint32_t blackboxIteration; static uint32_t blackboxPFrameIndex, blackboxIFrameIndex; @@ -633,17 +643,17 @@ static void blackboxSetState(BlackboxState newState) //Perform initial setup required for the new state switch (newState) { case BLACKBOX_STATE_SEND_HEADER: - startTime = millis(); - headerXmitIndex = 0; + xmitState.headerIndex = 0; + xmitState.u.startTime = millis(); break; case BLACKBOX_STATE_SEND_FIELDINFO: case BLACKBOX_STATE_SEND_GPS_G_HEADERS: case BLACKBOX_STATE_SEND_GPS_H_HEADERS: - headerXmitIndex = 0; - fieldXmitIndex = -1; + xmitState.headerIndex = 0; + xmitState.u.fieldIndex = -1; break; case BLACKBOX_STATE_SEND_SYSINFO: - headerXmitIndex = 0; + xmitState.headerIndex = 0; break; case BLACKBOX_STATE_RUNNING: blackboxIteration = 0; @@ -856,6 +866,15 @@ static void configureBlackboxPort(void) previousBaudRate = blackboxPort->baudRate; } } + + /* + * We want to write at about 7200 bytes per second to give the OpenLog a good chance to save to disk. If + * about looptime microseconds elapse between our writes, this is the budget of how many bytes we should + * transmit with each write. + * + * 9 / 1250 = 7200 / 1000000 + */ + serialChunkSize = max((masterConfig.looptime * 9) / 1250, 4); } static void releaseBlackboxPort(void) @@ -983,7 +1002,7 @@ static void loadBlackboxState(void) * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition. * - * Set headerXmitIndex to 0 and fieldXmitIndex to -1 before calling for the first time. + * Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time. * * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the * fieldDefinition and secondCondition arrays. @@ -1003,23 +1022,23 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit * the whole header. */ - if (fieldXmitIndex == -1) { - if (headerXmitIndex >= headerCount) + if (xmitState.u.fieldIndex == -1) { + if (xmitState.headerIndex >= headerCount) return false; //Someone probably called us again after we had already completed transmission charsWritten = blackboxPrint("H Field "); - charsWritten += blackboxPrint(headerNames[headerXmitIndex]); + charsWritten += blackboxPrint(headerNames[xmitState.headerIndex]); charsWritten += blackboxPrint(":"); - fieldXmitIndex++; + xmitState.u.fieldIndex++; needComma = false; } else charsWritten = 0; - for (; fieldXmitIndex < fieldCount && charsWritten < SERIAL_CHUNK_SIZE; fieldXmitIndex++) { - def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * fieldXmitIndex); + for (; xmitState.u.fieldIndex < fieldCount && charsWritten < serialChunkSize; xmitState.u.fieldIndex++) { + def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex); - if (!conditions || testBlackboxCondition(conditions[conditionsStride * fieldXmitIndex])) { + if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) { if (needComma) { blackboxWrite(','); charsWritten++; @@ -1027,16 +1046,16 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he needComma = true; // The first header is a field name - if (headerXmitIndex == 0) { + if (xmitState.headerIndex == 0) { charsWritten += blackboxPrint(def->name); } else { //The other headers are integers - if (def->arr[headerXmitIndex - 1] >= 10) { - blackboxWrite(def->arr[headerXmitIndex - 1] / 10 + '0'); - blackboxWrite(def->arr[headerXmitIndex - 1] % 10 + '0'); + if (def->arr[xmitState.headerIndex - 1] >= 10) { + blackboxWrite(def->arr[xmitState.headerIndex - 1] / 10 + '0'); + blackboxWrite(def->arr[xmitState.headerIndex - 1] % 10 + '0'); charsWritten += 2; } else { - blackboxWrite(def->arr[headerXmitIndex - 1] + '0'); + blackboxWrite(def->arr[xmitState.headerIndex - 1] + '0'); charsWritten++; } } @@ -1044,85 +1063,115 @@ static bool sendFieldDefinition(const char * const *headerNames, unsigned int he } // Did we complete this line? - if (fieldXmitIndex == fieldCount) { + if (xmitState.u.fieldIndex == fieldCount) { blackboxWrite('\n'); - headerXmitIndex++; - fieldXmitIndex = -1; + xmitState.headerIndex++; + xmitState.u.fieldIndex = -1; } - return headerXmitIndex < headerCount; + return xmitState.headerIndex < headerCount; } /** - * Transmit a portion of the system information headers. Begin with a xmitIndex of 0. Returns the next xmitIndex to - * call with, or -1 if transmission is complete. + * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns + * true iff transmission is complete, otherwise call again later to continue transmission. */ -static int blackboxWriteSysinfo(int xmitIndex) +static bool blackboxWriteSysinfo() { union floatConvert_t { float f; uint32_t u; } floatConvert; - switch (xmitIndex) { + if (xmitState.headerIndex == 0) { + xmitState.u.serialBudget = 0; + xmitState.headerIndex = 1; + } + + // How many bytes can we afford to transmit this loop? + xmitState.u.serialBudget = min(xmitState.u.serialBudget + serialChunkSize, 64); + + // Most headers will consume at least 20 bytes so wait until we've built up that much link budget + if (xmitState.u.serialBudget < 20) { + return false; + } + + switch (xmitState.headerIndex) { case 0: - blackboxPrintf("H Firmware type:Cleanflight\n"); + //Shouldn't ever get here break; case 1: - // Pause to allow more time for previous to transmit (it exceeds our chunk size) + blackboxPrintf("H Firmware type:Cleanflight\n"); + + xmitState.u.serialBudget -= strlen("H Firmware type:Cleanflight\n"); break; case 2: blackboxPrintf("H Firmware revision:%s\n", shortGitRevision); + + /* Don't need to be super exact about the budget so don't mind the fact that we're including the length of + * the placeholder "%s" + */ + xmitState.u.serialBudget -= strlen("H Firmware revision:%s\n") + strlen(shortGitRevision); break; case 3: - // Pause to allow more time for previous to transmit + blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); + + xmitState.u.serialBudget -= strlen("H Firmware date:%s %s\n") + strlen(buildDate) + strlen(buildTime); break; case 4: - blackboxPrintf("H Firmware date:%s %s\n", buildDate, buildTime); + blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + + xmitState.u.serialBudget -= strlen("H P interval:%d/%d\n"); + break; case 5: - // Pause to allow more time for previous to transmit + blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + + xmitState.u.serialBudget -= strlen("H rcRate:%d\n"); break; case 6: - blackboxPrintf("H P interval:%d/%d\n", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); + blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); + + xmitState.u.serialBudget -= strlen("H minthrottle:%d\n"); break; case 7: - blackboxPrintf("H rcRate:%d\n", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8); + blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); + + xmitState.u.serialBudget -= strlen("H maxthrottle:%d\n"); break; case 8: - blackboxPrintf("H minthrottle:%d\n", masterConfig.escAndServoConfig.minthrottle); - break; - case 9: - blackboxPrintf("H maxthrottle:%d\n", masterConfig.escAndServoConfig.maxthrottle); - break; - case 10: floatConvert.f = gyro.scale; blackboxPrintf("H gyro.scale:0x%x\n", floatConvert.u); + + xmitState.u.serialBudget -= strlen("H gyro.scale:0x%x\n") + 6; + break; + case 9: + blackboxPrintf("H acc_1G:%u\n", acc_1G); + + xmitState.u.serialBudget -= strlen("H acc_1G:%u\n"); + break; + case 10: + blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale); + + xmitState.u.serialBudget -= strlen("H vbatscale:%u\n"); break; case 11: - blackboxPrintf("H acc_1G:%u\n", acc_1G); - break; - case 12: - blackboxPrintf("H vbatscale:%u\n", masterConfig.batteryConfig.vbatscale); - break; - case 13: blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig.batteryConfig.vbatmincellvoltage, masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage); + + xmitState.u.serialBudget -= strlen("H vbatcellvoltage:%u,%u,%u\n"); break; - case 14: - //Pause - break; - case 15: + case 12: blackboxPrintf("H vbatref:%u\n", vbatReference); - break; - case 16: - // One more pause for good luck + + xmitState.u.serialBudget -= strlen("H vbatref:%u\n"); break; default: - return -1; + return true; } - return xmitIndex + 1; + xmitState.headerIndex++; + return false; } // Beep the buzzer and write the current time to the log as a synchronization point @@ -1147,26 +1196,26 @@ static void blackboxPlaySyncBeep() void handleBlackbox(void) { - int i, result; + int i; switch (blackboxState) { case BLACKBOX_STATE_SEND_HEADER: - //On entry of this state, headerXmitIndex is 0 and startTime is intialised + //On entry of this state, xmitState.headerIndex is 0 and startTime is intialised /* * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit * buffer. */ - if (millis() > startTime + 100) { - for (i = 0; i < SERIAL_CHUNK_SIZE && blackboxHeader[headerXmitIndex] != '\0'; i++, headerXmitIndex++) - blackboxWrite(blackboxHeader[headerXmitIndex]); + if (millis() > xmitState.u.startTime + 100) { + for (i = 0; i < serialChunkSize && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) + blackboxWrite(blackboxHeader[xmitState.headerIndex]); - if (blackboxHeader[headerXmitIndex] == '\0') + if (blackboxHeader[xmitState.headerIndex] == '\0') blackboxSetState(BLACKBOX_STATE_SEND_FIELDINFO); } break; case BLACKBOX_STATE_SEND_FIELDINFO: - //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 + //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1 if (!sendFieldDefinition(blackboxMainHeaderNames, ARRAY_LENGTH(blackboxMainHeaderNames), blackboxMainFields, blackboxMainFields + 1, ARRAY_LENGTH(blackboxMainFields), &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) { #ifdef GPS @@ -1179,28 +1228,26 @@ void handleBlackbox(void) break; #ifdef GPS case BLACKBOX_STATE_SEND_GPS_H_HEADERS: - //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 + //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1 if (!sendFieldDefinition(blackboxGPSHHeaderNames, ARRAY_LENGTH(blackboxGPSHHeaderNames), blackboxGpsHFields, blackboxGpsHFields + 1, - ARRAY_LENGTH(blackboxGpsHFields), NULL, 0)) { + ARRAY_LENGTH(blackboxGpsHFields), NULL, NULL)) { blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADERS); } break; case BLACKBOX_STATE_SEND_GPS_G_HEADERS: - //On entry of this state, headerXmitIndex is 0 and fieldXmitIndex is -1 + //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1 if (!sendFieldDefinition(blackboxGPSGHeaderNames, ARRAY_LENGTH(blackboxGPSGHeaderNames), blackboxGpsGFields, blackboxGpsGFields + 1, - ARRAY_LENGTH(blackboxGpsGFields), NULL, 0)) { + ARRAY_LENGTH(blackboxGpsGFields), NULL, NULL)) { blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO); } break; #endif case BLACKBOX_STATE_SEND_SYSINFO: - //On entry of this state, headerXmitIndex is 0 - result = blackboxWriteSysinfo(headerXmitIndex); + //On entry of this state, xmitState.headerIndex is 0 - if (result == -1) + //Keep writing chunks of the system info headers until it returns true to signal completion + if (blackboxWriteSysinfo()) blackboxSetState(BLACKBOX_STATE_PRERUN); - else - headerXmitIndex = result; break; case BLACKBOX_STATE_PRERUN: blackboxPlaySyncBeep(); From efbffee51afd21cb5fb2ab2dd2e7be3afec3985d Mon Sep 17 00:00:00 2001 From: Akfreak Date: Sat, 10 Jan 2015 22:03:10 -0800 Subject: [PATCH 30/41] Update LedStrip.md Data added or the Spaky board, "| Sparky, pin PWM5, signal PA6 --- docs/LedStrip.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/LedStrip.md b/docs/LedStrip.md index 0b6f28fd98..86c2076dc1 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -56,7 +56,7 @@ from another BEC. Just ensure that the GROUND is the same for all BEC outputs a | Naze/Olimexino | RC5 | Data In | PA6 | | CC3D | RCO5 | Data In | PB4 | | ChebuzzF3/F3Discovery | PB8 | Data In | PB8 | - +| Sparky | PWM5 | Data In | PA6 | Since RC5 is also used for SoftSerial on the Naze/Olimexino it means that you cannot use SoftSerial and led strips at the same time. Additionally, since RC5 is also used for Parallel PWM RC input on both the Naze, Chebuzz and STM32F3Discovery targets, led strips From 68be127f9c667352c163980d9718593bf6d9c3f8 Mon Sep 17 00:00:00 2001 From: eziosoft Date: Sun, 11 Jan 2015 21:32:24 +0100 Subject: [PATCH 31/41] Update Modes.md IDs corrected according to the source code --- docs/Modes.md | 36 ++++++++++++++++++------------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/docs/Modes.md b/docs/Modes.md index 047649c963..df9d318e92 100644 --- a/docs/Modes.md +++ b/docs/Modes.md @@ -9,24 +9,24 @@ auxillary receiver channels and other events such as failsafe detection. | 1 | ANGLE | Legacy auto-level flight mode | | 2 | HORIZON | Auto-level flight mode | | 3 | BARO | Altitude hold mode (Requires barometer sensor) | -| 4 | MAG | Heading lock | -| 5 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs | -| 6 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode | -| 7 | CAMSTAB | Camera Stabilisation | -| 8 | CAMTRIG | | -| 9 | GPSHOME | Autonomous flight to HOME position | -| 10 | GPSHOLD | Maintain the same longitude/lattitude | -| 11 | PASSTHRU | | -| 12 | BEEPERON | Enable beeping - useful for locating a crashed aircraft | -| 13 | LEDMAX | | -| 14 | LEDLOW | | -| 15 | LLIGHTS | | -| 16 | CALIB | | -| 17 | GOV | | -| 18 | OSD | Enable/Disable On-Screen-Display (OSD) | -| 19 | TELEMETRY | Enable telemetry via switch | -| 20 | AUTOTUNE | Autotune Pitch/Roll PIDs | -| 21 | SONAR | Altitude hold mode (sonar sensor only) | +| 5 | MAG | Heading lock | +| 6 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs | +| 7 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode | +| 8 | CAMSTAB | Camera Stabilisation | +| 9 | CAMTRIG | | +| 10 | GPSHOME | Autonomous flight to HOME position | +| 11 | GPSHOLD | Maintain the same longitude/lattitude | +| 12 | PASSTHRU | | +| 13 | BEEPERON | Enable beeping - useful for locating a crashed aircraft | +| 14 | LEDMAX | | +| 15 | LEDLOW | | +| 16 | LLIGHTS | | +| 17 | CALIB | | +| 18 | GOV | | +| 19 | OSD | Enable/Disable On-Screen-Display (OSD) | +| 20 | TELEMETRY | Enable telemetry via switch | +| 21 | AUTOTUNE | Autotune Pitch/Roll PIDs | +| 22 | SONAR | Altitude hold mode (sonar sensor only) | ## Mode details From 32888b673f36584183b1b5c0034ca9976f85550f Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Sun, 11 Jan 2015 20:39:45 +0000 Subject: [PATCH 32/41] Rename ID column to MSP ID in Modes documenation. --- docs/Modes.md | 48 ++++++++++++++++++++++++------------------------ 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/docs/Modes.md b/docs/Modes.md index df9d318e92..145997bfb4 100644 --- a/docs/Modes.md +++ b/docs/Modes.md @@ -3,30 +3,30 @@ Cleanflight has various modes that can be toggled on or off. Modes can be enabled/disabled by stick positions, auxillary receiver channels and other events such as failsafe detection. -| ID | Short Name | Function | -| --- | ---------- | -------------------------------------------------------------------- | -| 0 | ARM | Enables motors and flight stabilisation | -| 1 | ANGLE | Legacy auto-level flight mode | -| 2 | HORIZON | Auto-level flight mode | -| 3 | BARO | Altitude hold mode (Requires barometer sensor) | -| 5 | MAG | Heading lock | -| 6 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs | -| 7 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode | -| 8 | CAMSTAB | Camera Stabilisation | -| 9 | CAMTRIG | | -| 10 | GPSHOME | Autonomous flight to HOME position | -| 11 | GPSHOLD | Maintain the same longitude/lattitude | -| 12 | PASSTHRU | | -| 13 | BEEPERON | Enable beeping - useful for locating a crashed aircraft | -| 14 | LEDMAX | | -| 15 | LEDLOW | | -| 16 | LLIGHTS | | -| 17 | CALIB | | -| 18 | GOV | | -| 19 | OSD | Enable/Disable On-Screen-Display (OSD) | -| 20 | TELEMETRY | Enable telemetry via switch | -| 21 | AUTOTUNE | Autotune Pitch/Roll PIDs | -| 22 | SONAR | Altitude hold mode (sonar sensor only) | +| MSP ID | Short Name | Function | +| ------- | ---------- | -------------------------------------------------------------------- | +| 0 | ARM | Enables motors and flight stabilisation | +| 1 | ANGLE | Legacy auto-level flight mode | +| 2 | HORIZON | Auto-level flight mode | +| 3 | BARO | Altitude hold mode (Requires barometer sensor) | +| 5 | MAG | Heading lock | +| 6 | HEADFREE | Head Free - When enabled yaw has no effect on pitch/roll inputs | +| 7 | HEADADJ | Heading Adjust - Sets a new yaw origin for HEADFREE mode | +| 8 | CAMSTAB | Camera Stabilisation | +| 9 | CAMTRIG | | +| 10 | GPSHOME | Autonomous flight to HOME position | +| 11 | GPSHOLD | Maintain the same longitude/lattitude | +| 12 | PASSTHRU | | +| 13 | BEEPERON | Enable beeping - useful for locating a crashed aircraft | +| 14 | LEDMAX | | +| 15 | LEDLOW | | +| 16 | LLIGHTS | | +| 17 | CALIB | | +| 18 | GOV | | +| 19 | OSD | Enable/Disable On-Screen-Display (OSD) | +| 20 | TELEMETRY | Enable telemetry via switch | +| 21 | AUTOTUNE | Autotune Pitch/Roll PIDs | +| 22 | SONAR | Altitude hold mode (sonar sensor only) | ## Mode details From d7ee09c666e6fc51fd820eebb4165a936908e80f Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 12 Jan 2015 10:51:06 +0000 Subject: [PATCH 33/41] Update .gitignore to exclude generated files. --- .gitignore | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.gitignore b/.gitignore index cf98d4de42..34dd269dd7 100644 --- a/.gitignore +++ b/.gitignore @@ -11,3 +11,8 @@ obj/ patches/ startup_stm32f10x_md_gcc.s + +# script-generated files +docs/Manual.pdf +README.pdf + From a89ed666cd51aa3b5495b02d61e88fffa5db1961 Mon Sep 17 00:00:00 2001 From: Pim van Pelt Date: Mon, 12 Jan 2015 22:04:45 +0100 Subject: [PATCH 34/41] Building on Ubuntu --- docs/development/Building in Ubuntu.md | 66 ++++++++++++++++++++++++++ 1 file changed, 66 insertions(+) create mode 100755 docs/development/Building in Ubuntu.md diff --git a/docs/development/Building in Ubuntu.md b/docs/development/Building in Ubuntu.md new file mode 100755 index 0000000000..b80dd8d2e8 --- /dev/null +++ b/docs/development/Building in Ubuntu.md @@ -0,0 +1,66 @@ +# 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 Cleanflight. We suggest that you take an +alternative PPA from Terry Guo, found here: + +https://launchpad.net/~terry.guo/+archive/ubuntu/gcc-arm-embedded + +## Setup GNU ARM Toolchain + +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 +``` + +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 +``` + +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 +``` + +## Building on Ubuntu + +After the ARM toolchain from Terry is installed, you should be able to build from source. +``` +cd src +git clone git@github.com:cleanflight/cleanflight.git +cd cleanflight +make TARGET=NAZE +``` + +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/cleanflight_NAZE.elf + text data bss dec hex filename + 97164 320 11080 108564 1a814 ./obj/main/cleanflight_NAZE.elf +arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/cleanflight_NAZE.elf obj/cleanflight_NAZE.hex +$ ls -la obj/cleanflight_NAZE.hex +-rw-rw-r-- 1 pim pim 274258 Jan 12 21:45 obj/cleanflight_NAZE.hex +``` + +You can use the Cleanflight-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file. + +## Updating and rebuilding + +Navigate to the local cleanflight repository and use the following steps to pull the latest changes and rebuild your version of cleanflight: + +``` +cd src/cleanflight +git reset --hard +git pull +make clean TARGET=NAZE +make +``` + +Credit goes to K.C. Budd for doing the long legwork that yielded this very short document. From 90a36aea77f978afde76b44e087e60e03bbe2b11 Mon Sep 17 00:00:00 2001 From: Pim van Pelt Date: Mon, 12 Jan 2015 22:28:31 +0100 Subject: [PATCH 35/41] Add notes on success/fail TARGETs. Add Penguin to the list. --- docs/development/Building in Ubuntu.md | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/docs/development/Building in Ubuntu.md b/docs/development/Building in Ubuntu.md index b80dd8d2e8..4dbd3586da 100755 --- a/docs/development/Building in Ubuntu.md +++ b/docs/development/Building in Ubuntu.md @@ -18,14 +18,19 @@ sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded sudo apt-get update ``` +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 +``` + 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 ``` -For Ubuntu 14.10 (current release, called Utopic Unicorn), you should pin: +For Ubuntu 12.04 (previous LTS, called Precise Penguin), you should pin: ``` -sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0utopic12 +sudo apt-get install gcc-arm-none-eabi=4.9.3.2014q4-0precise12 ``` ## Building on Ubuntu @@ -63,4 +68,7 @@ make clean TARGET=NAZE make ``` +## Notes +There are compiler issues with at least the Sparky target. + Credit goes to K.C. Budd for doing the long legwork that yielded this very short document. From c12e1fe0872396845ec9fe3ddd59e91592e867c1 Mon Sep 17 00:00:00 2001 From: Pim van Pelt Date: Mon, 12 Jan 2015 23:00:09 +0100 Subject: [PATCH 36/41] Various tests/build for 4.8 on SPARKY, tested by AKfreak, add attributions --- docs/development/Building in Ubuntu.md | 25 ++++++++++++++++++++----- 1 file changed, 20 insertions(+), 5 deletions(-) diff --git a/docs/development/Building in Ubuntu.md b/docs/development/Building in Ubuntu.md index 4dbd3586da..d52e87c7d0 100755 --- a/docs/development/Building in Ubuntu.md +++ b/docs/development/Building in Ubuntu.md @@ -3,9 +3,13 @@ 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 Cleanflight. We suggest that you take an alternative PPA from Terry Guo, found here: - https://launchpad.net/~terry.guo/+archive/ubuntu/gcc-arm-embedded +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. + ## Setup GNU ARM Toolchain Note specifically the last paragraph of Terry's PPA documentation -- Ubuntu carries its own package for @@ -56,6 +60,20 @@ $ ls -la obj/cleanflight_NAZE.hex You can use the Cleanflight-Configurator to flash the ```obj/cleanflight_NAZE.hex``` file. +## Bricked/Bad build? + +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/ + +and use `dpkg` to install: +``` +sudo dpkg -i gcc-arm-none-eabi_4-8-2014q2-0saucy9_amd64.deb +``` + +Make sure to remove `obj/` and `make clean`, before building again. + ## Updating and rebuilding Navigate to the local cleanflight repository and use the following steps to pull the latest changes and rebuild your version of cleanflight: @@ -68,7 +86,4 @@ make clean TARGET=NAZE make ``` -## Notes -There are compiler issues with at least the Sparky target. - -Credit goes to K.C. Budd for doing the long legwork that yielded this very short document. +Credit goes to K.C. Budd, AKfreak for testing, and pulsar for doing the long legwork that yielded this very short document. From b6ac9204d388e3025db02da4534d286aa08ff3f0 Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 12 Jan 2015 22:01:45 +0000 Subject: [PATCH 37/41] STM32F3 - Fix LED Strip hardware initialisation. --- .../drivers/light_ws2811strip_stm32f10x.c | 6 +++++ .../drivers/light_ws2811strip_stm32f30x.c | 26 ++++++++++++++++--- src/main/drivers/pwm_mapping.c | 4 +-- src/main/drivers/serial_uart_stm32f30x.c | 3 +++ src/main/target/CHEBUZZF3/target.h | 16 ++++++++++++ src/main/target/SPARKY/target.h | 11 +++++--- 6 files changed, 58 insertions(+), 8 deletions(-) diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index 1462114324..2b0de69bdb 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -35,13 +35,16 @@ void ws2811LedStripHardwareInit(void) #ifdef CC3D RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + GPIO_StructInit(&GPIO_InitStructure); GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; GPIO_Init(GPIOB, &GPIO_InitStructure); #else RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); + /* GPIOA Configuration: TIM3 Channel 1 as alternate function push-pull */ + GPIO_StructInit(&GPIO_InitStructure); GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; @@ -52,6 +55,7 @@ void ws2811LedStripHardwareInit(void) /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_ClockDivision = 0; @@ -59,6 +63,7 @@ void ws2811LedStripHardwareInit(void) TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure); /* PWM1 Mode configuration: Channel1 */ + TIM_OCStructInit(&TIM_OCInitStructure); TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_Pulse = 0; @@ -75,6 +80,7 @@ void ws2811LedStripHardwareInit(void) /* DMA1 Channel6 Config */ DMA_DeInit(DMA1_Channel6); + DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index 8908dda081..7404f8e539 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -27,9 +27,11 @@ #include "drivers/light_ws2811strip.h" #ifndef WS2811_GPIO +#define USE_LED_STRIP_ON_DMA1_CHANNEL3 #define WS2811_GPIO GPIOB #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB -#define WS2811_PIN Pin_8 // TIM16_CH1 +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 #define WS2811_PIN_SOURCE GPIO_PinSource8 #define WS2811_TIMER TIM16 #define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 @@ -48,9 +50,10 @@ void ws2811LedStripHardwareInit(void) RCC_AHBPeriphClockCmd(WS2811_GPIO_AHB_PERIPHERAL, ENABLE); - GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, GPIO_AF_1); + GPIO_PinAFConfig(WS2811_GPIO, WS2811_PIN_SOURCE, WS2811_GPIO_AF); /* Configuration alternate function push-pull */ + GPIO_StructInit(&GPIO_InitStructure); GPIO_InitStructure.GPIO_Pin = WS2811_PIN; GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; @@ -60,9 +63,11 @@ void ws2811LedStripHardwareInit(void) RCC_APB2PeriphClockCmd(WS2811_TIMER_APB2_PERIPHERAL, ENABLE); + /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; TIM_TimeBaseStructure.TIM_ClockDivision = 0; @@ -70,6 +75,7 @@ void ws2811LedStripHardwareInit(void) TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure); /* PWM1 Mode configuration */ + TIM_OCStructInit(&TIM_OCInitStructure); TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_Pulse = 0; @@ -87,6 +93,7 @@ void ws2811LedStripHardwareInit(void) /* DMA1 Channel Config */ DMA_DeInit(WS2811_DMA_CHANNEL); + DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1; DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer; DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; @@ -117,6 +124,7 @@ void ws2811LedStripHardwareInit(void) ws2811UpdateStrip(); } +#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL3 void DMA1_Channel3_IRQHandler(void) { if (DMA_GetFlagStatus(DMA1_FLAG_TC3)) { @@ -125,8 +133,20 @@ void DMA1_Channel3_IRQHandler(void) DMA_ClearFlag(DMA1_FLAG_TC3); // clear DMA1 Channel transfer complete flag } } +#endif -#if 0 +#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL2 +void DMA1_Channel2_IRQHandler(void) +{ + if (DMA_GetFlagStatus(DMA1_FLAG_TC2)) { + ws2811LedDataTransferInProgress = 0; + DMA_Cmd(DMA1_Channel2, DISABLE); // disable DMA channel + DMA_ClearFlag(DMA1_FLAG_TC2); // clear DMA1 Channel transfer complete flag + } +} +#endif + +#ifdef USE_LED_STRIP_ON_DMA1_CHANNEL7 void DMA1_Channel7_IRQHandler(void) { if (DMA_GetFlagStatus(DMA1_FLAG_TC7)) { diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 67a01b2b47..9130d14841 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -337,8 +337,8 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (init->useLEDStrip) { if (timerHardwarePtr->tim == LED_STRIP_TIMER) continue; -#if defined(WS2811_GPIO) && defined(WS2811_PIN) - if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->pin == WS2811_PIN) +#if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE) + if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->gpioPinSource == WS2811_PIN_SOURCE) continue; #endif } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 354ce06dd3..3d8ee674cb 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -338,6 +338,7 @@ void DMA1_Channel7_IRQHandler(void) #endif // USART3 Tx DMA Handler +#ifdef USE_USART2_TX_DMA void DMA1_Channel2_IRQHandler(void) { uartPort_t *s = &uartPort3; @@ -345,6 +346,8 @@ void DMA1_Channel2_IRQHandler(void) DMA_Cmd(DMA1_Channel2, DISABLE); handleUsartTxDma(s); } +#endif + void usartIrqHandler(uartPort_t *s) { diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index f4bc202a54..de560a7fc5 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -69,7 +69,23 @@ #define GPS #define LED_STRIP +#if 1 #define LED_STRIP_TIMER TIM16 +#else +// alternative LED strip configuration, tested working. +#define LED_STRIP_TIMER TIM1 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL2 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_6 +#define WS2811_PIN GPIO_Pin_8 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM1 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define WS2811_DMA_CHANNEL DMA1_Channel2 +#define WS2811_IRQ DMA1_Channel2_IRQn +#endif #define BLACKBOX #define TELEMETRY diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 26cf2f709c..d020296653 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -97,9 +97,11 @@ // LED strip configuration using PWM motor output pin 5. #define LED_STRIP_TIMER TIM16 +#define USE_LED_STRIP_ON_DMA1_CHANNEL3 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_PIN Pin_6 // TIM16_CH1 +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_6 // TIM16_CH1 #define WS2811_PIN_SOURCE GPIO_PinSource6 #define WS2811_TIMER TIM16 #define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 @@ -108,12 +110,15 @@ #endif #if 0 -// Alternate LED strip pin - FIXME for some reason the DMA IRQ Transfer Complete is never called. +// Alternate LED strip pin +// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1 #define LED_STRIP_TIMER TIM17 +#define USE_LED_STRIP_ON_DMA1_CHANNEL7 #define WS2811_GPIO GPIOA #define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define WS2811_PIN Pin_7 // TIM17_CH1 +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1 #define WS2811_PIN_SOURCE GPIO_PinSource7 #define WS2811_TIMER TIM17 #define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17 From ec09f0d7fba6b6b38bfbf15c930257799c3b6e0c Mon Sep 17 00:00:00 2001 From: Dominic Clifton Date: Mon, 12 Jan 2015 23:27:48 +0000 Subject: [PATCH 38/41] Adding a Futuba SBus RX to the list of known working SBus receivers. --- docs/Rx.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/Rx.md b/docs/Rx.md index 1d99c394fb..98b2cee6bf 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -61,6 +61,10 @@ http://www.frsky-rc.com/product/pro.php?pro_id=135 FrSky X8R 8/16ch Telemetry Receiver http://www.frsky-rc.com/product/pro.php?pro_id=105 +Futaba R2008SB 2.4GHz S-FHSS +http://www.futaba-rc.com/systems/futk8100-8j/ + + #### OpenTX S.BUS configuration If using OpenTX set the transmitter module to D16 mode and select CH1-16 on the transmitter before binding to allow reception From b8fa926b3d3d77aedf94c27f20fc2d645b7d6b5a Mon Sep 17 00:00:00 2001 From: curtisbyers Date: Mon, 12 Jan 2015 17:50:55 -0600 Subject: [PATCH 39/41] Fix broken link in Buzzer.md. --- docs/Buzzer.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Buzzer.md b/docs/Buzzer.md index 73b759ff01..376235d579 100644 --- a/docs/Buzzer.md +++ b/docs/Buzzer.md @@ -35,4 +35,4 @@ Buzzer support on the CC3D requires that a buzzer circuit be created to which th PA15 is unused and not connected according to the CC3D Revision A schematic. Connecting to PA15 requires careful soldering. -See the [CC3D - buzzer circuir.pdf](Wiring/CC3D - buzzer circuir.pdf) for details. +See the [CC3D - buzzer circuit.pdf](Wiring/CC3D - buzzer circuit.pdf) for details. From f7a9a628b6ebb370641e451846733cb7f6c89562 Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 14 Jan 2015 11:46:44 +1300 Subject: [PATCH 40/41] Add logging for GPS ground course (heading) --- src/main/blackbox/blackbox.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 574b33d4dc..2365c39138 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -215,7 +215,8 @@ static const blackboxGPSFieldDefinition_t blackboxGpsGFields[] = { {"GPS_coord[0]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)}, {"GPS_coord[1]", SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB)}, {"GPS_altitude", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, - {"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)} + {"GPS_speed", UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)}, + {"GPS_ground_course",UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)} }; // GPS home frame @@ -942,6 +943,7 @@ static void writeGPSFrame() writeSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]); writeUnsignedVB(GPS_altitude); writeUnsignedVB(GPS_speed); + writeUnsignedVB(GPS_ground_course); gpsHistory.GPS_numSat = GPS_numSat; gpsHistory.GPS_coord[0] = GPS_coord[0]; From b893e457f138880eb48a026512caaad2515fb41a Mon Sep 17 00:00:00 2001 From: Nicholas Sherlock Date: Wed, 14 Jan 2015 15:42:38 +1300 Subject: [PATCH 41/41] Don't break the blackbox stream when PIDs change in-flight --- src/main/blackbox/blackbox.c | 39 ++++++++++++++++++-------- src/main/blackbox/blackbox_fielddefs.h | 13 ++++----- 2 files changed, 33 insertions(+), 19 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 2365c39138..028f54c903 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -267,6 +267,8 @@ static struct { } u; } xmitState; +static uint32_t blackboxConditionCache; + static uint32_t blackboxIteration; static uint32_t blackboxPFrameIndex, blackboxIFrameIndex; @@ -582,7 +584,7 @@ static void writeTag8_8SVB(int32_t *values, int valueCount) } } -static bool testBlackboxCondition(FlightLogFieldCondition condition) +static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) { switch (condition) { case FLIGHT_LOG_FIELD_CONDITION_ALWAYS: @@ -597,19 +599,10 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; + case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: return masterConfig.mixerMode == MIXER_TRI; - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0: - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1: - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2: - return currentProfile->pidProfile.P8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0] != 0; - - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0: - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1: - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2: - return currentProfile->pidProfile.I8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0] != 0; - case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2: @@ -639,6 +632,23 @@ static bool testBlackboxCondition(FlightLogFieldCondition condition) } } +static void blackboxBuildConditionCache() +{ + FlightLogFieldCondition cond; + + blackboxConditionCache = 0; + + for (cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) { + if (testBlackboxConditionUncached(cond)) + blackboxConditionCache |= 1 << cond; + } +} + +static bool testBlackboxCondition(FlightLogFieldCondition condition) +{ + return (blackboxConditionCache & (1 << condition)) != 0; +} + static void blackboxSetState(BlackboxState newState) { //Perform initial setup required for the new state @@ -908,6 +918,13 @@ void startBlackbox(void) //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it + /* + * We use conditional tests to decide whether or not certain fields should be logged. Since our headers + * must always agree with the logged data, the results of these tests must not change during logging. So + * cache those now. + */ + blackboxBuildConditionCache(); + blackboxSetState(BLACKBOX_STATE_SEND_HEADER); } } diff --git a/src/main/blackbox/blackbox_fielddefs.h b/src/main/blackbox/blackbox_fielddefs.h index 87db8ecbbb..1763561092 100644 --- a/src/main/blackbox/blackbox_fielddefs.h +++ b/src/main/blackbox/blackbox_fielddefs.h @@ -29,21 +29,18 @@ typedef enum FlightLogFieldCondition { FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8, FLIGHT_LOG_FIELD_CONDITION_TRICOPTER, - FLIGHT_LOG_FIELD_CONDITION_MAG = 20, + FLIGHT_LOG_FIELD_CONDITION_MAG, FLIGHT_LOG_FIELD_CONDITION_BARO, FLIGHT_LOG_FIELD_CONDITION_VBAT, - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_0 = 40, - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_1, - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_P_2, - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_0, - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_1, - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_I_2, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1, FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2, - FLIGHT_LOG_FIELD_CONDITION_NEVER = 255, + FLIGHT_LOG_FIELD_CONDITION_NEVER, + + FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS, + FLIGHT_LOG_FIELD_CONDITION_LAST = FLIGHT_LOG_FIELD_CONDITION_NEVER } FlightLogFieldCondition; typedef enum FlightLogFieldPredictor {