Skip to content

Commit 1ecf123

Browse files
authored
Merge pull request #40 from bcmi-labs/cleanup-expander
Cleanup expander code/initialisation logic.
2 parents edd8cb5 + cc81e78 commit 1ecf123

File tree

2 files changed

+49
-41
lines changed

2 files changed

+49
-41
lines changed

src/Braccio++.cpp

Lines changed: 46 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -21,15 +21,16 @@ extern "C" {
2121
using namespace std::chrono_literals;
2222

2323
BraccioClass::BraccioClass()
24-
: serial485{Serial1, 0, 7, 8} /* TX, DE, RE */
24+
: _i2c_mtx{}
25+
, serial485{Serial1, 0, 7, 8} /* TX, DE, RE */
2526
, servos{serial485}
2627
, PD_UFP{PD_LOG_LEVEL_VERBOSE}
27-
, _expander{TCA6424A_ADDRESS_ADDR_HIGH, i2c_mutex}
28+
, _expander{TCA6424A_ADDRESS_ADDR_HIGH, _i2c_mtx}
2829
, _is_ping_allowed{true}
2930
, _is_motor_connected{false}
3031
, _motors_connected_mtx{}
3132
, _motors_connected_thd{}
32-
, _bl{i2c_mutex}
33+
, _bl{_i2c_mtx}
3334
, _gfx{}
3435
, _lvgl_disp_drv{}
3536
, _lvgl_indev_drv{}
@@ -44,17 +45,16 @@ BraccioClass::BraccioClass()
4445

4546
bool BraccioClass::begin(voidFuncPtr custom_menu)
4647
{
48+
SPI.begin();
4749
Wire.begin();
4850
Serial.begin(115200);
4951

5052
pinMode(PIN_FUSB302_INT, INPUT_PULLUP);
5153

52-
#ifdef __MBED__
5354
static rtos::Thread th(osPriorityHigh);
5455
th.start(mbed::callback(this, &BraccioClass::pd_thread));
5556
attachInterrupt(PIN_FUSB302_INT, mbed::callback(this, &BraccioClass::unlock_pd_semaphore_irq), FALLING);
5657
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 10ms);
57-
#endif
5858

5959
PD_UFP.init_PPS(PPS_V(7.2), PPS_A(2.0));
6060

@@ -71,34 +71,8 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
7171
return false;
7272
_bl.turnOn();
7373

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;
10276

10377
pinMode(BTN_LEFT, INPUT_PULLUP);
10478
pinMode(BTN_RIGHT, INPUT_PULLUP);
@@ -144,11 +118,11 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
144118
{
145119
if (!PD_UFP.is_PPS_ready())
146120
{
147-
i2c_mutex.lock();
121+
_i2c_mtx.lock();
148122
PD_UFP.print_status(Serial);
149123
PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
150124
delay(10);
151-
i2c_mutex.unlock();
125+
_i2c_mtx.unlock();
152126
}
153127
};
154128

@@ -268,13 +242,13 @@ void BraccioClass::pd_thread() {
268242
pd_timer.detach();
269243
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 50ms);
270244
}
271-
i2c_mutex.lock();
245+
_i2c_mtx.lock();
272246
if (millis() - last_time_ask_pps > 5000) {
273247
PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
274248
last_time_ask_pps = millis();
275249
}
276250
PD_UFP.run();
277-
i2c_mutex.unlock();
251+
_i2c_mtx.unlock();
278252
if (PD_UFP.is_power_ready() && PD_UFP.is_PPS_ready()) {
279253

280254
}
@@ -335,6 +309,41 @@ void BraccioClass::lvgl_defaultMenu()
335309
lv_obj_set_pos(label1, 0, 0);
336310
}
337311

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+
338347
bool BraccioClass::isPingAllowed()
339348
{
340349
mbed::ScopedLock<rtos::Mutex> lock(_motors_connected_mtx);

src/Braccio++.h

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,10 +73,12 @@ class BraccioClass
7373

7474
private:
7575

76+
rtos::Mutex _i2c_mtx;
7677
RS485Class serial485;
7778
SmartServoClass servos;
7879
PD_UFP_log_c PD_UFP;
7980
TCA6424A _expander;
81+
bool expander_init();
8082

8183
bool _is_ping_allowed;
8284
bool _is_motor_connected[SmartServoClass::NUM_MOTORS];
@@ -112,9 +114,8 @@ class BraccioClass
112114
void lvgl_pleaseConnectPower();
113115
void lvgl_defaultMenu();
114116

115-
#ifdef __MBED__
117+
116118
rtos::EventFlags pd_events;
117-
rtos::Mutex i2c_mutex;
118119
mbed::Ticker pd_timer;
119120

120121
unsigned int start_pd_burst = 0xFFFFFFFF;
@@ -139,8 +140,6 @@ class BraccioClass
139140
}
140141

141142
void pd_thread();
142-
#endif
143-
144143
};
145144

146145
#define Braccio BraccioClass::get_default_instance()

0 commit comments

Comments
 (0)