Skip to content

Commit aeab746

Browse files
committed
Prefix all remaining member variables with a '_'.
1 parent 39c89b9 commit aeab746

File tree

2 files changed

+52
-52
lines changed

2 files changed

+52
-52
lines changed

src/Braccio++.cpp

Lines changed: 40 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,9 @@ using namespace std::chrono_literals;
3636

3737
BraccioClass::BraccioClass()
3838
: _i2c_mtx{}
39-
, serial485{Serial1, 0, 7, 8} /* TX, DE, RE */
40-
, servos{serial485}
41-
, PD_UFP{PD_LOG_LEVEL_VERBOSE}
39+
, _serial485{Serial1, 0, 7, 8} /* TX, DE, RE */
40+
, _servos{_serial485}
41+
, _PD_UFP{PD_LOG_LEVEL_VERBOSE}
4242
, _expander{TCA6424A_ADDRESS_ADDR_HIGH, _i2c_mtx}
4343
, _is_ping_allowed{true}
4444
, _is_motor_connected{false}
@@ -75,13 +75,13 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
7575
static rtos::Thread th(osPriorityHigh);
7676
th.start(mbed::callback(this, &BraccioClass::pd_thread));
7777
attachInterrupt(PIN_FUSB302_INT, mbed::callback(this, &BraccioClass::unlock_pd_semaphore_irq), FALLING);
78-
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 10ms);
78+
_pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 10ms);
7979

80-
PD_UFP.init_PPS(PPS_V(7.2), PPS_A(2.0));
80+
_PD_UFP.init_PPS(PPS_V(7.2), PPS_A(2.0));
8181

8282
/*
8383
while (millis() < 200) {
84-
PD_UFP.run();
84+
_PD_UFP.run();
8585
}
8686
*/
8787

@@ -97,11 +97,11 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
9797

