Skip to content

Commit 7eb5a26

Browse files
committed
Naming fixed and pause ping
1 parent ae89c74 commit 7eb5a26

File tree

2 files changed

+23
-19
lines changed

2 files changed

+23
-19
lines changed

src/Braccio++.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,8 @@ class BraccioClass {
7474

7575
TFT_eSPI gfx = TFT_eSPI();
7676

77+
bool ping_allowed = true;
78+
7779
protected:
7880
// ioexpander APIs
7981
void digitalWrite(int pin, uint8_t value);
@@ -116,7 +118,7 @@ class BraccioClass {
116118

117119
#ifdef __MBED__
118120
rtos::EventFlags pd_events;
119-
rtos::Mutex pd_mutex;
121+
rtos::Mutex i2c_mutex;
120122
mbed::Ticker pd_timer;
121123

122124
unsigned int start_pd_burst = 0xFFFFFFFF;

src/Braccio.cpp

Lines changed: 20 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ bool BraccioClass::begin(voidFuncPtr customMenu) {
3737

3838
SPI.begin();
3939

40-
pd_mutex.lock();
40+
i2c_mutex.lock();
4141
bl.begin();
4242
if (bl.getChipID() != 0xCE) {
4343
return false;
@@ -65,7 +65,7 @@ bool BraccioClass::begin(voidFuncPtr customMenu) {
6565
expander.setPinDirection(18, 0); // P22 = 8 * 2 + 2
6666
expander.writePin(18, 0); // reset LCD
6767
expander.writePin(18, 1); // LCD out of reset
68-
pd_mutex.unlock();
68+
i2c_mutex.unlock();
6969

7070
pinMode(BTN_LEFT, INPUT_PULLUP);
7171
pinMode(BTN_RIGHT, INPUT_PULLUP);
@@ -120,11 +120,11 @@ bool BraccioClass::begin(voidFuncPtr customMenu) {
120120

121121
PD_UFP.print_status(Serial);
122122
while (!PD_UFP.is_PPS_ready()) {
123-
pd_mutex.lock();
123+
i2c_mutex.lock();
124124
PD_UFP.print_status(Serial);
125125
//PD_UFP.print_status(Serial);
126126
PD_UFP.init_PPS(PPS_V(7.2), PPS_A(2.0));
127-
pd_mutex.unlock();
127+
i2c_mutex.unlock();
128128
}
129129

130130
#ifdef __MBED__
@@ -158,9 +158,9 @@ void BraccioClass::pd_thread() {
158158
pd_timer.detach();
159159
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 0.05f);
160160
}
161-
pd_mutex.lock();
161+
i2c_mutex.lock();
162162
PD_UFP.run();
163-
pd_mutex.unlock();
163+
i2c_mutex.unlock();
164164
if (PD_UFP.is_power_ready() && PD_UFP.is_PPS_ready()) {
165165

166166
}
@@ -201,18 +201,20 @@ void BraccioClass::defaultMenu() {
201201

202202
void BraccioClass::motors_connected_thread() {
203203
while (1) {
204-
for (int i = 1; i < 7; i++) {
205-
_connected[i] = (servos->ping(i) == 0);
206-
//Serial.print(String(i) + ": ");
207-
//Serial.println(_connected[i]);
208-
pd_mutex.lock();
209-
if (_connected[i]) {
210-
setGreen(i);
211-
} else {
212-
setRed(i);
213-
}
214-
pd_mutex.unlock();
215-
}
204+
if (ping_allowed) {
205+
for (int i = 1; i < 7; i++) {
206+
_connected[i] = (servos->ping(i) == 0);
207+
//Serial.print(String(i) + ": ");
208+
//Serial.println(_connected[i]);
209+
i2c_mutex.lock();
210+
if (_connected[i]) {
211+
setGreen(i);
212+
} else {
213+
setRed(i);
214+
}
215+
i2c_mutex.unlock();
216+
}
217+
}
216218
delay(1000);
217219
}
218220
}

0 commit comments

Comments
 (0)