Skip to content

Commit c9d8791

Browse files
committed
Ensure that run() is called often enough, otherwise we won't be able to complete the power (re)negotiation on time.
1 parent 8c60195 commit c9d8791

File tree

2 files changed

+38
-53
lines changed

2 files changed

+38
-53
lines changed

src/Braccio++.cpp

Lines changed: 33 additions & 49 deletions
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@ extern "C"
4242
{
4343
void braccio_disp_flush(lv_disp_drv_t *disp, const lv_area_t *area, lv_color_t *color_p);
4444
void braccio_read_keypad(lv_indev_drv_t * indev, lv_indev_data_t * data);
45-
void braccio_unlock_pd_semaphore_irq();
46-
void braccio_unlock_pd_semaphore();
45+
void braccio_onPowerIrqEvent();
46+
void braccio_onPowerTimerEvent();
4747
};
4848

4949
/**************************************************************************************
@@ -77,7 +77,6 @@ BraccioClass::BraccioClass()
7777
, _display_thd{}
7878
, _pd_events{}
7979
, _pd_timer{}
80-
, _start_pd_burst{0xFFFFFFFF}
8180
, _pd_thd{osPriorityHigh}
8281
{
8382

@@ -98,10 +97,10 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
9897
pinMode(PIN_FUSB302_INT, INPUT_PULLUP);
9998
pinMode(RS485_RX_PIN, INPUT_PULLUP);
10099

101-
_pd_thd.start(mbed::callback(this, &BraccioClass::pd_thread_func));
102-
attachInterrupt(PIN_FUSB302_INT, braccio_unlock_pd_semaphore_irq, FALLING);
103-
_pd_timer.attach(braccio_unlock_pd_semaphore, 10ms);
104100
_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));
103+
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
105104

106105
button_init();
107106

@@ -112,26 +111,14 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
112111
lvgl_init();
113112
_display_thd.start(mbed::callback(this, &BraccioClass::display_thread_func));
114113

115-
116-
auto check_power_func = [this]()
117-
{
118-
if (!_PD_UFP.is_PPS_ready())
119-
{
120-
_PD_UFP.print_status(Serial);
121-
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
122-
delay(10);
123-
}
124-
};
125-
126-
lvgl_splashScreen(2000, check_power_func);
114+
lvgl_splashScreen(2000);
127115
lv_obj_clean(lv_scr_act());
128116

129117
if (!_PD_UFP.is_PPS_ready())
130118
lvgl_pleaseConnectPower();
131119

132120
/* Loop forever, if no power is attached. */
133-
while(!_PD_UFP.is_PPS_ready())
134-
check_power_func();
121+
while(!_PD_UFP.is_PPS_ready()) { }
135122
lv_obj_clean(lv_scr_act());
136123

137124
if (custom_menu)
@@ -248,15 +235,14 @@ void BraccioClass::lvgl_disp_flush(lv_disp_drv_t *disp, const lv_area_t *area, l
248235
lv_disp_flush_ready(disp);
249236
}
250237

251-
void BraccioClass::unlock_pd_semaphore_irq()
238+
void BraccioClass::onPowerIrqEvent()
252239
{
253-
_start_pd_burst = millis();
254-
_pd_events.set(2);
240+
_pd_events.set(PD_IRQ_EVENT_FLAG);
255241
}
256242

257-
void BraccioClass::unlock_pd_semaphore()
243+
void BraccioClass::onPowerTimerEvent()
258244
{
259-
_pd_events.set(1);
245+
_pd_events.set(PD_TIMER_EVENT_FLAG);
260246
}
261247

262248
/**************************************************************************************
@@ -411,7 +397,7 @@ void BraccioClass::display_thread_func()
411397
}
412398
}
413399

414-
void BraccioClass::lvgl_splashScreen(unsigned long const duration_ms, std::function<void()> check_power_func)
400+
void BraccioClass::lvgl_splashScreen(unsigned long const duration_ms)
415401
{
416402
extern const lv_img_dsc_t img_bulb_gif;
417403

@@ -420,14 +406,8 @@ void BraccioClass::lvgl_splashScreen(unsigned long const duration_ms, std::funct
420406
lv_gif_set_src(img, &img_bulb_gif);
421407
lv_obj_align(img, LV_ALIGN_CENTER, 0, 0);
422408

423-
/* Wait until the splash screen duration is over.
424-
* Meanwhile use the wait time for checking the
425-
* power.
426-
*/
427-
for (unsigned long const start = millis(); millis() - start < duration_ms;)
428-
{
429-
check_power_func();
430-
}
409+
/* Wait until the splash screen duration is over. */
410+
for (unsigned long const start = millis(); millis() - start < duration_ms; delay(10)) { }
431411

