Skip to content

Commit cc81e78

Browse files
committed
Removing __MBED__ includes, moving i2c_mutex up and renaming to _i2c_mtx.
1 parent 2f5fe58 commit cc81e78

File tree

2 files changed

+10
-13
lines changed

2 files changed

+10
-13
lines changed

src/Braccio++.cpp

Lines changed: 8 additions & 9 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{}
@@ -50,12 +51,10 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
5051

5152
pinMode(PIN_FUSB302_INT, INPUT_PULLUP);
5253

53-
#ifdef __MBED__
5454
static rtos::Thread th(osPriorityHigh);
5555
th.start(mbed::callback(this, &BraccioClass::pd_thread));
5656
attachInterrupt(PIN_FUSB302_INT, mbed::callback(this, &BraccioClass::unlock_pd_semaphore_irq), FALLING);
5757
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 10ms);
58-
#endif
5958

6059
PD_UFP.init_PPS(PPS_V(7.2), PPS_A(2.0));
6160

@@ -119,11 +118,11 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
119118
{
120119
if (!PD_UFP.is_PPS_ready())
121120
{
122-
i2c_mutex.lock();
121+
_i2c_mtx.lock();
123122
PD_UFP.print_status(Serial);
124123
PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
125124
delay(10);
126-
i2c_mutex.unlock();
125+
_i2c_mtx.unlock();
127126
}
128127
};
129128

@@ -243,13 +242,13 @@ void BraccioClass::pd_thread() {
243242
pd_timer.detach();
244243
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 50ms);
245244
}
246-
i2c_mutex.lock();
245+
_i2c_mtx.lock();
247246
if (millis() - last_time_ask_pps > 5000) {
248247
PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
249248
last_time_ask_pps = millis();
250249
}
251250
PD_UFP.run();
252-
i2c_mutex.unlock();
251+
_i2c_mtx.unlock();
253252
if (PD_UFP.is_power_ready() && PD_UFP.is_PPS_ready()) {
254253

255254
}

src/Braccio++.h

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,7 @@ class BraccioClass
7373

7474
private:
7575

76+
rtos::Mutex _i2c_mtx;
7677
RS485Class serial485;
7778
SmartServoClass servos;
7879
PD_UFP_log_c PD_UFP;
@@ -113,9 +114,8 @@ class BraccioClass
113114
void lvgl_pleaseConnectPower();
114115
void lvgl_defaultMenu();
115116

116-
#ifdef __MBED__
117+
117118
rtos::EventFlags pd_events;
118-
rtos::Mutex i2c_mutex;
119119
mbed::Ticker pd_timer;
120120

121121
unsigned int start_pd_burst = 0xFFFFFFFF;
@@ -140,8 +140,6 @@ class BraccioClass
140140
}
141141

142142
void pd_thread();
143-
#endif
144-
145143
};
146144

147145
#define Braccio BraccioClass::get_default_instance()

0 commit comments

Comments
 (0)