@@ -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
@@ -96,12 +95,13 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
9695 Serial.begin (115200 );
9796
9897 pinMode (PIN_FUSB302_INT, INPUT_PULLUP);
98+ attachInterrupt (PIN_FUSB302_INT, braccio_onPowerIrqEvent, FALLING);
9999 pinMode (RS485_RX_PIN, INPUT_PULLUP);
100100
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);
104101 _PD_UFP.init_PPS (_i2c_mtx, PPS_V (7.2 ), PPS_A (2.0 ));
102+ _pd_timer.attach (braccio_onPowerTimerEvent, 10ms);
103+ braccio_onPowerIrqEvent (); /* Start power burst. */
104+ _pd_thd.start (mbed::callback (this , &BraccioClass::pd_thread_func));
105105
106106 button_init ();
107107
@@ -112,26 +112,14 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
112112 lvgl_init ();
113113 _display_thd.start (mbed::callback (this , &BraccioClass::display_thread_func));
114114
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);
115+ lvgl_splashScreen (2000 );
127116 lv_obj_clean (lv_scr_act ());
128117
129118 if (!_PD_UFP.is_PPS_ready ())
130119 lvgl_pleaseConnectPower ();
131120
132121 /* Loop forever, if no power is attached. */
133- while (!_PD_UFP.is_PPS_ready ())
134- check_power_func ();
122+ while (!_PD_UFP.is_PPS_ready ()) { delay (10 ); }
135123 lv_obj_clean (lv_scr_act ());
136124
137125 if (custom_menu)
@@ -248,15 +236,14 @@ void BraccioClass::lvgl_disp_flush(lv_disp_drv_t *disp, const lv_area_t *area, l
248236 lv_disp_flush_ready (disp);
249237}
250238
251- void BraccioClass::unlock_pd_semaphore_irq ()
239+ void BraccioClass::onPowerIrqEvent ()
252240{
253- _start_pd_burst = millis ();
254- _pd_events.set (2 );
241+ _pd_events.set (PD_IRQ_EVENT_FLAG);
255242}
256243
257- void BraccioClass::unlock_pd_semaphore ()
244+ void BraccioClass::onPowerTimerEvent ()
258245{
259- _pd_events.set (1 );
246+ _pd_events.set (PD_TIMER_EVENT_FLAG );
260247}
261248
262249/* *************************************************************************************
@@ -411,7 +398,7 @@ void BraccioClass::display_thread_func()
411398 }
412399}
413400
414- void BraccioClass::lvgl_splashScreen (unsigned long const duration_ms, std::function< void ()> check_power_func )
401+ void BraccioClass::lvgl_splashScreen (unsigned long const duration_ms)
415402{
416403 extern const lv_img_dsc_t img_bulb_gif;
417404
@@ -420,14 +407,8 @@ void BraccioClass::lvgl_splashScreen(unsigned long const duration_ms, std::funct
420407 lv_gif_set_src (img, &img_bulb_gif);
421408 lv_obj_align (img, LV_ALIGN_CENTER, 0 , 0 );
422409
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- }
410+ /* Wait until the splash screen duration is over. */
411+ for (unsigned long const start = millis (); millis () - start < duration_ms; delay (10 )) { }
431412
432413 lv_obj_del (img);
433414}
@@ -457,27 +438,40 @@ void BraccioClass::lvgl_defaultMenu()
457438
458439void BraccioClass::pd_thread_func ()
459440{
460- _start_pd_burst = millis ();
461441 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 ;
462444
463445 for (;;)
464446 {
465- auto ret = _pd_events.wait_any (0xFF );
466- if ((ret & 1 ) && (millis () - _start_pd_burst > 1000 )) {
467- _pd_timer.detach ();
468- _pd_timer.attach (braccio_unlock_pd_semaphore, 5s);
469- }
470- if (ret & 2 ) {
471- _pd_timer.detach ();
472- _pd_timer.attach (braccio_unlock_pd_semaphore, 50ms);
473- }
474- if (millis () - last_time_ask_pps > 5000 ) {
447+ /* Wait for either a timer or a IRQ event. */
448+ uint32_t const flags = _pd_events.wait_any (0xFF );
449+
450+ /* The actual calls to the PD library. */
451+ if ((millis () - last_time_ask_pps) > 5000 )
452+ {
453+ start_pd_burst = millis ();
475454 _PD_UFP.set_PPS (PPS_V (7.2 ), PPS_A (2.0 ));
476455 last_time_ask_pps = millis ();
477456 }
478457 _PD_UFP.run ();
479- if ( _PD_UFP.is_power_ready () && _PD_UFP. is_PPS_ready ()) {
458+ _PD_UFP.print_status (Serial);
480459
460+ /* Set up the next time this loop is called. */
461+ if (flags & PD_IRQ_EVENT_FLAG)
462+ {
463+ start_pd_burst = millis ();
464+ _pd_timer.detach ();
465+ _pd_timer.attach (braccio_onPowerTimerEvent, 10ms);
466+ }
467+
468+ if (flags & PD_TIMER_EVENT_FLAG)
469+ {
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);
481475 }
482476 }
483477}
@@ -539,12 +533,12 @@ extern "C" void braccio_read_keypad(lv_indev_drv_t * drv, lv_indev_data_t* data)
539533 data->key = last_key;
540534}
541535
542- void braccio_unlock_pd_semaphore_irq ()
536+ void braccio_onPowerIrqEvent ()
543537{
544- Braccio.unlock_pd_semaphore_irq ();
538+ Braccio.onPowerIrqEvent ();
545539}
546540
547- void braccio_unlock_pd_semaphore ()
541+ void braccio_onPowerTimerEvent ()
548542{
549- Braccio.unlock_pd_semaphore ();
543+ Braccio.onPowerTimerEvent ();
550544}
0 commit comments