Skip to content

Commit 48b60d3

Browse files
committed
Throttle back, only run a 10 ms loop during PD negotiation, otherwise run the loop once / second.
1 parent c9d8791 commit 48b60d3

File tree

1 file changed

+23
-13
lines changed

1 file changed

+23
-13
lines changed

src/Braccio++.cpp

Lines changed: 23 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -95,12 +95,13 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
9595
Serial.begin(115200);
9696

9797
pinMode(PIN_FUSB302_INT, INPUT_PULLUP);
98+
attachInterrupt(PIN_FUSB302_INT, braccio_onPowerIrqEvent, FALLING);
9899
pinMode(RS485_RX_PIN, INPUT_PULLUP);
99100

100101
_PD_UFP.init_PPS(_i2c_mtx, PPS_V(7.2), PPS_A(2.0));
101-
attachInterrupt(PIN_FUSB302_INT, braccio_onPowerIrqEvent, FALLING);
102-
_pd_thd.start(mbed::callback(this, &BraccioClass::pd_thread_func));
103102
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
103+
braccio_onPowerIrqEvent(); /* Start power burst. */
104+
_pd_thd.start(mbed::callback(this, &BraccioClass::pd_thread_func));
104105

105106
button_init();
106107

@@ -118,7 +119,7 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
118119
lvgl_pleaseConnectPower();
119120

120121
/* Loop forever, if no power is attached. */
121-
while(!_PD_UFP.is_PPS_ready()) { }
122+
while(!_PD_UFP.is_PPS_ready()) { delay(10); }
122123
lv_obj_clean(lv_scr_act());
123124

124125
if (custom_menu)
@@ -438,30 +439,39 @@ void BraccioClass::lvgl_defaultMenu()
438439
void BraccioClass::pd_thread_func()
439440
{
440441
size_t last_time_ask_pps = 0;
442+
unsigned long start_pd_burst = 0;
443+
static unsigned long const START_PD_BURST_TIMEOUT_ms = 1000;
441444

442445
for(;;)
443446
{
447+
/* Wait for either a timer or a IRQ event. */
444448
uint32_t const flags = _pd_events.wait_any(0xFF);
445449

446-
if (flags & PD_IRQ_EVENT_FLAG)
450+
/* The actual calls to the PD library. */
451+
if ((millis() - last_time_ask_pps) > 5000)
447452
{
448-
_pd_timer.detach();
449-
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
453+
start_pd_burst = millis();
454+
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
455+
last_time_ask_pps = millis();
450456
}
457+
_PD_UFP.run();
458+
_PD_UFP.print_status(Serial);
451459

452-
if (flags & PD_TIMER_EVENT_FLAG)
460+
/* Set up the next time this loop is called. */
461+
if (flags & PD_IRQ_EVENT_FLAG)
453462
{
463+
start_pd_burst = millis();
454464
_pd_timer.detach();
455465
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
456466
}
457467

458-
_PD_UFP.run();
459-
_PD_UFP.print_status(Serial);
460-
461-
if ((millis() - last_time_ask_pps) > 5000)
468+
if (flags & PD_TIMER_EVENT_FLAG)
462469
{
463-
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
464-
last_time_ask_pps = millis();
470+
_pd_timer.detach();
471+
if ((millis() - start_pd_burst) < START_PD_BURST_TIMEOUT_ms)
472+
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
473+
else
474+
_pd_timer.attach(braccio_onPowerTimerEvent, 1000ms);
465475
}
466476
}
467477
}

0 commit comments

Comments
 (0)