Skip to content

Commit fb4aca7

Browse files
committed
Issue #22: Fix en envío de envio y recepción de datos en arduino
Se arreglan bug en el firmware que no permitia la ejecución de varios comandos consecutivos (i.e. más de un comando en el buffer de entrada) Se arregla bug que asignaba como puerto analógico a un puerto digital.
1 parent ba4eafb commit fb4aca7

File tree

3 files changed

+75
-42
lines changed

3 files changed

+75
-42
lines changed

MLC/arduino/Firmware/Firmware.ino

Lines changed: 41 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -14,12 +14,12 @@ const uint8_t SET_REPORT_MODE_CMD = 0x05;
1414
const uint8_t ACTUATE_CMD = 0xF0;
1515

1616
// Commands executor caller -- one vector position == one command
17-
void (*executor[255])(const char*);
17+
int (*executor[255])(const char*);
1818

19-
void not_implemented(const char* data)
19+
int not_implemented(const char* data)
2020
{
2121
//nothing to do...
22-
return;
22+
return 0;
2323
}
2424

2525
typedef enum ReportModes {average, bulk, rt};
@@ -39,7 +39,7 @@ const char* ACK = "\xFF\x00";
3939
/**
4040
ANALOG_PRECISION: 0x01 0x01 [BITS]
4141
*/
42-
void set_analog_precision(const char* data)
42+
int set_analog_precision(const char* data)
4343
{
4444
int i = byte(data[2]);
4545
// Tal vez conviene separar estas funciones ya que hay boards con resoluciones distintas...
@@ -48,55 +48,67 @@ void set_analog_precision(const char* data)
4848
analogReadResolution(i);
4949

5050
LOG("Resolution changed to: ", i);
51+
52+
return 3; // Command of 3 bytes
5153
}
5254

5355
/**
5456
PIN_MODE: 0x04 0x02 [PIN] [MODE]
5557
*/
56-
void set_pin_mode(const char* data)
58+
int set_pin_mode(const char* data)
5759
{
5860
pinMode(data[2], data[3]);
5961
LOG("Changed pin mode on pin ", uint8_t(data[2]));
6062
LOG("Mode set to ", uint8_t(data[3]));
63+
64+
return 4; // Command of 4 bytes
6165
}
6266

6367
/**
6468
REPORT_MODE: 0x05 0x03 [MODE] [READ_COUNT] [READ_DELAY]
6569
*/
66-
void set_report_mode(const char* data)
70+
int set_report_mode(const char* data)
6771
{
6872
REPORT_MODE = (ReportModes)(data[2]);
6973
REPORT_READ_COUNT = byte(data[3]);
7074
REPORT_READ_DELAY = byte(data[4]);
7175
LOG("Report mode changed on port ", byte(data[3]));
76+
77+
return 5; // Command of 5 bytes
7278
}
7379

7480
/**
7581
ANALOG_INPUT: 0x02 0x01 [PORT]
7682
*/
77-
void set_analog_input(const char* data)
83+
int set_analog_input(const char* data)
7884
{
7985
INPUT_PORTS[0] += 1;
8086
INPUT_PORTS[INPUT_PORTS[0]] = byte(data[2]);
8187
LOG("New analog input: ", byte(data[2]));
88+
89+
return 3; // Command of 3 bytes
8290
}
8391

8492
/**
8593
* ANALOG_OUTPUT: 0x03 0x01 [PORT]
8694
*/
87-
void set_analog_output(const char* data)
95+
int set_analog_output(const char* data)
8896
{
8997
// No se si vale la pena guardar registro de pines de salida...
98+
99+
return 3; // Command of 3 bytes
90100
}
91101

