@@ -312,6 +312,10 @@ void BraccioClass::lvgl_defaultMenu()
312312
313313bool BraccioClass::expander_init ()
314314{
315+ static uint16_t constexpr EXPANDER_RS485_SLEW_PIN = 21 ; /* P25 = 8 * 2 + 5 = 21 */
316+ static uint16_t constexpr EXPANDER_RS485_TERM_PIN = 19 ; /* P23 = 8 * 2 + 3 = 19 */
317+ static uint16_t constexpr EXPANDER_RS485_RST_DP_PIN = 18 ; /* P22 = 8 * 2 + 2 = 18 */
318+
315319 if (!_expander.testConnection ())
316320 return false ;
317321
@@ -321,17 +325,17 @@ bool BraccioClass::expander_init()
321325 }
322326
323327 /* Set SLEW to low */
324- _expander.setPinDirection (21 , 0 ); // P25 = 8 * 2 + 5
325- _expander.writePin (21 , 0 );
328+ _expander.setPinDirection (EXPANDER_RS485_SLEW_PIN , 0 );
329+ _expander.writePin (EXPANDER_RS485_SLEW_PIN , 0 );
326330
327331 /* Set TERM to HIGH (default) */
328- _expander.setPinDirection (19 , 0 ); // P23 = 8 * 2 + 3
329- _expander.writePin (19 , 1 );
332+ _expander.setPinDirection (EXPANDER_RS485_TERM_PIN , 0 );
333+ _expander.writePin (EXPANDER_RS485_TERM_PIN , 1 );
330334
331335 /* Reset GLCD */
332- _expander.setPinDirection (18 , 0 ); // P22 = 8 * 2 + 2
333- _expander.writePin (18 , 0 ); // reset LCD
334- _expander.writePin (18 , 1 ); // LCD out of reset
336+ _expander.setPinDirection (EXPANDER_RS485_RST_DP_PIN , 0 ); // P22 = 8 * 2 + 2
337+ _expander.writePin (EXPANDER_RS485_RST_DP_PIN , 0 ); // reset LCD
338+ _expander.writePin (EXPANDER_RS485_RST_DP_PIN , 1 ); // LCD out of reset
335339
336340 /* Set all motor status LEDs to red. */
337341 for (int id = SmartServoClass::MIN_MOTOR_ID; id <= SmartServoClass::MAX_MOTOR_ID; id++) {
0 commit comments