9898
auto check_power_func = [this]()
9999
{
100-
if (!PD_UFP.is_PPS_ready())
100+
if (!_PD_UFP.is_PPS_ready())
101101
{
102102
_i2c_mtx.lock();
103-
PD_UFP.print_status(Serial);
104-
PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
103+
_PD_UFP.print_status(Serial);
104+
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
105105
delay(10);
106106
_i2c_mtx.unlock();
107107
}
@@ -110,11 +110,11 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
110110
lvgl_splashScreen(2000, check_power_func);
111111
lv_obj_clean(lv_scr_act());
112112

113-
if (!PD_UFP.is_PPS_ready())
113+
if (!_PD_UFP.is_PPS_ready())
114114
lvgl_pleaseConnectPower();
115115

116116
/* Loop forever, if no power is attached. */
117-
while(!PD_UFP.is_PPS_ready())
117+
while(!_PD_UFP.is_PPS_ready())
118118
check_power_func();
119119
lv_obj_clean(lv_scr_act());
120120

@@ -123,9 +123,9 @@ bool BraccioClass::begin(voidFuncPtr custom_menu)
123123
else
124124
lvgl_defaultMenu();
125125

126-
servos.begin();
127-
servos.setTime(SmartServoClass::BROADCAST, SLOW);
128-
servos.setPositionMode(PositionMode::IMMEDIATE);
126+
_servos.begin();
127+
_servos.setTime(SmartServoClass::BROADCAST, SLOW);
128+
_servos.setPositionMode(PositionMode::IMMEDIATE);
129129

130130
_motors_connected_thd.start(mbed::callback(this, &BraccioClass::motorConnectedThreadFunc));
131131

@@ -152,7 +152,7 @@ bool BraccioClass::connected(int const id)
152152

153153
Servo BraccioClass::move(int const id)
154154
{
155-
Servo wrapper(servos, id);
155+
Servo wrapper(_servos, id);
156156
return wrapper;
157157
}
158158

@@ -163,32 +163,32 @@ Servo BraccioClass::get(int const id)
163163

164164
void BraccioClass::moveTo(float const a1, float const a2, float const a3, float const a4, float const a5, float const a6)
165165
{
166-
servos.setPositionMode(PositionMode::SYNC);
167-
servos.setPosition(1, a1);
168-
servos.setPosition(2, a2);
169-
servos.setPosition(3, a3);
170-
servos.setPosition(4, a4);
171-
servos.setPosition(5, a5);
172-
servos.setPosition(6, a6);
173-
servos.synchronize();
174-
servos.setPositionMode(PositionMode::IMMEDIATE);
166+
_servos.setPositionMode(PositionMode::SYNC);
167+
_servos.setPosition(1, a1);
168+
_servos.setPosition(2, a2);
169+
_servos.setPosition(3, a3);
170+
_servos.setPosition(4, a4);
171+
_servos.setPosition(5, a5);
172+
_servos.setPosition(6, a6);
173+
_servos.synchronize();
174+
_servos.setPositionMode(PositionMode::IMMEDIATE);
175175
}
176176

177177
void BraccioClass::positions(float * buffer)
178178
{
179179
for (int id = SmartServoClass::MIN_MOTOR_ID; id <= SmartServoClass::MAX_MOTOR_ID; id++)
180-
*buffer++ = servos.getPosition(id);
180+
*buffer++ = _servos.getPosition(id);
181181
}
182182

183183
void BraccioClass::positions(float & a1, float & a2, float & a3, float & a4, float & a5, float & a6)
184184
{
185185
// TODO: add check if motors are actually connected
186-
a1 = servos.getPosition(1);
187-
a2 = servos.getPosition(2);
188-
a3 = servos.getPosition(3);
189-
a4 = servos.getPosition(4);
190-
a5 = servos.getPosition(5);
191-
a6 = servos.getPosition(6);
186+
a1 = _servos.getPosition(1);
187+
a2 = _servos.getPosition(2);
188+
a3 = _servos.getPosition(3);
189+
a4 = _servos.getPosition(4);
190+
a5 = _servos.getPosition(5);
191+
a6 = _servos.getPosition(6);
192192
}
193193

194194
int BraccioClass::getKey() {
@@ -313,7 +313,7 @@ void BraccioClass::motorConnectedThreadFunc()
313313
{
314314
for (int id = SmartServoClass::MIN_MOTOR_ID; id <= SmartServoClass::MAX_MOTOR_ID; id++)
315315
{
316-
bool const is_connected = (servos.ping(id) == 0);
316+
bool const is_connected = (_servos.ping(id) == 0);
317317
setMotorConnectionStatus(id, is_connected);
318318
}
319319

@@ -432,23 +432,23 @@ void BraccioClass::pd_thread() {
432432
start_pd_burst = millis();
433433
size_t last_time_ask_pps = 0;
434434
while (1) {
435-
auto ret = pd_events.wait_any(0xFF);
435+
auto ret = _pd_events.wait_any(0xFF);
436436
if ((ret & 1) && (millis() - start_pd_burst > 1000)) {
437-
pd_timer.detach();
438-
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 5s);
437+
_pd_timer.detach();
438+
_pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 5s);
439439
}
440440
if (ret & 2) {
441-
pd_timer.detach();
442-
pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 50ms);
441+
_pd_timer.detach();
442+
_pd_timer.attach(mbed::callback(this, &BraccioClass::unlock_pd_semaphore), 50ms);
443443
}
444444
_i2c_mtx.lock();
445445
if (millis() - last_time_ask_pps > 5000) {
446-
PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
446+
_PD_UFP.set_PPS(PPS_V(7.2), PPS_A(2.0));
447447
last_time_ask_pps = millis();
448448
}
449-
PD_UFP.run();
449+
_PD_UFP.run();
450450
_i2c_mtx.unlock();
451-
if (PD_UFP.is_power_ready() && PD_UFP.is_PPS_ready()) {
451+
if (_PD_UFP.is_power_ready() && _PD_UFP.is_PPS_ready()) {
452452

453453
}
454454
}

src/Braccio++.h

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -60,11 +60,11 @@ class BraccioClass
6060
void positions(float * buffer);
6161
void positions(float & a1, float & a2, float & a3, float & a4, float & a5, float & a6);
6262

63-
inline void speed(speed_grade_t const speed_grade) { servos.setTime(SmartServoClass::BROADCAST, speed_grade); }
64-
inline void speed(int const id, speed_grade_t const speed_grade) { servos.setTime(id, speed_grade); }
63+
inline void speed(speed_grade_t const speed_grade) { _servos.setTime(SmartServoClass::BROADCAST, speed_grade); }
64+
inline void speed(int const id, speed_grade_t const speed_grade) { _servos.setTime(id, speed_grade); }
6565

66-
inline void disengage(int const id = SmartServoClass::BROADCAST) { servos.disengage(id); }
67-
inline void engage (int const id = SmartServoClass::BROADCAST) { servos.engage(id); }
66+
inline void disengage(int const id = SmartServoClass::BROADCAST) { _servos.disengage(id); }
67+
inline void engage (int const id = SmartServoClass::BROADCAST) { _servos.engage(id); }
6868

6969
int getKey();
7070
void connectJoystickTo(lv_obj_t* obj);
@@ -85,16 +85,16 @@ class BraccioClass
8585

8686
protected:
8787

88-
inline void setID(int const id) { servos.setID(id); }
88+
inline void setID(int const id) { _servos.setID(id); }
8989

9090
private:
9191

9292
void button_init();
9393

9494
rtos::Mutex _i2c_mtx;
95-
RS485Class serial485;
96-
SmartServoClass servos;
97-
PD_UFP_log_c PD_UFP;
95+
RS485Class _serial485;
96+
SmartServoClass _servos;
97+
PD_UFP_log_c _PD_UFP;
9898
TCA6424A _expander;
9999
bool expander_init();
100100
void expander_setGreen(int const i);
@@ -138,18 +138,18 @@ class BraccioClass
138138
void lvgl_defaultMenu();
139139

140140

141-
rtos::EventFlags pd_events;
142-
mbed::Ticker pd_timer;
141+
rtos::EventFlags _pd_events;
142+
mbed::Ticker _pd_timer;
143143

144144
unsigned int start_pd_burst = 0xFFFFFFFF;
145145

146146
void unlock_pd_semaphore_irq() {
147147
start_pd_burst = millis();
148-
pd_events.set(2);
148+
_pd_events.set(2);
149149
}
150150

151151
void unlock_pd_semaphore() {
152-
pd_events.set(1);
152+
_pd_events.set(1);
153153
}
154154

155155
void pd_thread();

0 commit comments

Comments
 (0)