Skip to content

Commit 8091602

Browse files
committed
Move wire mutex inside PD library.
Now you don't have to set up dedicated lock/unlock code blocks around every call to the PD library.
1 parent 6c0a15e commit 8091602

File tree

5 files changed

+22
-30
lines changed

5 files changed

+22
-30
lines changed

src/Braccio++.cpp

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
101101
_pd_thd.start(mbed::callback(this, &BraccioClass::pd_thread_func));
102102
attachInterrupt(PIN_FUSB302_INT, braccio_unlock_pd_semaphore_irq, FALLING);
103103
_pd_timer.attach(braccio_unlock_pd_semaphore, 10ms);
104-
_PD_UFP.init_PPS(PPS_V(7.2), PPS_A(2.0));
104+
_PD_UFP.init_PPS(_i2c_mtx, PPS_V(7.2), PPS_A(2.0));
105105

106106
button_init();
107107

@@ -117,11 +117,9 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
117117
{
118118
if (!_PD_UFP.is_PPS_ready())
119119
{
120-
_i2c_mtx.lock();
121120
_PD_UFP.print_status(Serial);
122121
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
123122
delay(10);
124-
_i2c_mtx.unlock();
125123
}
126124
};
127125

@@ -473,13 +471,11 @@ void BraccioClass::pd_thread_func()
473471
_pd_timer.detach();
474472
_pd_timer.attach(braccio_unlock_pd_semaphore, 50ms);
475473
}
476-
_i2c_mtx.lock();
477474
if (millis() - last_time_ask_pps > 5000) {
478475
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
479476
last_time_ask_pps = millis();
480477
}
481478
_PD_UFP.run();
482-
_i2c_mtx.unlock();
483479
if (_PD_UFP.is_power_ready() && _PD_UFP.is_PPS_ready()) {
484480

485481
}

src/lib/powerdelivery/FUSB302_UFP.c renamed to src/lib/powerdelivery/FUSB302_UFP.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@
1515
*
1616
*/
1717

18-
#include <string.h>
1918
#include "FUSB302_UFP.h"
2019