432412
lv_obj_del(img);
433413
}
@@ -457,27 +437,31 @@ void BraccioClass::lvgl_defaultMenu()
457437

458438
void BraccioClass::pd_thread_func()
459439
{
460-
_start_pd_burst = millis();
461440
size_t last_time_ask_pps = 0;
462441

463442
for(;;)
464443
{
465-
auto ret = _pd_events.wait_any(0xFF);
466-
if ((ret & 1) && (millis() - _start_pd_burst > 1000)) {
444+
uint32_t const flags = _pd_events.wait_any(0xFF);
445+
446+
if (flags & PD_IRQ_EVENT_FLAG)
447+
{
467448
_pd_timer.detach();
468-
_pd_timer.attach(braccio_unlock_pd_semaphore, 5s);
449+
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
469450
}
470-
if (ret & 2) {
451+
452+
if (flags & PD_TIMER_EVENT_FLAG)
453+
{
471454
_pd_timer.detach();
472-
_pd_timer.attach(braccio_unlock_pd_semaphore, 50ms);
473-
}
474-
if (millis() - last_time_ask_pps > 5000) {
475-
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
476-
last_time_ask_pps = millis();
455+
_pd_timer.attach(braccio_onPowerTimerEvent, 10ms);
477456
}
457+
478458
_PD_UFP.run();
479-
if (_PD_UFP.is_power_ready() && _PD_UFP.is_PPS_ready()) {
459+
_PD_UFP.print_status(Serial);
480460

461+
if ((millis() - last_time_ask_pps) > 5000)
462+
{
463+
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
464+
last_time_ask_pps = millis();
481465
}
482466
}
483467
}
@@ -539,12 +523,12 @@ extern "C" void braccio_read_keypad(lv_indev_drv_t * drv, lv_indev_data_t* data)
539523
data->key = last_key;
540524
}
541525

542-
void braccio_unlock_pd_semaphore_irq()
526+
void braccio_onPowerIrqEvent()
543527
{
544-
Braccio.unlock_pd_semaphore_irq();
528+
Braccio.onPowerIrqEvent();
545529
}
546530

547-
void braccio_unlock_pd_semaphore()
531+
void braccio_onPowerTimerEvent()
548532
{
549-
Braccio.unlock_pd_semaphore();
533+
Braccio.onPowerTimerEvent();
550534
}

src/Braccio++.h

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -103,8 +103,8 @@ class BraccioClass
103103

104104
/* Those functions MUST NOT be used by the user. */
105105
void lvgl_disp_flush(lv_disp_drv_t *disp, const lv_area_t *area, lv_color_t *color_p);
106-
void unlock_pd_semaphore_irq();
107-
void unlock_pd_semaphore();
106+
void onPowerIrqEvent();
107+
void onPowerTimerEvent();
108108

109109
protected:
110110

@@ -156,14 +156,15 @@ class BraccioClass
156156
void display_init();
157157
void lvgl_init();
158158
void display_thread_func();
159-
void lvgl_splashScreen(unsigned long const duration_ms, std::function<void()> check_power_func);
159+
void lvgl_splashScreen(unsigned long const duration_ms);
160160
void lvgl_pleaseConnectPower();
161161
void lvgl_defaultMenu();
162162

163163

164+
static uint32_t constexpr PD_IRQ_EVENT_FLAG = 1;
165+
static uint32_t constexpr PD_TIMER_EVENT_FLAG = 2;
164166
rtos::EventFlags _pd_events;
165167
mbed::Ticker _pd_timer;
166-
unsigned int _start_pd_burst;
167168
rtos::Thread _pd_thd;
168169
void pd_thread_func();
169170
};

0 commit comments

Comments
 (0)