mirror of
https://github.com/Show-maket/IR-protocol.git
synced 2026-04-28 03:08:08 +00:00
add brightness controll
This commit is contained in:
59
IR_Encoder.h
59
IR_Encoder.h
@ -1,5 +1,6 @@
|
||||
#pragma once
|
||||
#include "IR_config.h"
|
||||
#include "IrTxBsrrWave.h"
|
||||
|
||||
// TODO: Отложенная передача после завершения приема
|
||||
|
||||
@ -22,10 +23,7 @@ class IR_Encoder : public IR_FOX
|
||||
public:
|
||||
static HardwareTimer* IR_Timer;
|
||||
|
||||
struct IR_TxGateRun {
|
||||
uint16_t lenTicks; // number of timer ticks at carrierFrec*2
|
||||
bool gate; // true: carrier enabled (output toggles), false: silent (output forced low)
|
||||
};
|
||||
using IR_TxGateRun = IrTxGateRun;
|
||||
|
||||
using ExternalTxBusyFn = bool (*)(void *ctx);
|
||||
using ExternalTxStartFn = bool (*)(void *ctx, IR_Encoder *enc, const uint8_t *packet, uint8_t len);
|
||||
@ -40,12 +38,42 @@ public:
|
||||
IR_Encoder(uint8_t pin, uint16_t addr = 0, IR_DecoderRaw *decPair = nullptr, bool autoHandle = true);
|
||||
static void isr();
|
||||
static void begin(HardwareTimer* timer, uint8_t channel, IRQn_Type IRQn, uint8_t priority, void(*isrCallback)() = nullptr);
|
||||
/** Configure timer frequency for TX clock (carrierFrec*2) without attaching ISR. */
|
||||
/**
|
||||
* Глобальный знаменатель: частота таймера TX = carrierFrec × multiply (слотов на период несущей).
|
||||
* По умолчанию multiply=2 (как бывшие carrierFrec×2). Задавать до begin/beginClockOnly либо после
|
||||
* изменения вызвать retuneCarrierClock() (не менять multiply во время активной передачи).
|
||||
*/
|
||||
static void setCarrierMultiply(uint16_t multiply);
|
||||
static uint16_t carrierMultiply();
|
||||
/** Повторно применить carrierFrec×multiply к IR_Timer (pause + setOverflow), ISR не перенавешивает. */
|
||||
static void retuneCarrierClock();
|
||||
|
||||
/** Максимальный числитель мощности: ⌊multiply/2⌋ (100% в setPowerPercent). */
|
||||
static uint16_t maxPowerNumerator();
|
||||
|
||||
/** Числитель N: при открытой огибающей N из multiply тиков HIGH за период несущей. Clamped к maxPowerNumerator(). */
|
||||
void setPowerNumerator(uint16_t n);
|
||||
uint16_t powerNumerator() const;
|
||||
/** p∈[0,100] → ближайший допустимый числитель; 100% даёт N = maxPowerNumerator(). */
|
||||
void setPowerPercent(uint8_t p);
|
||||
|
||||
/** После buildGateRuns: lenTicks в тактах 2×Fc → физические тики (carrierFrec×multiply). Может разбить сегменты. */
|
||||
static bool scaleGateRunsToPhysical(IR_TxGateRun* runs, size_t* ioCount, size_t maxRuns, uint16_t multiply);
|
||||
|
||||
/** Configure timer frequency for TX clock (carrierFrec × multiply) without attaching ISR. */
|
||||
static void beginClockOnly(HardwareTimer *timer);
|
||||
static HardwareTimer* get_IR_Timer();
|
||||
/** Call from main loop/tick: if ISR requested carrier stop, pause timer here (not in ISR). */
|
||||
static void tick();
|
||||
|
||||
/**
|
||||
* Режим внутреннего TX без DMA: false — BSRR + кольцо (buildGateRuns + scaleGateRunsToPhysical);
|
||||
* true — FSM «налету» + скважность несущей как у буферного пути (подшаги multiply/2 на шаг FSM).
|
||||
* Выставить до begin/rawSend (глобально на все IR_Encoder). Игнорируется при externalTxStartFn.
|
||||
*/
|
||||
static void setTxIsrLegacyMode(bool legacy);
|
||||
static bool txIsrLegacyMode();
|
||||
|
||||
/** Optional: register external TX backend (e.g. DMA driver). */
|
||||
static void setExternalTxBackend(ExternalTxStartFn startFn, ExternalTxBusyFn busyFn, void *ctx);
|
||||
|
||||
@ -99,6 +127,8 @@ public:
|
||||
void _isr();
|
||||
private:
|
||||
static volatile bool carrierStopPending;
|
||||
static bool txIsrLegacyMode_;
|
||||
static uint16_t s_carrierMultiply;
|
||||
static void carrierResume();
|
||||
static void carrierPauseIfIdle();
|
||||
|
||||
@ -146,6 +176,25 @@ private:
|
||||
void loadTxFsmFromMembers(TxFsmState &st) const;
|
||||
void storeTxFsmToMembers(const TxFsmState &st);
|
||||
|
||||
IrTxBsrrWave txBsrrWave_{};
|
||||
IR_TxGateRun txGateRuns_[irproto::kIsrTxMaxGateRuns]{};
|
||||
uint32_t txBsrrWords_[irproto::kIsrTxBsrrWordCount]{};
|
||||
uint16_t txBsrrReadIdx_ = 0;
|
||||
uint16_t txBsrrHalfLen_ = 0;
|
||||
uint32_t txBsrrTotalTicks_ = 0;
|
||||
uint32_t txBsrrTicksSent_ = 0;
|
||||
|
||||
/** Снимок на старт TX (буферный и legacy путь). */
|
||||
uint16_t txPowerSnap_ = 1;
|
||||
uint16_t txMultiplySnap_ = 2;
|
||||
|
||||
/** Legacy: физических тиков на один логический шаг FSM = multiply/2. */
|
||||
uint16_t legacyPhysPerLogical_ = 1;
|
||||
uint16_t legacyPhysCounter_ = 0;
|
||||
uint16_t legacySlotInPeriod_ = 0;
|
||||
|
||||
volatile uint16_t powerNumerator_ = 1;
|
||||
|
||||
IR_DecoderRaw *decPair = nullptr;
|
||||
IR_DecoderRaw *singleBlindDecoder = nullptr;
|
||||
IR_DecoderRaw **blindDecoders = nullptr;
|
||||
|
||||
Reference in New Issue
Block a user