@@ -32,7 +32,7 @@ static void processRequest() {
32
32
33
33
template <typename Tail>
34
34
static void sendData (const Tail & tail) {
35
- TwoWayIntegerEasyTransfer.writeByte (tail);
35
+ TwoWayIntegerEasyTransfer.write (tail);
36
36
TwoWayIntegerEasyTransfer.sendData ();
37
37
}
38
38
@@ -44,26 +44,30 @@ static void requestData(const Tail & tail) {
44
44
45
45
template <typename Head, typename ... Body>
46
46
static void sendData (const Head & head, const Body & ... body) {
47
- TwoWayIntegerEasyTransfer.writeByte (head);
47
+ TwoWayIntegerEasyTransfer.write (head);
48
48
sendData (body...);
49
49
}
50
50
51
51
template <typename Head, typename ... Body>
52
52
static void requestData (const Head & head, const Body & ... body) {
53
- TwoWayIntegerEasyTransfer.writeByte (head);
53
+ TwoWayIntegerEasyTransfer.write (head);
54
54
requestData (body...);
55
55
}
56
56
57
57
ControlBoard::ControlBoard ()
58
58
: _multiplexer{ NOT_A_PIN, MUXA, MUXB, MUXC, MUXD } {
59
+ _multiplexer.pinMode (MUX_IN, INPUT);
59
60
}
60
61
61
62
void ControlBoard::setMode (uint8_t mode) {
62
- sendData (COMMAND_SWITCH_MODE, mode);
63
+ sendData (static_cast < uint8_t >( COMMAND_SWITCH_MODE) , mode);
63
64
}
64
65
65
66
void ControlBoard::pauseMode (bool isPaused) {
66
- sendData (COMMAND_PAUSE_MODE, isPaused);
67
+ sendData (
68
+ static_cast <uint8_t >(COMMAND_PAUSE_MODE),
69
+ static_cast <uint8_t >(isPaused)
70
+ );
67
71
}
68
72
69
73
bool ControlBoard::isActionDone (void ) {
@@ -82,35 +86,42 @@ bool ControlBoard::isActionDone(void) {
82
86
void ControlBoard::lineFollowConfig (
83
87
uint8_t kP , uint8_t kD ,
84
88
uint8_t robotSpeedPercentage, uint8_t intergrationTimeMillis) {
85
- sendData (COMMAND_LINE_FOLLOW_CONFIG,
89
+ sendData (static_cast < uint8_t >( COMMAND_LINE_FOLLOW_CONFIG) ,
86
90
kP , kD , robotSpeedPercentage, intergrationTimeMillis);
87
91
}
88
92
89
93
void ControlBoard::motorsWrite (int speedLeft, int speedRight) {
90
- sendData (COMMAND_RUN, speedLeft, speedRight);
94
+ sendData (static_cast < uint8_t >( COMMAND_RUN) , speedLeft, speedRight);
91
95
}
92
96
93
97
void ControlBoard::motorsStop (void ) {
94
- sendData (COMMAND_MOTORS_STOP);
98
+ sendData (static_cast <uint8_t >(COMMAND_MOTORS_STOP));
99
+ }
100
+
101
+ void ControlBoard::pinMode (TopMicrocontrollerPin pin, uint8_t value) {
102
+ /* Arduino*/ ::pinMode (pin, value);
103
+ }
104
+
105
+ void ControlBoard::pinMode (BottomMicrocontrollerPin pin, uint8_t value) {
106
+ sendData (
107
+ static_cast <uint8_t >(COMMAND_PIN_MODE),
108
+ static_cast <uint8_t >(pin), value
109
+ );
95
110
}
96
111
97
112
bool ControlBoard::digitalRead (TopMicrocontrollerPin pin) {
98
- // TODO: set pinMode
99
113
return /* Arduino*/ ::digitalRead (pin);
100
114
}
101
115
102
116
bool ControlBoard::digitalRead (TopMultiplexerPin pin) {
103
117
int channel = pin - T_TK0;
104
- // TODO: set pinMode
105
- _multiplexer.pinMode (MUX_IN, INPUT);
106
118
return _multiplexer.digitalRead (channel);
107
119
}
108
120
109
121
bool ControlBoard::digitalRead (BottomMicrocontrollerPin pin) {
110
- // TODO: is pinMode set?
111
122
static uint8_t pinCode;
112
123
static uint8_t pinValue;
113
- pinCode = pin;
124
+ pinCode = static_cast < uint8_t >( pin) ;
114
125
TwoWayIntegerEasyTransfer.attach (
115
126
[](uint8_t command, IntegerEasyTransfer & request) {
116
127
if ((command == COMMAND_DIGITAL_READ_RE) &&
@@ -119,37 +130,34 @@ bool ControlBoard::digitalRead(BottomMicrocontrollerPin pin) {
119
130
else
120
131
pinValue = 0 ;
121
132
});
122
- requestData (COMMAND_DIGITAL_READ, pinCode);
133
+ requestData (static_cast < uint8_t >( COMMAND_DIGITAL_READ) , pinCode);
123
134
return (pinValue != 0 );
124
135
}
125
136
126
- void ControlBoard::digitalWrite (TopMicrocontrollerPin pin, bool value) {
127
- // TODO: set pinMode
137
+ void ControlBoard::digitalWrite (TopMicrocontrollerPin pin, uint8_t value) {
128
138
/* Arduino*/ ::digitalWrite (pin, value);
129
139
}
130
140
131
- void ControlBoard::digitalWrite (BottomMicrocontrollerPin pin, bool value) {
132
- // TODO: is pinMode set?
133
- sendData (COMMAND_DIGITAL_WRITE, pin, value);
141
+ void ControlBoard::digitalWrite (BottomMicrocontrollerPin pin, uint8_t value) {
142
+ sendData (
143
+ static_cast <uint8_t >(COMMAND_DIGITAL_WRITE),
144
+ static_cast <uint8_t >(pin), value
145
+ );
134
146
}
135
147
136
148
int ControlBoard::analogRead (TopMicrocontrollerPin pin) {
137
- // TODO: set pinMode
138
149
return /* Arduino*/ ::analogRead (pin);
139
150
}
140
151
141
152
int ControlBoard::analogRead (TopMultiplexerPin pin) {
142
153
int channel = pin - T_TK0;
143
- // TODO: set pinMode
144
- _multiplexer.pinMode (MUX_IN, INPUT);
145
154
return _multiplexer.analogRead (channel);
146
155
}
147
156
148
157
int ControlBoard::analogRead (BottomMicrocontrollerPin pin) {
149
- // TODO: is pinMode set?
150
- static uint8_t pinCode = pin;
158
+ static uint8_t pinCode;
151
159
static int pinValue;
152
- pinCode = pin;
160
+ pinCode = static_cast < uint8_t >( pin) ;
153
161
TwoWayIntegerEasyTransfer.attach (
154
162
[](uint8_t command, IntegerEasyTransfer & request) {
155
163
if ((command == COMMAND_ANALOG_READ_RE) &&
@@ -158,12 +166,11 @@ int ControlBoard::analogRead(BottomMicrocontrollerPin pin) {
158
166
else
159
167
pinValue = 0 ;
160
168
});
161
- requestData (COMMAND_ANALOG_READ, pinCode);
169
+ requestData (static_cast < uint8_t >( COMMAND_ANALOG_READ) , pinCode);
162
170
return pinValue;
163
171
}
164
172
165
173
void ControlBoard::analogWrite (TopMicrocontrollerPin pin, uint8_t value) {
166
- // TODO: set pinMode
167
174
if (pin == T_TKD4)
168
175
/* Arduino*/ ::analogWrite (pin, value);
169
176
}
@@ -182,7 +189,7 @@ uint8_t ControlBoard::updateIR(uint16_t * ir, uint8_t size) {
182
189
irValues[i] = 0 ;
183
190
}
184
191
});
185
- requestData (COMMAND_READ_IR);
192
+ requestData (static_cast < uint8_t >( COMMAND_READ_IR) );
186
193
memcpy (ir, irValues, maxItems * sizeof (uint16_t ));
187
194
return maxItems;
188
195
}
@@ -196,7 +203,7 @@ int LottieLemon::ControlBoard::trimRead() {
196
203
else
197
204
trimmerValue = 0 ;
198
205
});
199
- requestData (COMMAND_READ_TRIM);
206
+ requestData (static_cast < uint8_t >( COMMAND_READ_TRIM) );
200
207
return trimmerValue;
201
208
}
202
209
0 commit comments