Skip to content

Commit 9d39167

Browse files
committed
Ensure that init_PPS is called before the first call to run().
1 parent 8c60195 commit 9d39167

File tree

1 file changed

+1
-2
lines changed

1 file changed

+1
-2
lines changed

src/Braccio++.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -98,10 +98,10 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
9898
pinMode(PIN_FUSB302_INT, INPUT_PULLUP);
9999
pinMode(RS485_RX_PIN, INPUT_PULLUP);
100100

101+
_PD_UFP.init_PPS(_i2c_mtx, PPS_V(7.2), PPS_A(2.0));
101102
_pd_thd.start(mbed::callback(this, &BraccioClass::pd_thread_func));
102103
attachInterrupt(PIN_FUSB302_INT, braccio_unlock_pd_semaphore_irq, FALLING);
103104
_pd_timer.attach(braccio_unlock_pd_semaphore, 10ms);
104-
_PD_UFP.init_PPS(_i2c_mtx, PPS_V(7.2), PPS_A(2.0));
105105

106106
button_init();
107107

@@ -477,7 +477,6 @@ void BraccioClass::pd_thread_func()
477477
}
478478
_PD_UFP.run();
479479
if (_PD_UFP.is_power_ready() && _PD_UFP.is_PPS_ready()) {
480-
481480
}
482481
}
483482
}

0 commit comments

Comments
 (0)