@@ -21,15 +21,16 @@ extern "C" {
21
21
using namespace std ::chrono_literals;
22
22
23
23
BraccioClass::BraccioClass ()
24
- : serial485{Serial1, 0 , 7 , 8 } /* TX, DE, RE */
24
+ : _i2c_mtx{}
25
+ , serial485{Serial1, 0 , 7 , 8 } /* TX, DE, RE */
25
26
, servos{serial485}
26
27
, PD_UFP{PD_LOG_LEVEL_VERBOSE}
27
- , _expander{TCA6424A_ADDRESS_ADDR_HIGH, i2c_mutex }
28
+ , _expander{TCA6424A_ADDRESS_ADDR_HIGH, _i2c_mtx }
28
29
, _is_ping_allowed{true }
29
30
, _is_motor_connected{false }
30
31
, _motors_connected_mtx{}
31
32
, _motors_connected_thd{}
32
- , _bl{i2c_mutex }
33
+ , _bl{_i2c_mtx }
33
34
, _gfx{}
34
35
, _lvgl_disp_drv{}
35
36
, _lvgl_indev_drv{}
@@ -44,17 +45,16 @@ BraccioClass::BraccioClass()
44
45
45
46
bool BraccioClass::begin (voidFuncPtr custom_menu)
46
47
{
48
+ SPI.begin ();
47
49
Wire.begin ();
48
50
Serial.begin (115200 );
49
51
50
52
pinMode (PIN_FUSB302_INT, INPUT_PULLUP);
51
53
52
- #ifdef __MBED__
53
54
static rtos::Thread th (osPriorityHigh);
54
55
th.start (mbed::callback (this , &BraccioClass::pd_thread));
55
56
attachInterrupt (PIN_FUSB302_INT, mbed::callback (this , &BraccioClass::unlock_pd_semaphore_irq), FALLING);
56
57
pd_timer.attach (mbed::callback (this , &BraccioClass::unlock_pd_semaphore), 10ms);
57
- #endif
58
58
59
59
PD_UFP.init_PPS (PPS_V (7.2 ), PPS_A (2.0 ));
60
60
@@ -71,34 +71,8 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
71
71
return false ;
72
72
_bl.turnOn ();
73
73
74
- SPI.begin ();
75
-
76
- int ret = _expander.testConnection ();
77
-
78
- if (ret == false ) {
79
- return ret;
80
- }
81
-
82
- for (int i = 0 ; i < 14 ; i++) {
83
- _expander.setPinDirection (i, 0 );
84
- }
85
-
86
- // Set SLEW to low
87
- _expander.setPinDirection (21 , 0 ); // P25 = 8 * 2 + 5
88
- _expander.writePin (21 , 0 );
89
-
90
- // Set TERM to HIGH (default)
91
- _expander.setPinDirection (19 , 0 ); // P23 = 8 * 2 + 3
92
- _expander.writePin (19 , 1 );
93
-
94
- _expander.setPinDirection (18 , 0 ); // P22 = 8 * 2 + 2
95
- _expander.writePin (18 , 0 ); // reset LCD
96
- _expander.writePin (18 , 1 ); // LCD out of reset
97
-
98
- /* Set all motor status LEDs to red. */
99
- for (int id = SmartServoClass::MIN_MOTOR_ID; id <= SmartServoClass::MAX_MOTOR_ID; id++) {
100
- setRed (id);
101
- }
74
+ if (!expander_init ())
75
+ return false ;
102
76
103
77
pinMode (BTN_LEFT, INPUT_PULLUP);
104
78
pinMode (BTN_RIGHT, INPUT_PULLUP);
@@ -144,11 +118,11 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
144
118
{
145
119
if (!PD_UFP.is_PPS_ready ())
146
120
{
147
- i2c_mutex .lock ();
121
+ _i2c_mtx .lock ();
148
122
PD_UFP.print_status (Serial);
149
123
PD_UFP.set_PPS (PPS_V (7.2 ), PPS_A (2.0 ));
150
124
delay (10 );
151
- i2c_mutex .unlock ();
125
+ _i2c_mtx .unlock ();
152
126
}
153
127
};
154
128
@@ -268,13 +242,13 @@ void BraccioClass::pd_thread() {
268
242
pd_timer.detach ();
269
243
pd_timer.attach (mbed::callback (this , &BraccioClass::unlock_pd_semaphore), 50ms);
270
244
}
271
- i2c_mutex .lock ();
245
+ _i2c_mtx .lock ();
272
246
if (millis () - last_time_ask_pps > 5000 ) {
273
247
PD_UFP.set_PPS (PPS_V (7.2 ), PPS_A (2.0 ));
274
248
last_time_ask_pps = millis ();
275
249
}
276
250
PD_UFP.run ();
277
- i2c_mutex .unlock ();
251
+ _i2c_mtx .unlock ();
278
252
if (PD_UFP.is_power_ready () && PD_UFP.is_PPS_ready ()) {
279
253
280
254
}
@@ -335,6 +309,41 @@ void BraccioClass::lvgl_defaultMenu()
335
309
lv_obj_set_pos (label1, 0 , 0 );
336
310
}
337
311
312
+ bool BraccioClass::expander_init ()
313
+ {
314
+ static uint16_t constexpr EXPANDER_RS485_SLEW_PIN = 21 ; /* P25 = 8 * 2 + 5 = 21 */
315
+ static uint16_t constexpr EXPANDER_RS485_TERM_PIN = 19 ; /* P23 = 8 * 2 + 3 = 19 */
316
+ static uint16_t constexpr EXPANDER_RS485_RST_DP_PIN = 18 ; /* P22 = 8 * 2 + 2 = 18 */
317
+
318
+ if (!_expander.testConnection ())
319
+ return false ;
320
+
321
+ /* Init IO expander outputs of RGB LEDs */
322
+ for (int i = 0 ; i < 14 ; i++) {
323
+ _expander.setPinDirection (i, 0 );
324
+ }
325
+
326
+ /* Set SLEW to low */
327
+ _expander.setPinDirection (EXPANDER_RS485_SLEW_PIN, 0 );
328
+ _expander.writePin (EXPANDER_RS485_SLEW_PIN, 0 );
329
+
330
+ /* Set TERM to HIGH (default) */
331
+ _expander.setPinDirection (EXPANDER_RS485_TERM_PIN, 0 );
332
+ _expander.writePin (EXPANDER_RS485_TERM_PIN, 1 );
333
+
334
+ /* Reset GLCD */
335
+ _expander.setPinDirection (EXPANDER_RS485_RST_DP_PIN, 0 ); // P22 = 8 * 2 + 2
336
+ _expander.writePin (EXPANDER_RS485_RST_DP_PIN, 0 ); // reset LCD
337
+ _expander.writePin (EXPANDER_RS485_RST_DP_PIN, 1 ); // LCD out of reset
338
+
339
+ /* Set all motor status LEDs to red. */
340
+ for (int id = SmartServoClass::MIN_MOTOR_ID; id <= SmartServoClass::MAX_MOTOR_ID; id++) {
341
+ setRed (id);
342
+ }
343
+
344
+ return true ;
345
+ }
346
+
338
347
bool BraccioClass::isPingAllowed ()
339
348
{
340
349
mbed::ScopedLock<rtos::Mutex> lock (_motors_connected_mtx);
0 commit comments