90
docs/LED pin PWM.md
Normal file
|
@ -0,0 +1,90 @@
|
|||
# LED pin PWM
|
||||
|
||||
Normally LED pin is used to drive WS2812 led strip. LED pin is held low, and every 10ms or 20ms a set of pulses is sent to change color of the 32 LEDs:
|
||||
|
||||

|
||||

|
||||
|
||||
As alternative function, it is possible to generate PWM signal with specified duty ratio on the LED pin.
|
||||
|
||||
Feature can be used to drive external devices. It is also used to simulate [OSD joystick](OSD%20Joystick.md) to control cameras.
|
||||
|
||||
PWM frequency is fixed to 24kHz with duty ratio between 0 and 100%:
|
||||
|
||||

|
||||
|
||||
There are four modes of operation:
|
||||
- low
|
||||
- high
|
||||
- shared_low
|
||||
- shared_high
|
||||
|
||||
Mode is configured using ```led_pin_pwm_mode``` setting: ```LOW```, ```HIGH```, ```SHARED_LOW```, ```SHARED_HIGH```
|
||||
|
||||
*Note that in any mode, there will be ~2 seconds LOW pulse on boot.*
|
||||
|
||||
## LOW
|
||||
LED Pin is initialized to output low level by default and can be used to generate PWM signal.
|
||||
|
||||
ws2812 strip can not be controlled.
|
||||
|
||||
## HIGH
|
||||
LED Pin is initialized to output high level by default and can be used to generate PWM signal.
|
||||
|
||||
ws2812 strip can not be controlled.
|
||||
|
||||
## SHARED_LOW (default)
|
||||
LED Pin is used to drive WS2812 strip. Pauses between pulses are low:
|
||||
|
||||

|
||||
|
||||
It is possible to generate PWM signal with duty ratio >0...100%.
|
||||
|
||||
While PWM signal is generated, ws2811 strip is not updated.
|
||||
|
||||
When PWM generation is disabled, LED pin is used to drive ws2812 strip.
|
||||
|
||||
Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM signal with duty ratio < ~10%.
|
||||
|
||||
## SHARED_HIGH
|
||||
LED Pin is used to drive WS2812 strip. Pauses between pulses are high. ws2812 pulses are prefixed with 50us low 'reset' pulse:
|
||||
|
||||

|
||||

|
||||
|
||||
It is possible to generate PWM signal with duty ratio 0...<100%.
|
||||
|
||||
While PWM signal is generated, ws2811 strip is not updated.
|
||||
|
||||
When PWM generation is disabled, LED pin is used to drive ws2812 strip. Total ws2812 pulses duration is ~1ms with ~9ms pauses. Thus connected device should ignore PWM signal with duty ratio > ~90%.
|
||||
|
||||
After sending ws2812 protocol pulses for 32 LEDS, we held line high for 9ms, then send 50us low 'reset' pulse. Datasheet for ws2812 protocol does not describe behavior for long high pulse, but in practice it works the same as 'reset' pulse. To be safe, we also send correct low 'reset' pulse before starting next LEDs update sequence.
|
||||
|
||||
This mode is used to simulate OSD joystick. It is Ok that effectively voltage level is held >90% while driving LEDs, because OSD joystick keypress voltages are below 90%.
|
||||
|
||||
See [OSD Joystick](OSD%20Joystick.md) for more information.
|
||||
|
||||
# Generating PWM signal with programming framework
|
||||
|
||||
See "LED Pin PWM" operation in [Programming Framework](Programming%20Framework.md)
|
||||
|
||||
|
||||
# Generating PWM signal from CLI
|
||||
|
||||
```ledpinpwm <value>``` - value = 0...100 - enable PWM generation with specified duty cycle
|
||||
|
||||
```ledpinpwm``` - disable PWM generation ( disable to allow ws2812 LEDs updates in shared modes )
|
||||
|
||||
|
||||
# Example of driving LED
|
||||
|
||||
It is possible to drive single color LED with brightness control. Current consumption should not be greater then 1-2ma, thus LED can be used for indication only.
|
||||
|
||||

|
||||
|
||||
# Example of driving powerfull white LED
|
||||
|
||||
To drive power LED with brightness control, Mosfet should be used:
|
||||
|
||||

