@@ -42,8 +42,8 @@ extern "C"
42
42
{
43
43
void braccio_disp_flush (lv_disp_drv_t *disp, const lv_area_t *area, lv_color_t *color_p);
44
44
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 ();
47
47
};
48
48
49
49
/* *************************************************************************************
@@ -77,7 +77,6 @@ BraccioClass::BraccioClass()
77
77
, _display_thd{}
78
78
, _pd_events{}
79
79
, _pd_timer{}
80
- , _start_pd_burst{0xFFFFFFFF }
81
80
, _pd_thd{osPriorityHigh}
82
81
{
83
82
@@ -98,10 +97,10 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
98
97
pinMode (PIN_FUSB302_INT, INPUT_PULLUP);
99
98
pinMode (RS485_RX_PIN, INPUT_PULLUP);
100
99
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);
104
100
_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);
105
104
106
105
button_init ();
107
106
@@ -112,26 +111,14 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
112
111
lvgl_init ();
113
112
_display_thd.start (mbed::callback (this , &BraccioClass::display_thread_func));
114
113
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 );
127
115
lv_obj_clean (lv_scr_act ());
128
116
129
117
if (!_PD_UFP.is_PPS_ready ())
130
118
lvgl_pleaseConnectPower ();
131
119
132
120
/* 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 ()) { }
135
122
lv_obj_clean (lv_scr_act ());
136
123
137
124
if (custom_menu)
@@ -248,15 +235,14 @@ void BraccioClass::lvgl_disp_flush(lv_disp_drv_t *disp, const lv_area_t *area, l
248
235
lv_disp_flush_ready (disp);
249
236
}
250
237
251
- void BraccioClass::unlock_pd_semaphore_irq ()
238
+ void BraccioClass::onPowerIrqEvent ()
252
239
{
253
- _start_pd_burst = millis ();
254
- _pd_events.set (2 );
240
+ _pd_events.set (PD_IRQ_EVENT_FLAG);
255
241
}
256
242
257
- void BraccioClass::unlock_pd_semaphore ()
243
+ void BraccioClass::onPowerTimerEvent ()
258
244
{
259
- _pd_events.set (1 );
245
+ _pd_events.set (PD_TIMER_EVENT_FLAG );
260
246
}
261
247
262
248
/* *************************************************************************************
@@ -411,7 +397,7 @@ void BraccioClass::display_thread_func()
411
397
}
412
398
}
413
399
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)
415
401
{
416
402
extern const lv_img_dsc_t img_bulb_gif;
417
403
@@ -420,14 +406,8 @@ void BraccioClass::lvgl_splashScreen(unsigned long const duration_ms, std::funct
420
406
lv_gif_set_src (img, &img_bulb_gif);
421
407
lv_obj_align (img, LV_ALIGN_CENTER, 0 , 0 );
422
408
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 )) { }
431
411
432
412
lv_obj_del (img);
433
413
}
@@ -457,27 +437,31 @@ void BraccioClass::lvgl_defaultMenu()
457
437
458
438
void BraccioClass::pd_thread_func ()
459
439
{
460
- _start_pd_burst = millis ();
461
440
size_t last_time_ask_pps = 0 ;
462
441
463
442
for (;;)
464
443
{
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
+ {
467
448
_pd_timer.detach ();
468
- _pd_timer.attach (braccio_unlock_pd_semaphore, 5s );
449
+ _pd_timer.attach (braccio_onPowerTimerEvent, 10ms );
469
450
}
470
- if (ret & 2 ) {
451
+
452
+ if (flags & PD_TIMER_EVENT_FLAG)
453
+ {
471
454
_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);
477
456
}
457
+
478
458
_PD_UFP.run ();
479
- if ( _PD_UFP.is_power_ready () && _PD_UFP. is_PPS_ready ()) {
459
+ _PD_UFP.print_status (Serial);
480
460
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 ();
481
465
}
482
466
}
483
467
}
@@ -539,12 +523,12 @@ extern "C" void braccio_read_keypad(lv_indev_drv_t * drv, lv_indev_data_t* data)
539
523
data->key = last_key;
540
524
}
541
525
542
- void braccio_unlock_pd_semaphore_irq ()
526
+ void braccio_onPowerIrqEvent ()
543
527
{
544
- Braccio.unlock_pd_semaphore_irq ();
528
+ Braccio.onPowerIrqEvent ();
545
529
}
546
530
547
- void braccio_unlock_pd_semaphore ()
531
+ void braccio_onPowerTimerEvent ()
548
532
{
549
- Braccio.unlock_pd_semaphore ();
533
+ Braccio.onPowerTimerEvent ();
550
534
}
0 commit comments