92102
/**
93-
* ACTUATE: 0xF0 [PIN_COUNT] [PIN_A] [VALUE_PIN_A] ... [PIN_N] [VALUE_PIN_N]
103+
* ACTUATE: 0xF0 [DATA_LEN] [PIN_A] [VALUE_PIN_A] ... [PIN_N] [VALUE_PIN_N]
94104
*/
95-
void actuate(const char* data)
105+
int actuate(const char* data)
96106
{
97107
int offset = 0;
98108
int byte_count = byte(data[1]); // Un byte puede llegar a limitar la cantidad de salidas... creo
99109

110+
LOG("Actutating over payload of size: ", byte_count);
111+
100112
// ACTUATION ZONE
101113
while (offset < byte_count)
102114
{
@@ -130,7 +142,7 @@ void actuate(const char* data)
130142
{
131143
if ( INPUT_PORTS[i] >= A0 )
132144
{
133-
int data = analogRead(INPUT_PORTS[i]);
145+
int data = analogRead(INPUT_PORTS[i]-A0);
134146
response[len + 1] = byte((data & 0xFF00) >> 8); // Se guarda el msb en el buffer
135147
response[len + 2] = byte(data & 0xFF); // Se guarda el lsb en el buffer
136148

@@ -148,13 +160,15 @@ void actuate(const char* data)
148160

149161
response[1] = len - 1;
150162
SerialUSB.write(response, len + 2); // 2 bytes extras por el id de comando y la longitud
163+
164+
return offset + 2;
151165
}
152166

153167
void setup() {
154168
SerialUSB.begin(115200);
155169

156170
#ifdef DEBUG
157-
Serial.begin(57600);
171+
Serial.begin(115200);
158172
#endif
159173

160174
for (int i = 0; i < 255; i++)
@@ -172,29 +186,30 @@ void setup() {
172186
executor[SET_REPORT_MODE_CMD] = &set_report_mode;
173187
executor[ACTUATE_CMD] = &actuate;
174188

175-
executor[ANALOG_PRECISION_CMD]("\x01\x01\x12");
176-
executor[ADD_INPUT_PORT_CMD]("\x02\x01\x37"); // Configura a A1 como lectura
177-
executor[ADD_INPUT_PORT_CMD]("\x02\x01\x38"); // Configura a A2 como lectura
178-
executor[SET_PIN_MODE_CMD]("\x04\x02\x28\x01");
179-
executor[SET_PIN_MODE_CMD]("\x04\x02\x55\x00");
180-
181189
}
182190

183191
void loop() {
184-
LOG("Escribiendo...", " ");
185-
executor[ACTUATE_CMD]("\xF0\x01\x28\x01");
192+
//executor[ACTUATE_CMD]("\xF0\x01\x28\x01");
186193

187194
if (SerialUSB.available() > 0)
188195
{
196+
LOG("USB serial data available ", SerialUSB.available());
189197
char input[64]; // Esto se reserva en el stack, tal vez hacerlo global consume menos recursos...
190-
198+
199+
byte b_read = 0;
200+
byte b_pos = 0;
201+
191202
while (SerialUSB.available() > 0)
192203
{
193-
SerialUSB.readBytes(input, SerialUSB.available());
204+
b_read += SerialUSB.readBytes(input, SerialUSB.available());
205+
}
206+
207+
// Loop to process all commands received in the buffer
208+
while(b_pos < b_read)
209+
{
210+
LOG("Executing command: ", int(input[b_pos]));
211+
b_pos += executor[input[b_pos]](&input[b_pos]); // Does the callback for the command
212+
LOG("b_pos ", b_pos);
194213
}
195-
196-
executor[input[0]](input); // Does the callback for the command
197214
}
198-
199-
delay(5000);
200215
}

MLC/arduino/connection/serialconnection.py

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,15 @@
44

55
class SerialConnection(BaseConnection):
66
def __init__(self, **args):
7+
""" Starts a serial connection
8+
9+
Keyword arguments:
10+
port -- connection to the device. In Linux: /dev/ttyXXX On Windows: COMX. This options is mandatory!
11+
baudrates -- baurates of the connection. By default will be set to 115200
12+
parity -- parity check bits from pySerial. By default it is set to PARITY_ONE. Available options: PARITY_EVEN, PARITY_ODD, PARITY_MARK & PARITY_SPACE
13+
stopbits -- stop bits from pySerial. By default it is set to STOPBITS_ONE. Available options: STOPBITS_ONE_POINT_FIVE & STOPBITS_TWO
14+
bytesize -- byte size from pySerial. By default it is set to EIGHTBITS. Available options: FIVEBITS, SIXBITS & SEVENBITS
15+
"""
716
if "port" not in args.keys():
817
raise Exception("Port is mandatory!")
918

@@ -19,4 +28,10 @@ def send(self, data):
1928
self._connection.write(data)
2029

2130
def recv(self, length):
31+
""" Receives the specified amount of bytes
32+
WARNING: This function is blocked until receive the amount of bytes
33+
34+
Keyword arguments:
35+
length -- amount of bytes to receive
36+
"""
2237
return self._connection.read(length)

MLC/arduino/protocol.py

Lines changed: 19 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,11 @@
11

22
_PROTOCOL_CMDS = { "ANALOG_PRECISION": '\x01\x01%s',
33
"SET_INPUT" : '\x02\x01%s',
4-
"PIN_OUTPUT" : '\x03\x01%s',
4+
"SET_OUTPUT" : '\x03\x01%s',
55
"PIN_MODE" : '\x04\x02%s%s',
66
"REPORT_MODE" : '\x05\x03%s%s%s',
77
"ACK" : '\xFF\x00',
8-
"ACTUATE" : '\xF0%s',
8+
"ACTUATE" : '\xF0',
99
"ACTUATE_REPORT" : '\xF1' }
1010

1111
class ArduinoInterface:
@@ -27,9 +27,9 @@ def set_precition(self, bits):
2727
self._connection.send(_PROTOCOL_CMDS["ANALOG_PRECISION"] % chr(bits))
2828
self._anlg_precition = bits
2929

30-
def set_pin_mode(self, port, mode):
30+
def __set_pin_mode(self, port, mode):
3131
if mode not in self.PIN_MOD.keys():
32-
raise Exception("Pind mode error. Unknown mode: %s. Modes availables: %s " % (mode, str(PIN_MOD.keys())))
32+
raise Exception("Pind mode error. Unknown mode: %s. Modes availables: %s " % (mode, str(self.PIN_MOD.keys())))
3333

3434
self._connection.send(_PROTOCOL_CMDS["PIN_MODE"] % (chr(port), chr(self.PIN_MOD[mode])))
3535

@@ -44,36 +44,35 @@ def add_input(self, port):
4444
if port in self._anlg_outputs or port in self._digital_outputs:
4545
raise Exception("Pin %s is configured as output!" % port)
4646

47-
self._validate_pin(port)
47+
self.__validate_pin(port)
48+
self._connection.send(_PROTOCOL_CMDS["SET_INPUT"] % chr(port))
49+
self.__set_pin_mode(port, "INPUT")
4850

4951
# Determines if we are setting as input an analog port
5052
if port not in self._anlg_inputs and port in self._board["ANALOG_PINS"]:
51-
# The "analogRead" arduino function maps the ADC pins not by their base pin number but from their relative ADC pin number
52-
self._connection.send(_PROTOCOL_CMDS["SET_INPUT"] % chr(port - min(self._board["ANALOG_PINS"])))
5353
self._anlg_inputs.append(port)
5454

5555
# Determines if we are setting as input a Digital port
5656
if port not in self._digital_inputs and port in self._board["DIGITAL_PINS"]:
57-
self._connection.send(_PROTOCOL_CMDS["SET_INPUT"] % chr(port))
5857
self._digital_inputs.append(port)
5958

6059

6160
def add_output(self, port):
6261
if port in self._anlg_inputs or port in self._digital_inputs:
6362
raise Exception("Port %s is configured as input!" % port)
6463

65-
self._validate_pin(port)
64+
self.__validate_pin(port)
65+
self._connection.send(_PROTOCOL_CMDS["SET_OUTPUT"] % chr(port))
66+
self.__set_pin_mode(port, "OUTPUT")
6667

67-
if port not in self._anlg_outputs:
68-
self._connection.send(_PROTOCOL_CMDS["PIN_OUTPUT"] % chr(port))
68+
if port not in self._anlg_outputs and port in self._board["ANALOG_PINS"]:
6969
self._anlg_outputs.append(port)
7070

7171
# Determines if we are setting as input a Digital port
7272
if port not in self._digital_outputs and port in self._board["DIGITAL_PINS"]:
73-
self._connection.send(_PROTOCOL_CMDS["PIN_OUTPUT"] % chr(port))
7473
self._digital_outputs.append(port)
7574

76-
def _validate_pin(self, pin):
75+
def __validate_pin(self, pin):
7776
if pin not in self._board["DIGITAL_PINS"] and pin not in self._board["ANALOG_PINS"]:
7877
raise Exception("Invalid pin %s for board %s" % (pin, self._board["NAME"]))
7978
return
@@ -88,7 +87,8 @@ def actuate(self, data):
8887
"""
8988
payload = ""
9089
size = 0
91-
#TODO: Ver como validar puertos digitales
90+
91+
# Sets as payload every digital or analog port
9292
for i in data:
9393
if i[0] not in self._anlg_outputs and i[0] not in self._digital_outputs:
9494
raise Exception("Port %s not configured as output!" % i[0])
@@ -119,8 +119,11 @@ def actuate(self, data):
119119
results.append((data[pos], (ord(data[pos+1]) << 8) + ord(data[pos+2])))
120120
pos = pos + 3
121121
else:
122-
results.append((data[pos], bool(ord(data[pos+1]))))
123-
pos = pos + 2
122+
if ord(data[pos]) in self._digital_inputs:
123+
results.append((data[pos], bool(ord(data[pos+1]))))
124+
pos = pos + 2
125+
else:
126+
raise Exception("Unknown port in response. Restart Arduino board, your software and pray")
124127

125128
return results
126129

0 commit comments

Comments
 (0)