|
||||
|
94
docs/OSD Joystick.md
Normal file
|
@ -0,0 +1,94 @@
|
|||
# OSD joystick
|
||||
|
||||
LED pin can be used to emulate 5key OSD joystick for OSD camera pin, while still driving ws2812 LEDs (shared functionality).
|
||||
|
||||
See [LED pin PWM](LED%20pin%20PWM.md) for more details.
|
||||
|
||||
Note that for cameras which support RuncamDevice protocol, there is alternative functionality using serial communication: [Runcam device](Runcam%20device.md)
|
||||
|
||||
Also special adapters exist to convert RuncamDevice protocol to OSD Joystick: [Runcam control adapter](https://www.runcam.com/download/runcam_control_adapter_manual.pdf)
|
||||
|
||||
# OSD Joystick schematics
|
||||
|
||||

|
||||
|
||||
Camera internal resistance seems to be 47kOhm or 9kOhm depending on camera model.
|
||||
|
||||
Each key effectively turns on voltage divider. Voltage is sensed by the camera and is compared to the list of keys voltages with some threshold.
|
||||
|
||||
Key voltage has to be held for at least 200ms.
|
||||
|
||||
To simulate 5key joystick, it is sufficient to generate correct voltage on camera OSD pin.
|
||||
|
||||
# Enabling OSD Joystick emulation
|
||||
|
||||
```set led_pin_pwm_mode=shared_high```
|
||||
|
||||
```set osd_joystick_enabled=on```
|
||||
|
||||
Also enable "Multi-color RGB LED Strip support" in Configuration tab.
|
||||
|
||||
# Connection diagram
|
||||
|
||||
We use LED pin PWM functionality with RC filter to generate voltage:
|
||||
|
||||

|
||||
|
||||
# Example PCB layout (SMD components)
|
||||
|
||||
RC Filter can be soldered on a small piece of PCB:
|
||||
|
||||

|
||||
|
||||
# Configuring keys voltages
|
||||
|
||||
If default voltages does not work with your camera model, then you have to measure voltages and find out corresponding PWM duty ratios.
|
||||
|
||||
1. Connect 5keys joystick to camera.
|
||||
2. Measure voltages on OSD pin while each key is pressed.
|
||||
3. Connect camera to FC throught RC filter as shown on schematix above.
|
||||
4. Enable OSD Joystick emulation (see "Enabling OSD Joystick emulation" above)
|
||||
4. Use cli command ```led_pin_pwm <value>```, value = 0...100 to find out PWM values for each voltage.
|
||||
5. Specify PWM values in configuration and save:
|
||||
|
||||
```set osd_joystick_down=0```
|
||||
|
||||
```set osd_joystick_up=48```
|
||||
|
||||
```set osd_joystick_left=63```
|
||||
|
||||
```set osd_joystick_right=28```
|
||||
|
||||
```set osd_joystick_enter=75```
|
||||
|
||||
```save```
|
||||
|
||||
# Entering OSD Joystick emulation mode
|
||||
|
||||
Emulation can be enabled in unarmed state only.
|
||||
|
||||
OSD Joystick emulation mode is enabled using the following stick combination:
|
||||
|
||||
```Throttle:CENTER Yaw:RIGHT```
|
||||
|
||||
|
||||
Than camera OSD can be navigated using right stick. See [Controls](Controls.md) for all stick combinations.
|
||||
|
||||
*Note that the same stick combination is used to enable 5keys joystick emulation with RuncamDevice protocol.*
|
||||
|
||||
Mode is exited using stick combination:
|
||||
|
||||
```Throttle:CENTER Yaw:LEFT```
|
||||
|
||||
# RC Box
|
||||
|
||||
There are 3 RC Boxes which can be used in armed and unarmed state:
|
||||
- Camera 1 - Enter
|
||||
- Camera 2 - Up
|
||||
- Camera 3 - Down
|
||||
|
||||
Other keys can be emulated using Programming framework ( see [LED pin PWM](LED%20pin%20PWM.md) for more details ).
|
||||
|
||||
# Behavior on boot
|
||||
|
||||
There is ~2 seconds LOW pulse during boot sequence, which corresponds to DOWN key. Fortunately, cameras seem to ignore any key events few seconds after statup.
|
|
@ -97,6 +97,7 @@ IPF can be edited using INAV Configurator user interface, or via CLI. To use COn
|
|||
| 49 | TIMER | A simple on - off timer. `true` for the duration of `Operand A` [ms]. Then `false` for the duration of `Operand B` [ms]. |
|
||||
| 50 | DELTA | This returns `true` when the value of `Operand A` has changed by the value of `Operand B` or greater within 100ms. |
|
||||
| 51 | APPROX_EQUAL | `true` if `Operand B` is within 1% of `Operand A`. |
|
||||
| 52 | LED_PIN_PWM | Value `Operand A` from [`0` : `100`] starts PWM generation on LED Pin. See [LED pin PWM](LED%20pin%20PWM.md). Any other value stops PWM generation (stop to allow ws2812 LEDs updates in shared modes)|
|
||||
|
||||
### Operands
|
||||
|
||||
|
|
32
docs/Runcam device.md
Normal file
|
@ -0,0 +1,32 @@
|
|||
# Runcam device
|
||||
|
||||
Cameras which support [Runcam device protocol](https://support.runcam.com/hc/en-us/articles/360014537794-RunCam-Device-Protocol), can be configured using sticks.
|
||||
|
||||
Note that for cameras which has OSD pin, there is alternative functionality: [OSD Joystick](OSD%20Joystick.md).
|
||||
|
||||
Camera's RX/TX should be connected to FC's UART, which has "Runcam device" option selected.
|
||||
|
||||
# Entering Joystick emulation mode
|
||||
|
||||
Emulation can be enabled in unarmed state only.
|
||||
|
||||
Joystick emulation mode is enabled using the following stick combination:
|
||||
|
||||
```RIGHT CENTER```
|
||||
|
||||
|
||||
Than camera OSD can be navigated using right stick. See [Controls](Controls.md) for all stick combinations.
|
||||
|
||||
*Note that the same stick combination is used to enable [OSD Joystick](OSD%20Joystick.md).*
|
||||
|
||||
Mode is exited using stick combination:
|
||||
|
||||
```LEFT CENTER```
|
||||
|
||||
# RC Box
|
||||
|
||||
There are 3 RC Boxes which can be used in armed and unarmed state:
|
||||
- Camera 1 - Simulate Wifi button
|
||||
- Camera 2 - Simulate POWER button
|
||||
- Camera 3 - Simulate Change Mode button.
|
||||
|
|
@ -2012,6 +2012,16 @@ Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened w
|
|||
|
||||
---
|
||||
|
||||
### led_pin_pwm_mode
|
||||
|
||||
PWM mode of LED pin.
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| SHARED_LOW | | |
|
||||
|
||||
---
|
||||
|
||||
### ledstrip_visual_beeper
|
||||
|
||||
_// TODO_
|
||||
|
@ -4442,6 +4452,66 @@ The space between the INAV and pilot logos, if `osd_use_pilot_logo` is `ON`. Thi
|
|||
|
||||
---
|
||||
|
||||
### osd_joystick_down
|
||||
|
||||
PWM value for DOWN key
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 0 | 0 | 100 |
|
||||
|
||||
---
|
||||
|
||||
### osd_joystick_enabled
|
||||
|
||||
Enable OSD Joystick emulation
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| OFF | OFF | ON |
|
||||
|
||||
---
|
||||
|
||||
### osd_joystick_enter
|
||||
|
||||
PWM value for ENTER key
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 75 | 0 | 100 |
|
||||
|
||||
---
|
||||
|
||||
### osd_joystick_left
|
||||
|
||||
PWM value for LEFT key
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 63 | 0 | 100 |
|
||||
|
||||
---
|
||||
|
||||
### osd_joystick_right
|
||||
|
||||
PWM value for RIGHT key
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 28 | 0 | 100 |
|
||||
|
||||
---
|
||||
|
||||
### osd_joystick_up
|
||||
|
||||
PWM value for UP key
|
||||
|
||||
| Default | Min | Max |
|
||||
| --- | --- | --- |
|
||||
| 48 | 0 | 100 |
|
||||
|
||||
---
|
||||
|
||||
### osd_left_sidebar_scroll
|
||||
|
||||
_// TODO_
|
||||
|
|
BIN
docs/assets/images/led_pin_pwm.png
Normal file
After Width: | Height: | Size: 5 KiB |
BIN
docs/assets/images/ledpinpwmfilter.png
Normal file
After Width: | Height: | Size: 3.3 KiB |
BIN
docs/assets/images/ledpinpwmled.png
Normal file
After Width: | Height: | Size: 2.1 KiB |
BIN
docs/assets/images/ledpinpwmpowerled.png
Normal file
After Width: | Height: | Size: 3.4 KiB |
BIN
docs/assets/images/osd_joystick.jpg
Normal file
After Width: | Height: | Size: 26 KiB |
BIN
docs/assets/images/osd_joystick_keys.png
Normal file
After Width: | Height: | Size: 5.6 KiB |
BIN
docs/assets/images/ws2811_data.png
Normal file
After Width: | Height: | Size: 4.2 KiB |
BIN
docs/assets/images/ws2811_data_high.png
Normal file
After Width: | Height: | Size: 4 KiB |
BIN
docs/assets/images/ws2811_packets.png
Normal file
After Width: | Height: | Size: 6.4 KiB |
BIN
docs/assets/images/ws2811_packets_high.png
Normal file
After Width: | Height: | Size: 5 KiB |
|
@ -525,6 +525,8 @@ main_sources(COMMON_SRC
|
|||
io/osd_grid.h
|
||||
io/osd_hud.c
|
||||
io/osd_hud.h
|
||||
io/osd_joystick.c
|
||||
io/osd_joystick.h
|
||||
io/smartport_master.c
|
||||
io/smartport_master.h
|
||||
io/vtx.c
|
||||
|
|
|
@ -121,7 +121,10 @@
|
|||
#define PG_OSD_COMMON_CONFIG 1031
|
||||
#define PG_TIMER_OVERRIDE_CONFIG 1032
|
||||
#define PG_EZ_TUNE 1033
|
||||
#define PG_INAV_END PG_EZ_TUNE
|
||||
#define PG_LEDPIN_CONFIG 1034
|
||||
#define PG_OSD_JOYSTICK_CONFIG 1035
|
||||
#define PG_INAV_END PG_OSD_JOYSTICK_CONFIG
|
||||
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
//#define PG_OSD_FONT_CONFIG 2047
|
||||
|
|
|
@ -43,15 +43,26 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "fc/settings.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#define WS2811_PERIOD (WS2811_TIMER_HZ / WS2811_CARRIER_HZ)
|
||||
#define WS2811_BIT_COMPARE_1 ((WS2811_PERIOD * 2) / 3)
|
||||
#define WS2811_BIT_COMPARE_0 (WS2811_PERIOD / 3)
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(ledPinConfig_t, ledPinConfig, PG_LEDPIN_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(ledPinConfig_t, ledPinConfig,
|
||||
.led_pin_pwm_mode = SETTING_LED_PIN_PWM_MODE_DEFAULT
|
||||
);
|
||||
|
||||
static DMA_RAM timerDMASafeType_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||
|
||||
static IO_t ws2811IO = IO_NONE;
|
||||
static TCH_t * ws2811TCH = NULL;
|
||||
static bool ws2811Initialised = false;
|
||||
static bool pwmMode = false;
|
||||
|
||||
static hsvColor_t ledColorBuffer[WS2811_LED_STRIP_LENGTH];
|
||||
|
||||
|
@ -91,6 +102,24 @@ void setStripColors(const hsvColor_t *colors)
|
|||
}
|
||||
}
|
||||
|
||||
bool ledConfigureDMA(void) {
|
||||
/* Compute the prescaler value */
|
||||
uint8_t period = WS2811_TIMER_HZ / WS2811_CARRIER_HZ;
|
||||
|
||||
timerConfigBase(ws2811TCH, period, WS2811_TIMER_HZ);
|
||||
timerPWMConfigChannel(ws2811TCH, 0);
|
||||
|
||||
return timerPWMConfigChannelDMA(ws2811TCH, ledStripDMABuffer, sizeof(ledStripDMABuffer[0]), WS2811_DMA_BUFFER_SIZE);
|
||||
}
|
||||
|
||||
void ledConfigurePWM(void) {
|
||||
timerConfigBase(ws2811TCH, 100, WS2811_TIMER_HZ );
|
||||
timerPWMConfigChannel(ws2811TCH, 0);
|
||||
timerPWMStart(ws2811TCH);
|
||||
timerEnable(ws2811TCH);
|
||||
pwmMode = true;
|
||||
}
|
||||
|
||||
void ws2811LedStripInit(void)
|
||||
{
|
||||
const timerHardware_t * timHw = timerGetByTag(IO_TAG(WS2811_PIN), TIM_USE_ANY);
|
||||
|
@ -104,28 +133,33 @@ void ws2811LedStripInit(void)
|
|||
return;
|
||||
}
|
||||
|
||||
/* Compute the prescaler value */
|
||||
uint8_t period = WS2811_TIMER_HZ / WS2811_CARRIER_HZ;
|
||||
|
||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
||||
IOConfigGPIOAF(ws2811IO, IOCFG_AF_PP_FAST, timHw->alternateFunction);
|
||||
|
||||
timerConfigBase(ws2811TCH, period, WS2811_TIMER_HZ);
|
||||
timerPWMConfigChannel(ws2811TCH, 0);
|
||||
|
||||
if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_LOW ) {
|
||||
ledConfigurePWM();
|
||||
*timerCCR(ws2811TCH) = 0;
|
||||
} else if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH ) {
|
||||
ledConfigurePWM();
|
||||
*timerCCR(ws2811TCH) = 100;
|
||||
} else {
|
||||
if (!ledConfigureDMA()) {
|
||||
// If DMA failed - abort
|
||||
if (!timerPWMConfigChannelDMA(ws2811TCH, ledStripDMABuffer, sizeof(ledStripDMABuffer[0]), WS2811_DMA_BUFFER_SIZE)) {
|
||||
ws2811Initialised = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// Zero out DMA buffer
|
||||
memset(&ledStripDMABuffer, 0, sizeof(ledStripDMABuffer));
|
||||
if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_SHARED_HIGH ) {
|
||||
ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE-1] = 255;
|
||||
}
|
||||
ws2811Initialised = true;
|
||||
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
}
|
||||
|
||||
bool isWS2811LedStripReady(void)
|
||||
{
|
||||
|
@ -140,7 +174,7 @@ STATIC_UNIT_TESTED void fastUpdateLEDDMABuffer(rgbColor24bpp_t *color)
|
|||
uint32_t grb = (color->rgb.g << 16) | (color->rgb.r << 8) | (color->rgb.b);
|
||||
|
||||
for (int8_t index = 23; index >= 0; index--) {
|
||||
ledStripDMABuffer[dmaBufferOffset++] = (grb & (1 << index)) ? WS2811_BIT_COMPARE_1 : WS2811_BIT_COMPARE_0;
|
||||
ledStripDMABuffer[WS2811_DELAY_BUFFER_LENGTH + dmaBufferOffset++] = (grb & (1 << index)) ? WS2811_BIT_COMPARE_1 : WS2811_BIT_COMPARE_0;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -153,7 +187,7 @@ void ws2811UpdateStrip(void)
|
|||
static rgbColor24bpp_t *rgb24;
|
||||
|
||||
// don't wait - risk of infinite block, just get an update next time round
|
||||
if (timerPWMDMAInProgress(ws2811TCH)) {
|
||||
if (pwmMode || timerPWMDMAInProgress(ws2811TCH)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -178,4 +212,40 @@ void ws2811UpdateStrip(void)
|
|||
timerPWMStartDMA(ws2811TCH);
|
||||
}
|
||||
|
||||
//value
|
||||
void ledPinStartPWM(uint16_t value) {
|
||||
if (ws2811TCH == NULL) {
|
||||
return;
|
||||
}
|
||||
|
||||
if ( !pwmMode ) {
|
||||
timerPWMStopDMA(ws2811TCH);
|
||||
//FIXME: implement method to release DMA
|
||||
ws2811TCH->dma->owner = OWNER_FREE;
|
||||
|
||||
ledConfigurePWM();
|
||||
}
|
||||
*timerCCR(ws2811TCH) = value;
|
||||
}
|
||||
|
||||
void ledPinStopPWM(void) {
|
||||
if (ws2811TCH == NULL || !pwmMode ) {
|
||||
return;
|
||||
}
|
||||
|
||||
if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_HIGH ) {
|
||||
*timerCCR(ws2811TCH) = 100;
|
||||
return;
|
||||
} else if ( ledPinConfig()->led_pin_pwm_mode == LED_PIN_PWM_MODE_LOW ) {
|
||||
*timerCCR(ws2811TCH) = 0;
|
||||
return;
|
||||
}
|
||||
pwmMode = false;
|
||||
|
||||
if (!ledConfigureDMA()) {
|
||||
ws2811Initialised = false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
|
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
#include "common/color.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#define WS2811_LED_STRIP_LENGTH 32
|
||||
#define WS2811_BITS_PER_LED 24
|
||||
|
@ -24,16 +25,33 @@
|
|||
|
||||
#define WS2811_DATA_BUFFER_SIZE (WS2811_BITS_PER_LED * WS2811_LED_STRIP_LENGTH)
|
||||
|
||||
#define WS2811_DMA_BUFFER_SIZE (WS2811_DATA_BUFFER_SIZE + WS2811_DELAY_BUFFER_LENGTH) // number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes)
|
||||
#define WS2811_DMA_BUFFER_SIZE (WS2811_DELAY_BUFFER_LENGTH + WS2811_DATA_BUFFER_SIZE + 1) // leading bytes (reset low 302us) + data bytes LEDS*3 + 1 byte(keep line high optionally)
|
||||
|
||||
#define WS2811_TIMER_HZ 2400000
|
||||
#define WS2811_CARRIER_HZ 800000
|
||||
|
||||
typedef enum {
|
||||
LED_PIN_PWM_MODE_SHARED_LOW = 0,
|
||||
LED_PIN_PWM_MODE_SHARED_HIGH = 1,
|
||||
LED_PIN_PWM_MODE_LOW = 2,
|
||||
LED_PIN_PWM_MODE_HIGH = 3
|
||||
} led_pin_pwm_mode_e;
|
||||
|
||||
typedef struct ledPinConfig_s {
|
||||
uint8_t led_pin_pwm_mode; //led_pin_pwm_mode_e
|
||||
} ledPinConfig_t;
|
||||
|
||||
PG_DECLARE(ledPinConfig_t, ledPinConfig);
|
||||
|
||||
void ws2811LedStripInit(void);
|
||||
void ws2811LedStripHardwareInit(void);
|
||||
void ws2811LedStripDMAEnable(void);
|
||||
bool ws2811LedStripDMAInProgress(void);
|
||||
|
||||
//value 0...100
|
||||
void ledPinStartPWM(uint16_t value);
|
||||
void ledPinStopPWM(void);
|
||||
|
||||
void ws2811UpdateStrip(void);
|
||||
|
||||
void setLedHsv(uint16_t index, const hsvColor_t *color);
|
||||
|
|
|
@ -81,13 +81,16 @@ void impl_timerConfigBase(TCH_t * tch, uint16_t period, uint32_t hz)
|
|||
TIM_HandleTypeDef * timHandle = tch->timCtx->timHandle;
|
||||
TIM_TypeDef * timer = tch->timCtx->timDef->tim;
|
||||
|
||||
if (timHandle->Instance == timer) {
|
||||
uint16_t period1 = (period - 1) & 0xffff;
|
||||
uint16_t prescaler1 = lrintf((float)timerGetBaseClock(tch) / hz + 0.01f) - 1;
|
||||
|
||||
if (timHandle->Instance == timer && timHandle->Init.Prescaler == prescaler1 && timHandle->Init.Period == period1) {
|
||||
return;
|
||||
}
|
||||
|
||||
timHandle->Instance = timer;
|
||||
timHandle->Init.Prescaler = lrintf((float)timerGetBaseClock(tch) / hz + 0.01f) - 1;
|
||||
timHandle->Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR
|
||||
timHandle->Init.Prescaler = prescaler1;
|
||||
timHandle->Init.Period = period1; // AKA TIMx_ARR
|
||||
timHandle->Init.RepetitionCounter = 0;
|
||||
timHandle->Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||
timHandle->Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||
|
@ -565,6 +568,15 @@ void impl_timerPWMStartDMA(TCH_t * tch)
|
|||
|
||||
void impl_timerPWMStopDMA(TCH_t * tch)
|
||||
{
|
||||
(void)tch;
|
||||
// FIXME
|
||||
const uint32_t streamLL = lookupDMALLStreamTable[DMATAG_GET_STREAM(tch->timHw->dmaTag)];
|
||||
DMA_TypeDef *dmaBase = tch->dma->dma;
|
||||
|
||||
ATOMIC_BLOCK(NVIC_PRIO_MAX) {
|
||||
LL_TIM_DisableDMAReq_CCx(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex]);
|
||||
LL_DMA_DisableStream(dmaBase, streamLL);
|
||||
DMA_CLEAR_FLAG(tch->dma, DMA_IT_TCIF);
|
||||
}
|
||||
tch->dmaState = TCH_DMA_IDLE;
|
||||
|
||||
HAL_TIM_Base_Start(tch->timCtx->timHandle);
|
||||
}
|
||||
|
|
|
@ -516,5 +516,6 @@ void impl_timerPWMStopDMA(TCH_t * tch)
|
|||
{
|
||||
DMA_Cmd(tch->dma->ref, DISABLE);
|
||||
TIM_DMACmd(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], DISABLE);
|
||||
tch->dmaState = TCH_DMA_IDLE;
|
||||
TIM_Cmd(tch->timHw->tim, ENABLE);
|
||||
}
|
||||
|
|
|
@ -404,6 +404,6 @@ void impl_timerPWMStopDMA(TCH_t * tch)
|
|||
{
|
||||
dma_channel_enable(tch->dma->ref,FALSE);
|
||||
tmr_dma_request_enable(tch->timHw->tim, lookupDMASourceTable[tch->timHw->channelIndex], FALSE);
|
||||
tch->dmaState = TCH_DMA_IDLE;
|
||||
tmr_counter_enable(tch->timHw->tim, TRUE);
|
||||
|
||||
}
|
||||
|
|
|
@ -68,6 +68,7 @@ bool cliMode = false;
|
|||
#include "drivers/time.h"
|
||||
#include "drivers/usb_msc.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
|
||||
#include "fc/fc_core.h"
|
||||
#include "fc/cli.h"
|
||||
|
@ -1688,6 +1689,20 @@ static void cliModeColor(char *cmdline)
|
|||
cliPrintLinef("mode_color %u %u %u", modeIdx, funIdx, color);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliLedPinPWM(char *cmdline)
|
||||
{
|
||||
int i;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
ledPinStopPWM();
|
||||
cliPrintLine("PWM stopped");
|
||||
} else {
|
||||
i = fastA2I(cmdline);
|
||||
ledPinStartPWM(i);
|
||||
cliPrintLinef("PWM started: %d%%",i);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static void cliDelay(char* cmdLine) {
|
||||
|
@ -4035,6 +4050,7 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
|
||||
#ifdef USE_LED_STRIP
|
||||
CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
|
||||
CLI_COMMAND_DEF("ledpinpwm", "start/stop PWM on LED pin, 0..100 duty ratio", "[<value>]\r\n", cliLedPinPWM),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("map", "configure rc channel order", "[<map>]", cliMap),
|
||||
CLI_COMMAND_DEF("memory", "view memory usage", NULL, cliMemory),
|
||||
|
|
|
@ -62,6 +62,7 @@
|
|||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
#include "io/osd_joystick.h"
|
||||
#include "io/smartport_master.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_msp.h"
|
||||
|
@ -393,8 +394,12 @@ void fcTasksInit(void)
|
|||
#endif
|
||||
#endif
|
||||
#ifdef USE_RCDEVICE
|
||||
#ifdef USE_LED_STRIP
|
||||
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled() || osdJoystickEnabled());
|
||||
#else
|
||||
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
|
||||
#endif
|
||||
#endif
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true);
|
||||
#endif
|
||||
|
|
55
src/main/fc/settings.yaml
Executable file → Normal file
|
@ -193,6 +193,9 @@ tables:
|
|||
- name: nav_mc_althold_throttle
|
||||
values: ["STICK", "MID_STICK", "HOVER"]
|
||||
enum: navMcAltHoldThrottle_e
|
||||
- name: led_pin_pwm_mode
|
||||
values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"]
|
||||
enum: led_pin_pwm_mode_e
|
||||
|
||||
constants:
|
||||
RPYL_PID_MIN: 0
|
||||
|
@ -4019,3 +4022,55 @@ groups:
|
|||
default_value: 1.2
|
||||
field: attnFilterCutoff
|
||||
max: 100
|
||||
|
||||
- name: PG_LEDPIN_CONFIG
|
||||
type: ledPinConfig_t
|
||||
headers: ["drivers/light_ws2811strip.h"]
|
||||
members:
|
||||
- name: led_pin_pwm_mode
|
||||
condition: USE_LED_STRIP
|
||||
description: "PWM mode of LED pin."
|
||||
default_value: "SHARED_LOW"
|
||||
field: led_pin_pwm_mode
|
||||
table: led_pin_pwm_mode
|
||||
|
||||
- name: PG_OSD_JOYSTICK_CONFIG
|
||||
type: osdJoystickConfig_t
|
||||
headers: ["io/osd_joystick.h"]
|
||||
condition: USE_RCDEVICE && USE_LED_STRIP
|
||||
members:
|
||||
- name: osd_joystick_enabled
|
||||
description: "Enable OSD Joystick emulation"
|
||||
default_value: OFF
|
||||
field: osd_joystick_enabled
|
||||
type: bool
|
||||
- name: osd_joystick_down
|
||||
description: "PWM value for DOWN key"
|
||||
default_value: 0
|
||||
field: osd_joystick_down
|
||||
min: 0
|
||||
max: 100
|
||||
- name: osd_joystick_up
|
||||
description: "PWM value for UP key"
|
||||
default_value: 48
|
||||
field: osd_joystick_up
|
||||
min: 0
|
||||
max: 100
|
||||
- name: osd_joystick_left
|
||||
description: "PWM value for LEFT key"
|
||||
default_value: 63
|
||||
field: osd_joystick_left
|
||||
min: 0
|
||||
max: 100
|
||||
- name: osd_joystick_right
|
||||
description: "PWM value for RIGHT key"
|
||||
default_value: 28
|
||||
field: osd_joystick_right
|
||||
min: 0
|
||||
max: 100
|
||||
- name: osd_joystick_enter
|
||||
description: "PWM value for ENTER key"
|
||||
default_value: 75
|
||||
field: osd_joystick_enter
|
||||
min: 0
|
||||
max: 100
|
||||
|
|
74
src/main/io/osd_joystick.c
Normal file
|
@ -0,0 +1,74 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/crc.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/streambuf.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
#include "fc/settings.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/rcdevice.h"
|
||||
|
||||
#include "osd_joystick.h"
|
||||
|
||||
#ifdef USE_RCDEVICE
|
||||
#ifdef USE_LED_STRIP
|
||||
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(osdJoystickConfig_t, osdJoystickConfig, PG_OSD_JOYSTICK_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(osdJoystickConfig_t, osdJoystickConfig,
|
||||
.osd_joystick_enabled = SETTING_OSD_JOYSTICK_ENABLED_DEFAULT,
|
||||
.osd_joystick_down = SETTING_OSD_JOYSTICK_DOWN_DEFAULT,
|
||||
.osd_joystick_up = SETTING_OSD_JOYSTICK_UP_DEFAULT,
|
||||
.osd_joystick_left = SETTING_OSD_JOYSTICK_LEFT_DEFAULT,
|
||||
.osd_joystick_right = SETTING_OSD_JOYSTICK_RIGHT_DEFAULT,
|
||||
.osd_joystick_enter = SETTING_OSD_JOYSTICK_ENTER_DEFAULT
|
||||
);
|
||||
|
||||
bool osdJoystickEnabled(void) {
|
||||
return osdJoystickConfig()->osd_joystick_enabled;
|
||||
}
|
||||
|
||||
|
||||
void osdJoystickSimulate5KeyButtonPress(uint8_t operation) {
|
||||
switch (operation) {
|
||||
case RCDEVICE_CAM_KEY_ENTER:
|
||||
ledPinStartPWM( osdJoystickConfig()->osd_joystick_enter );
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_LEFT:
|
||||
ledPinStartPWM( osdJoystickConfig()->osd_joystick_left );
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_UP:
|
||||
ledPinStartPWM( osdJoystickConfig()->osd_joystick_up );
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_RIGHT:
|
||||
ledPinStartPWM( osdJoystickConfig()->osd_joystick_right );
|
||||
break;
|
||||
case RCDEVICE_CAM_KEY_DOWN:
|
||||
ledPinStartPWM( osdJoystickConfig()->osd_joystick_down );
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void osdJoystickSimulate5KeyButtonRelease(void) {
|
||||
ledPinStopPWM();
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
#endif
|
26
src/main/io/osd_joystick.h
Normal file
|
@ -0,0 +1,26 @@
|
|||
#pragma once
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#ifdef USE_RCDEVICE
|
||||
#ifdef USE_LED_STRIP
|
||||
|
||||
typedef struct osdJoystickConfig_s {
|
||||
bool osd_joystick_enabled;
|
||||
uint8_t osd_joystick_down;
|
||||
uint8_t osd_joystick_up;
|
||||
uint8_t osd_joystick_left;
|
||||
uint8_t osd_joystick_right;
|
||||
uint8_t osd_joystick_enter;
|
||||
} osdJoystickConfig_t;
|
||||
|
||||
PG_DECLARE(osdJoystickConfig_t, osdJoystickConfig);
|
||||
|
||||
bool osdJoystickEnabled(void);
|
||||
|
||||
// 5 key osd cable simulation
|
||||
void osdJoystickSimulate5KeyButtonPress(uint8_t operation);
|
||||
void osdJoystickSimulate5KeyButtonRelease(void);
|
||||
|
||||
#endif
|
||||
#endif
|
|
@ -29,6 +29,7 @@
|
|||
|
||||
#include "io/beeper.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
#include "io/osd_joystick.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
@ -47,6 +48,14 @@ bool waitingDeviceResponse = false;
|
|||
|
||||
static bool isFeatureSupported(uint8_t feature)
|
||||
{
|
||||
#ifndef UNIT_TEST
|
||||
#ifdef USE_LED_STRIP
|
||||
if (!rcdeviceIsEnabled() && osdJoystickEnabled() ) {
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
if (camDevice->info.features & feature) {
|
||||
return true;
|
||||
}
|
||||
|
@ -72,6 +81,7 @@ static void rcdeviceCameraControlProcess(void)
|
|||
}
|
||||
|
||||
uint8_t behavior = RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION;
|
||||
uint8_t behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION;
|
||||
switch (i) {
|
||||
case BOXCAMERA1:
|
||||
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON)) {
|
||||
|
@ -81,11 +91,13 @@ static void rcdeviceCameraControlProcess(void)
|
|||
if (!ARMING_FLAG(ARMED)) {
|
||||
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN;
|
||||
}
|
||||
behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN;
|
||||
}
|
||||
break;
|
||||
case BOXCAMERA2:
|
||||
if (isFeatureSupported(RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON)) {
|
||||
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN;
|
||||
behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN;
|
||||
}
|
||||
break;
|
||||
case BOXCAMERA3:
|
||||
|
@ -94,16 +106,43 @@ static void rcdeviceCameraControlProcess(void)
|
|||
if (!ARMING_FLAG(ARMED)) {
|
||||
behavior = RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE;
|
||||
}
|
||||
behavior1 = RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if (behavior != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) {
|
||||
if ((behavior != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) && rcdeviceIsEnabled()) {
|
||||
runcamDeviceSimulateCameraButton(camDevice, behavior);
|
||||
switchStates[switchIndex].isActivated = true;
|
||||
}
|
||||
#ifndef UNIT_TEST
|
||||
#ifdef USE_LED_STRIP
|
||||
else if ((behavior1 != RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION) && osdJoystickEnabled()) {
|
||||
switch (behavior1) {
|
||||
case RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN:
|
||||
osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_ENTER);
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN:
|
||||
osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_UP);
|
||||
break;
|
||||
case RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE:
|
||||
osdJoystickSimulate5KeyButtonPress(RCDEVICE_CAM_KEY_DOWN);
|
||||
break;
|
||||
}
|
||||
switchStates[switchIndex].isActivated = true;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
UNUSED(behavior1);
|
||||
} else {
|
||||
#ifndef UNIT_TEST
|
||||
#ifdef USE_LED_STRIP
|
||||
if (osdJoystickEnabled() && switchStates[switchIndex].isActivated) {
|
||||
osdJoystickSimulate5KeyButtonRelease();
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
switchStates[switchIndex].isActivated = false;
|
||||
}
|
||||
}
|
||||
|
@ -225,15 +264,25 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (camDevice->serialPort == 0 || ARMING_FLAG(ARMED)) {
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (isButtonPressed) {
|
||||
if (IS_MID(YAW) && IS_MID(PITCH) && IS_MID(ROLL)) {
|
||||
if ( rcdeviceIsEnabled() ) {
|
||||
rcdeviceSend5KeyOSDCableSimualtionEvent(RCDEVICE_CAM_KEY_RELEASE);
|
||||
waitingDeviceResponse = true;
|
||||
}
|
||||
#ifndef UNIT_TEST
|
||||
#ifdef USE_LED_STRIP
|
||||
else if (osdJoystickEnabled()) {
|
||||
osdJoystickSimulate5KeyButtonRelease();
|
||||
isButtonPressed = false;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
} else {
|
||||
if (waitingDeviceResponse) {
|
||||
return;
|
||||
|
@ -266,16 +315,33 @@ static void rcdevice5KeySimulationProcess(timeUs_t currentTimeUs)
|
|||
}
|
||||
|
||||
if (key != RCDEVICE_CAM_KEY_NONE) {
|
||||
if ( rcdeviceIsEnabled() ) {
|
||||
rcdeviceSend5KeyOSDCableSimualtionEvent(key);
|
||||
isButtonPressed = true;
|
||||
waitingDeviceResponse = true;
|
||||
}
|
||||
#ifndef UNIT_TEST
|
||||
#ifdef USE_LED_STRIP
|
||||
else if (osdJoystickEnabled()) {
|
||||
if ( key == RCDEVICE_CAM_KEY_CONNECTION_OPEN ) {
|
||||
rcdeviceInMenu = true;
|
||||
} else if ( key == RCDEVICE_CAM_KEY_CONNECTION_CLOSE ) {
|
||||
rcdeviceInMenu = false;
|
||||
} else {
|
||||
osdJoystickSimulate5KeyButtonPress(key);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
isButtonPressed = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void rcdeviceUpdate(timeUs_t currentTimeUs)
|
||||
{
|
||||
if ( rcdeviceIsEnabled() ) {
|
||||
rcdeviceReceive(currentTimeUs);
|
||||
}
|
||||
|
||||
rcdeviceCameraControlProcess();
|
||||
|
||||
|
|
|
@ -56,6 +56,7 @@
|
|||
|
||||
#include "io/vtx.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 4);
|
||||
|
||||
|
@ -475,6 +476,17 @@ static int logicConditionCompute(
|
|||
}
|
||||
break;
|
||||
|
||||
#ifdef LED_PIN
|
||||
case LOGIC_CONDITION_LED_PIN_PWM:
|
||||
if (operandA >=0 && operandA <= 100) {
|
||||
ledPinStartPWM((uint8_t)operandA);
|
||||
} else {
|
||||
ledPinStopPWM();
|
||||
}
|
||||
return operandA;
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return false;
|
||||
break;
|
||||
|
|
|
@ -81,7 +81,8 @@ typedef enum {
|
|||
LOGIC_CONDITION_TIMER = 49,
|
||||
LOGIC_CONDITION_DELTA = 50,
|
||||
LOGIC_CONDITION_APPROX_EQUAL = 51,
|
||||
LOGIC_CONDITION_LAST = 52,
|
||||
LOGIC_CONDITION_LED_PIN_PWM = 52,
|
||||
LOGIC_CONDITION_LAST = 53,
|
||||
} logicOperation_e;
|
||||
|
||||
typedef enum logicOperandType_s {
|
||||
|
|