2120
/* Switches0 : 02h */
@@ -248,7 +247,7 @@ enum FUSB302_state_t {
248247

249248
static inline FUSB302_ret_t reg_read(FUSB302_dev_t *dev, uint8_t address, uint8_t *data, uint8_t count)
250249
{
251-
FUSB302_ret_t ret = dev->i2c_read(dev->i2c_address, address, data, count);
250+
FUSB302_ret_t ret = dev->i2c_read(*(dev->wire_mtx), dev->i2c_address, address, data, count);
252251
if (ret != FUSB302_SUCCESS) {
253252
dev->err_msg = FUSB302_ERR_MSG("Fail to read register");
254253
}
@@ -257,7 +256,7 @@ static inline FUSB302_ret_t reg_read(FUSB302_dev_t *dev, uint8_t address, uint8_
257256

258257
static inline FUSB302_ret_t reg_write(FUSB302_dev_t *dev, uint8_t address, uint8_t *data, uint8_t count)
259258
{
260-
FUSB302_ret_t ret = dev->i2c_write(dev->i2c_address, address, data, count);
259+
FUSB302_ret_t ret = dev->i2c_write(*(dev->wire_mtx), dev->i2c_address, address, data, count);
261260
if (ret != FUSB302_SUCCESS) {
262261
dev->err_msg = FUSB302_ERR_MSG("Fail to write register");
263262
}

src/lib/powerdelivery/FUSB302_UFP.h

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,8 @@
1818
#ifndef FUSB302_UFP_H
1919
#define FUSB302_UFP_H
2020

21-
#include <stdint.h>
21+
#include <Arduino.h>
22+
#include <mbed.h>
2223

2324
enum {
2425
FUSB302_SUCCESS = 0,
@@ -39,8 +40,9 @@ typedef uint8_t FUSB302_event_t;
3940
typedef struct {
4041
/* setup by user */
4142
uint8_t i2c_address;
42-
FUSB302_ret_t (*i2c_read)(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
43-
FUSB302_ret_t (*i2c_write)(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
43+
rtos::Mutex * wire_mtx;
44+
FUSB302_ret_t (*i2c_read)(rtos::Mutex & wire_mtx, uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
45+
FUSB302_ret_t (*i2c_write)(rtos::Mutex & wire_mtx, uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
4446
FUSB302_ret_t (*delay_ms)(uint32_t t);
4547

4648
/* used by this library */

src/lib/powerdelivery/PD_UFP.cpp

Lines changed: 8 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,6 @@
1313
*
1414
*/
1515

16-
#include <stdint.h>
17-
#include <string.h>
18-
1916
#include "PD_UFP.h"
2017

2118
#define t_PD_POLLING 100
@@ -61,16 +58,12 @@ PD_UFP_core_c::PD_UFP_core_c():
6158
memset(&protocol, 0, sizeof(PD_protocol_t));
6259
}
6360

64-
void PD_UFP_core_c::init(enum PD_power_option_t power_option)
65-
{
66-
init_PPS(0, 0, power_option);
67-
}
68-
69-
void PD_UFP_core_c::init_PPS(uint16_t PPS_voltage, uint8_t PPS_current, enum PD_power_option_t power_option)
61+
void PD_UFP_core_c::init_PPS(rtos::Mutex & wire_mtx, uint16_t PPS_voltage, uint8_t PPS_current, enum PD_power_option_t power_option)
7062
{
7163
// Initialize FUSB302
7264
pinMode(PIN_FUSB302_INT, INPUT_PULLUP); // Set FUSB302 int pin input ant pull up
7365
FUSB302.i2c_address = 0x22;
66+
FUSB302.wire_mtx = &wire_mtx;
7467
FUSB302.i2c_read = FUSB302_i2c_read;
7568
FUSB302.i2c_write = FUSB302_i2c_write;
7669
FUSB302.delay_ms = FUSB302_delay_ms;
@@ -127,8 +120,10 @@ void PD_UFP_core_c::clock_prescale_set(uint8_t prescaler)
127120
}
128121
}
129122

130-
FUSB302_ret_t PD_UFP_core_c::FUSB302_i2c_read(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count)
123+
FUSB302_ret_t PD_UFP_core_c::FUSB302_i2c_read(rtos::Mutex & wire_mtx, uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count)
131124
{
125+
mbed::ScopedLock<rtos::Mutex> lock(wire_mtx);
126+
132127
Wire.beginTransmission(dev_addr);
133128
Wire.write(reg_addr);
134129
Wire.endTransmission();
@@ -140,8 +135,10 @@ FUSB302_ret_t PD_UFP_core_c::FUSB302_i2c_read(uint8_t dev_addr, uint8_t reg_addr
140135
return count == 0 ? FUSB302_SUCCESS : FUSB302_ERR_READ_DEVICE;
141136
}
142137

143-
FUSB302_ret_t PD_UFP_core_c::FUSB302_i2c_write(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count)
138+
FUSB302_ret_t PD_UFP_core_c::FUSB302_i2c_write(rtos::Mutex & wire_mtx, uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count)
144139
{
140+
mbed::ScopedLock<rtos::Mutex> lock(wire_mtx);
141+
145142
Wire.beginTransmission(dev_addr);
146143
Wire.write(reg_addr);
147144
while (count > 0) {

src/lib/powerdelivery/PD_UFP.h

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -16,16 +16,15 @@
1616
#ifndef PD_UFP_H
1717
#define PD_UFP_H
1818

19-
#include <stdint.h>
20-
2119
#include <Arduino.h>
2220
#include <Wire.h>
2321
#include <HardwareSerial.h>
2422

2523
#define PIN_FUSB302_INT A2
2624

27-
extern "C" {
28-
#include "FUSB302_UFP.h"
25+
#include "FUSB302_UFP.h"
26+
extern "C"
27+
{
2928
#include "PD_UFP_Protocol.h"
3029
}
3130

@@ -64,8 +63,7 @@ class PD_UFP_core_c
6463
public:
6564
PD_UFP_core_c();
6665
// Init
67-
void init(enum PD_power_option_t power_option = PD_POWER_OPTION_MAX_5V);
68-
void init_PPS(uint16_t PPS_voltage, uint8_t PPS_current, enum PD_power_option_t power_option = PD_POWER_OPTION_MAX_5V);
66+
void init_PPS(rtos::Mutex & wire_mtx, uint16_t PPS_voltage, uint8_t PPS_current, enum PD_power_option_t power_option = PD_POWER_OPTION_MAX_5V);
6967
// Task
7068
void run(void);
7169
// Status
@@ -82,8 +80,8 @@ class PD_UFP_core_c
8280
static void clock_prescale_set(uint8_t prescaler);
8381

8482
protected:
85-
static FUSB302_ret_t FUSB302_i2c_read(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
86-
static FUSB302_ret_t FUSB302_i2c_write(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
83+
static FUSB302_ret_t FUSB302_i2c_read(rtos::Mutex & wire_mtx, uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
84+
static FUSB302_ret_t FUSB302_i2c_write(rtos::Mutex & wire_mtx, uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint8_t count);
8785
static FUSB302_ret_t FUSB302_delay_ms(uint32_t t);
8886
void handle_protocol_event(PD_protocol_event_t events);
8987
void handle_FUSB302_event(FUSB302_event_t events);

0 commit comments

Comments
 (0)