@@ -32,7 +32,7 @@ static void processRequest() {
3232
3333template <typename Tail>
3434static void sendData (const Tail & tail) {
35- TwoWayIntegerEasyTransfer.writeByte (tail);
35+ TwoWayIntegerEasyTransfer.write (tail);
3636 TwoWayIntegerEasyTransfer.sendData ();
3737}
3838
@@ -44,26 +44,30 @@ static void requestData(const Tail & tail) {
4444
4545template <typename Head, typename ... Body>
4646static void sendData (const Head & head, const Body & ... body) {
47- TwoWayIntegerEasyTransfer.writeByte (head);
47+ TwoWayIntegerEasyTransfer.write (head);
4848 sendData (body...);
4949}
5050
5151template <typename Head, typename ... Body>
5252static void requestData (const Head & head, const Body & ... body) {
53- TwoWayIntegerEasyTransfer.writeByte (head);
53+ TwoWayIntegerEasyTransfer.write (head);
5454 requestData (body...);
5555}
5656
5757ControlBoard::ControlBoard ()
5858 : _multiplexer{ NOT_A_PIN, MUXA, MUXB, MUXC, MUXD } {
59+ _multiplexer.pinMode (MUX_IN, INPUT);
5960}
6061
6162void ControlBoard::setMode (uint8_t mode) {
62- sendData (COMMAND_SWITCH_MODE, mode);
63+ sendData (static_cast < uint8_t >( COMMAND_SWITCH_MODE) , mode);
6364}
6465
6566void 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+ );
6771}
6872
6973bool ControlBoard::isActionDone (void ) {
@@ -82,35 +86,42 @@ bool ControlBoard::isActionDone(void) {
8286void ControlBoard::lineFollowConfig (
8387 uint8_t kP , uint8_t kD ,
8488 uint8_t robotSpeedPercentage, uint8_t intergrationTimeMillis) {
85- sendData (COMMAND_LINE_FOLLOW_CONFIG,
89+ sendData (static_cast < uint8_t >( COMMAND_LINE_FOLLOW_CONFIG) ,
8690 kP , kD , robotSpeedPercentage, intergrationTimeMillis);
8791}
8892
8993void ControlBoard::motorsWrite (int speedLeft, int speedRight) {
90- sendData (COMMAND_RUN, speedLeft, speedRight);
94+ sendData (static_cast < uint8_t >( COMMAND_RUN) , speedLeft, speedRight);
9195}
9296
9397void 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+ );
95110}
96111
97112bool ControlBoard::digitalRead (TopMicrocontrollerPin pin) {
98- // TODO: set pinMode
99113 return /* Arduino*/ ::digitalRead (pin);
100114}
101115
102116bool ControlBoard::digitalRead (TopMultiplexerPin pin) {
103117 int channel = pin - T_TK0;
104- // TODO: set pinMode
105- _multiplexer.pinMode (MUX_IN, INPUT);
106118 return _multiplexer.digitalRead (channel);
107119}
108120
109121bool ControlBoard::digitalRead (BottomMicrocontrollerPin pin) {
110- // TODO: is pinMode set?
111122 static uint8_t pinCode;
112123 static uint8_t pinValue;
113- pinCode = pin;
124+ pinCode = static_cast < uint8_t >( pin) ;
114125 TwoWayIntegerEasyTransfer.attach (
115126 [](uint8_t command, IntegerEasyTransfer & request) {
116127 if ((command == COMMAND_DIGITAL_READ_RE) &&
@@ -119,37 +130,34 @@ bool ControlBoard::digitalRead(BottomMicrocontrollerPin pin) {
119130 else
120131 pinValue = 0 ;
121132 });
122- requestData (COMMAND_DIGITAL_READ, pinCode);
133+ requestData (static_cast < uint8_t >( COMMAND_DIGITAL_READ) , pinCode);
123134 return (pinValue != 0 );
124135}
125136
126- void ControlBoard::digitalWrite (TopMicrocontrollerPin pin, bool value) {
127- // TODO: set pinMode
137+ void ControlBoard::digitalWrite (TopMicrocontrollerPin pin, uint8_t value) {
128138 /* Arduino*/ ::digitalWrite (pin, value);
129139}
130140
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+ );
134146}
135147
136148int ControlBoard::analogRead (TopMicrocontrollerPin pin) {
137- // TODO: set pinMode
138149 return /* Arduino*/ ::analogRead (pin);
139150}
140151
141152int ControlBoard::analogRead (TopMultiplexerPin pin) {
142153 int channel = pin - T_TK0;
143- // TODO: set pinMode
144- _multiplexer.pinMode (MUX_IN, INPUT);
145154 return _multiplexer.analogRead (channel);
146155}
147156
148157int ControlBoard::analogRead (BottomMicrocontrollerPin pin) {
149- // TODO: is pinMode set?
150- static uint8_t pinCode = pin;
158+ static uint8_t pinCode;
151159 static int pinValue;
152- pinCode = pin;
160+ pinCode = static_cast < uint8_t >( pin) ;
153161 TwoWayIntegerEasyTransfer.attach (
154162 [](uint8_t command, IntegerEasyTransfer & request) {
155163 if ((command == COMMAND_ANALOG_READ_RE) &&
@@ -158,12 +166,11 @@ int ControlBoard::analogRead(BottomMicrocontrollerPin pin) {
158166 else
159167 pinValue = 0 ;
160168 });
161- requestData (COMMAND_ANALOG_READ, pinCode);
169+ requestData (static_cast < uint8_t >( COMMAND_ANALOG_READ) , pinCode);
162170 return pinValue;
163171}
164172
165173void ControlBoard::analogWrite (TopMicrocontrollerPin pin, uint8_t value) {
166- // TODO: set pinMode
167174 if (pin == T_TKD4)
168175 /* Arduino*/ ::analogWrite (pin, value);
169176}
@@ -182,7 +189,7 @@ uint8_t ControlBoard::updateIR(uint16_t * ir, uint8_t size) {
182189 irValues[i] = 0 ;
183190 }
184191 });
185- requestData (COMMAND_READ_IR);
192+ requestData (static_cast < uint8_t >( COMMAND_READ_IR) );
186193 memcpy (ir, irValues, maxItems * sizeof (uint16_t ));
187194 return maxItems;
188195}
@@ -196,7 +203,7 @@ int LottieLemon::ControlBoard::trimRead() {
196203 else
197204 trimmerValue = 0 ;
198205 });
199- requestData (COMMAND_READ_TRIM);
206+ requestData (static_cast < uint8_t >( COMMAND_READ_TRIM) );
200207 return trimmerValue;
201208}
202209
0 commit comments