-
Notifications
You must be signed in to change notification settings - Fork 1
/
Msg.cpp
752 lines (696 loc) · 20.4 KB
/
Msg.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
/**
* <pre>
*
Welcome to Msg.java
Its created by running ArduinoMsgGenerator
which combines the MrlComm message schema (src/resource/Arduino/arduinoMsg.schema)
with the cpp template (src/resource/Arduino/generate/Msg.template.cpp)
Schema Type Conversions
Schema ARDUINO Java Range
none byte/unsigned char int (cuz Java byte bites) 1 byte - 0 to 255
boolean boolean boolean 0 1
b16 int int (short) 2 bytes -32,768 to 32,767
b32 long int 4 bytes -2,147,483,648 to 2,147,483, 647
bu32 unsigned long long 0 to 4,294,967,295
str char*, size String variable length
[] byte[], size int[] variable length
All message editing should be done in the arduinoMsg.schema
The binary wire format of an Arduino is:
MAGIC_NUMBER|MSG_SIZE|METHOD_NUMBER|PARAM0|PARAM1 ...
</pre>
*/
#include "Msg.h"
#include "LinkedList.h"
#include "MrlComm.h"
Msg* Msg::instance = NULL;
Msg::Msg() {
this->mrlComm = mrlComm;
}
Msg::~Msg() {
}
// the two singleton methods - the one with the MrlComm paramters
// must be used for initialization
Msg* Msg::getInstance(MrlComm* mrlComm) {
instance = new Msg();
instance->mrlComm = mrlComm;
return instance;
}
Msg* Msg::getInstance() {
return instance;
}
/**
* Expected Interface - these are the method signatures which will be called
* by Msg class
*
* PC --serialized--> Msg --de-serialized--> MrlComm.method(parm0, param1, ...)
*
// > getBoardInfo
void getBoardInfo();
// > enableBoardStatus/bool enabled
void enableBoardStatus( boolean enabled);
// > enablePin/address/type/b16 rate
void enablePin( byte address, byte type, int rate);
// > setDebug/bool enabled
void setDebug( boolean enabled);
// > setSerialRate/b32 rate
void setSerialRate( long rate);
// > softReset
void softReset();
// > enableAck/bool enabled
void enableAck( boolean enabled);
// > enableHeartbeat/bool enabled
void enableHeartbeat( boolean enabled);
// > heartbeat
void heartbeat();
// > echo/bu32 sInt
void echo( unsigned long sInt);
// > controllerAttach/serialPort
void controllerAttach( byte serialPort);
// > customMsg/[] msg
void customMsg( byte msgSize, const byte*msg);
// > deviceDetach/deviceId
void deviceDetach( byte deviceId);
// > i2cBusAttach/deviceId/i2cBus
void i2cBusAttach( byte deviceId, byte i2cBus);
// > i2cRead/deviceId/deviceAddress/size
void i2cRead( byte deviceId, byte deviceAddress, byte size);
// > i2cWrite/deviceId/deviceAddress/[] data
void i2cWrite( byte deviceId, byte deviceAddress, byte dataSize, const byte*data);
// > i2cWriteRead/deviceId/deviceAddress/readSize/writeValue
void i2cWriteRead( byte deviceId, byte deviceAddress, byte readSize, byte writeValue);
// > neoPixelAttach/deviceId/pin/b32 numPixels
void neoPixelAttach( byte deviceId, byte pin, long numPixels);
// > neoPixelSetAnimation/deviceId/animation/red/green/blue/b16 speed
void neoPixelSetAnimation( byte deviceId, byte animation, byte red, byte green, byte blue, int speed);
// > neoPixelWriteMatrix/deviceId/[] buffer
void neoPixelWriteMatrix( byte deviceId, byte bufferSize, const byte*buffer);
// > disablePin/pin
void disablePin( byte pin);
// > disablePins
void disablePins();
// > setTrigger/pin/triggerValue
void setTrigger( byte pin, byte triggerValue);
// > setDebounce/pin/delay
void setDebounce( byte pin, byte delay);
// > servoAttach/deviceId/pin/initPos/b16 initVelocity
void servoAttach( byte deviceId, byte pin, byte initPos, int initVelocity);
// > servoEnablePwm/deviceId/pin
void servoEnablePwm( byte deviceId, byte pin);
// > servoDisablePwm/deviceId
void servoDisablePwm( byte deviceId);
// > servoSetMaxVelocity/deviceId/b16 maxVelocity
void servoSetMaxVelocity( byte deviceId, int maxVelocity);
// > servoSetVelocity/deviceId/b16 velocity
void servoSetVelocity( byte deviceId, int velocity);
// > servoSweepStart/deviceId/min/max/step
void servoSweepStart( byte deviceId, byte min, byte max, byte step);
// > servoSweepStop/deviceId
void servoSweepStop( byte deviceId);
// > servoWrite/deviceId/target
void servoWrite( byte deviceId, byte target);
// > servoWriteMicroseconds/deviceId/b16 ms
void servoWriteMicroseconds( byte deviceId, int ms);
// > serialAttach/deviceId/relayPin
void serialAttach( byte deviceId, byte relayPin);
// > serialRelay/deviceId/[] data
void serialRelay( byte deviceId, byte dataSize, const byte*data);
// > ultrasonicSensorAttach/deviceId/triggerPin/echoPin
void ultrasonicSensorAttach( byte deviceId, byte triggerPin, byte echoPin);
// > ultrasonicSensorStartRanging/deviceId/b32 timeout
void ultrasonicSensorStartRanging( byte deviceId, long timeout);
// > ultrasonicSensorStopRanging/deviceId
void ultrasonicSensorStopRanging( byte deviceId);
*/
void Msg::publishMRLCommError(const char* errorMsg, byte errorMsgSize) {
write(MAGIC_NUMBER);
write(1 + (1 + errorMsgSize)); // size
write(PUBLISH_MRLCOMM_ERROR); // msgType = 1
write((byte*)errorMsg, errorMsgSize);
flush();
reset();
}
void Msg::publishBoardInfo( byte version, byte boardType) {
write(MAGIC_NUMBER);
write(1 + 1 + 1); // size
write(PUBLISH_BOARD_INFO); // msgType = 3
write(version);
write(boardType);
flush();
reset();
}
void Msg::publishAck( byte function) {
write(MAGIC_NUMBER);
write(1 + 1); // size
write(PUBLISH_ACK); // msgType = 10
write(function);
flush();
reset();
}
void Msg::publishHeartbeat() {
write(MAGIC_NUMBER);
write(1); // size
write(PUBLISH_HEARTBEAT); // msgType = 13
flush();
reset();
}
void Msg::publishEcho( unsigned long sInt) {
write(MAGIC_NUMBER);
write(1 + 4); // size
write(PUBLISH_ECHO); // msgType = 15
writebu32(sInt);
flush();
reset();
}
void Msg::publishCustomMsg(const byte* msg, byte msgSize) {
write(MAGIC_NUMBER);
write(1 + (1 + msgSize)); // size
write(PUBLISH_CUSTOM_MSG); // msgType = 18
write((byte*)msg, msgSize);
flush();
reset();
}
void Msg::publishI2cData( byte deviceId, const byte* data, byte dataSize) {
write(MAGIC_NUMBER);
write(1 + 1 + (1 + dataSize)); // size
write(PUBLISH_I2C_DATA); // msgType = 24
write(deviceId);
write((byte*)data, dataSize);
flush();
reset();
}
void Msg::publishAttachedDevice( byte deviceId, const char* deviceName, byte deviceNameSize) {
write(MAGIC_NUMBER);
write(1 + 1 + (1 + deviceNameSize)); // size
write(PUBLISH_ATTACHED_DEVICE); // msgType = 33
write(deviceId);
write((byte*)deviceName, deviceNameSize);
flush();
reset();
}
void Msg::publishBoardStatus( int microsPerLoop, int sram, const byte* deviceSummary, byte deviceSummarySize) {
write(MAGIC_NUMBER);
write(1 + 2 + 2 + (1 + deviceSummarySize)); // size
write(PUBLISH_BOARD_STATUS); // msgType = 34
writeb16(microsPerLoop);
writeb16(sram);
write((byte*)deviceSummary, deviceSummarySize);
flush();
reset();
}
void Msg::publishDebug(const char* debugMsg, byte debugMsgSize) {
write(MAGIC_NUMBER);
write(1 + (1 + debugMsgSize)); // size
write(PUBLISH_DEBUG); // msgType = 35
write((byte*)debugMsg, debugMsgSize);
flush();
reset();
}
void Msg::publishPinArray(const byte* data, byte dataSize) {
write(MAGIC_NUMBER);
write(1 + (1 + dataSize)); // size
write(PUBLISH_PIN_ARRAY); // msgType = 36
write((byte*)data, dataSize);
flush();
reset();
}
void Msg::publishSerialData( byte deviceId, const byte* data, byte dataSize) {
write(MAGIC_NUMBER);
write(1 + 1 + (1 + dataSize)); // size
write(PUBLISH_SERIAL_DATA); // msgType = 50
write(deviceId);
write((byte*)data, dataSize);
flush();
reset();
}
void Msg::publishUltrasonicSensorData( byte deviceId, int echoTime) {
write(MAGIC_NUMBER);
write(1 + 1 + 2); // size
write(PUBLISH_ULTRASONIC_SENSOR_DATA); // msgType = 54
write(deviceId);
writeb16(echoTime);
flush();
reset();
}
void Msg::processCommand() {
int startPos = 0;
int method = ioCmd[0];
switch (method) {
case GET_BOARD_INFO: { // getBoardInfo
mrlComm->getBoardInfo();
break;
}
case ENABLE_BOARD_STATUS: { // enableBoardStatus
boolean enabled = (ioCmd[startPos+1]);
startPos += 1;
mrlComm->enableBoardStatus( enabled);
break;
}
case ENABLE_PIN: { // enablePin
byte address = ioCmd[startPos+1]; // bu8
startPos += 1;
byte type = ioCmd[startPos+1]; // bu8
startPos += 1;
int rate = b16(ioCmd, startPos+1);
startPos += 2; //b16
mrlComm->enablePin( address, type, rate);
break;
}
case SET_DEBUG: { // setDebug
boolean enabled = (ioCmd[startPos+1]);
startPos += 1;
mrlComm->setDebug( enabled);
break;
}
case SET_SERIAL_RATE: { // setSerialRate
long rate = b32(ioCmd, startPos+1);
startPos += 4; //b32
mrlComm->setSerialRate( rate);
break;
}
case SOFT_RESET: { // softReset
mrlComm->softReset();
break;
}
case ENABLE_ACK: { // enableAck
boolean enabled = (ioCmd[startPos+1]);
startPos += 1;
mrlComm->enableAck( enabled);
break;
}
case ENABLE_HEARTBEAT: { // enableHeartbeat
boolean enabled = (ioCmd[startPos+1]);
startPos += 1;
mrlComm->enableHeartbeat( enabled);
break;
}
case HEARTBEAT: { // heartbeat
mrlComm->heartbeat();
break;
}
case ECHO: { // echo
unsigned long sInt = bu32(ioCmd, startPos+1);
startPos += 4; //bu32
mrlComm->echo( sInt);
break;
}
case CONTROLLER_ATTACH: { // controllerAttach
byte serialPort = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->controllerAttach( serialPort);
break;
}
case CUSTOM_MSG: { // customMsg
const byte* msg = ioCmd+startPos+2;
byte msgSize = ioCmd[startPos+1];
startPos += 1 + ioCmd[startPos+1];
mrlComm->customMsg( msgSize, msg);
break;
}
case DEVICE_DETACH: { // deviceDetach
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->deviceDetach( deviceId);
break;
}
case I2C_BUS_ATTACH: { // i2cBusAttach
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte i2cBus = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->i2cBusAttach( deviceId, i2cBus);
break;
}
case I2C_READ: { // i2cRead
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte deviceAddress = ioCmd[startPos+1]; // bu8
startPos += 1;
byte size = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->i2cRead( deviceId, deviceAddress, size);
break;
}
case I2C_WRITE: { // i2cWrite
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte deviceAddress = ioCmd[startPos+1]; // bu8
startPos += 1;
const byte* data = ioCmd+startPos+2;
byte dataSize = ioCmd[startPos+1];
startPos += 1 + ioCmd[startPos+1];
mrlComm->i2cWrite( deviceId, deviceAddress, dataSize, data);
break;
}
case I2C_WRITE_READ: { // i2cWriteRead
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte deviceAddress = ioCmd[startPos+1]; // bu8
startPos += 1;
byte readSize = ioCmd[startPos+1]; // bu8
startPos += 1;
byte writeValue = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->i2cWriteRead( deviceId, deviceAddress, readSize, writeValue);
break;
}
case NEO_PIXEL_ATTACH: { // neoPixelAttach
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
long numPixels = b32(ioCmd, startPos+1);
startPos += 4; //b32
mrlComm->neoPixelAttach( deviceId, pin, numPixels);
break;
}
case NEO_PIXEL_SET_ANIMATION: { // neoPixelSetAnimation
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte animation = ioCmd[startPos+1]; // bu8
startPos += 1;
byte red = ioCmd[startPos+1]; // bu8
startPos += 1;
byte green = ioCmd[startPos+1]; // bu8
startPos += 1;
byte blue = ioCmd[startPos+1]; // bu8
startPos += 1;
int speed = b16(ioCmd, startPos+1);
startPos += 2; //b16
mrlComm->neoPixelSetAnimation( deviceId, animation, red, green, blue, speed);
break;
}
case NEO_PIXEL_WRITE_MATRIX: { // neoPixelWriteMatrix
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
const byte* buffer = ioCmd+startPos+2;
byte bufferSize = ioCmd[startPos+1];
startPos += 1 + ioCmd[startPos+1];
mrlComm->neoPixelWriteMatrix( deviceId, bufferSize, buffer);
break;
}
case ANALOG_WRITE: { // analogWrite
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte value = ioCmd[startPos+1]; // bu8
startPos += 1;
analogWrite( pin, value);
break;
}
case DIGITAL_WRITE: { // digitalWrite
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte value = ioCmd[startPos+1]; // bu8
startPos += 1;
digitalWrite( pin, value);
break;
}
case DISABLE_PIN: { // disablePin
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->disablePin( pin);
break;
}
case DISABLE_PINS: { // disablePins
mrlComm->disablePins();
break;
}
case PIN_MODE: { // pinMode
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte mode = ioCmd[startPos+1]; // bu8
startPos += 1;
pinMode( pin, mode);
break;
}
case SET_TRIGGER: { // setTrigger
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte triggerValue = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->setTrigger( pin, triggerValue);
break;
}
case SET_DEBOUNCE: { // setDebounce
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte delay = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->setDebounce( pin, delay);
break;
}
case SERVO_ATTACH: { // servoAttach
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte initPos = ioCmd[startPos+1]; // bu8
startPos += 1;
int initVelocity = b16(ioCmd, startPos+1);
startPos += 2; //b16
mrlComm->servoAttach( deviceId, pin, initPos, initVelocity);
break;
}
case SERVO_ENABLE_PWM: { // servoEnablePwm
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte pin = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->servoEnablePwm( deviceId, pin);
break;
}
case SERVO_DISABLE_PWM: { // servoDisablePwm
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->servoDisablePwm( deviceId);
break;
}
case SERVO_SET_MAX_VELOCITY: { // servoSetMaxVelocity
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
int maxVelocity = b16(ioCmd, startPos+1);
startPos += 2; //b16
mrlComm->servoSetMaxVelocity( deviceId, maxVelocity);
break;
}
case SERVO_SET_VELOCITY: { // servoSetVelocity
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
int velocity = b16(ioCmd, startPos+1);
startPos += 2; //b16
mrlComm->servoSetVelocity( deviceId, velocity);
break;
}
case SERVO_SWEEP_START: { // servoSweepStart
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte min = ioCmd[startPos+1]; // bu8
startPos += 1;
byte max = ioCmd[startPos+1]; // bu8
startPos += 1;
byte step = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->servoSweepStart( deviceId, min, max, step);
break;
}
case SERVO_SWEEP_STOP: { // servoSweepStop
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->servoSweepStop( deviceId);
break;
}
case SERVO_WRITE: { // servoWrite
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte target = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->servoWrite( deviceId, target);
break;
}
case SERVO_WRITE_MICROSECONDS: { // servoWriteMicroseconds
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
int ms = b16(ioCmd, startPos+1);
startPos += 2; //b16
mrlComm->servoWriteMicroseconds( deviceId, ms);
break;
}
case SERIAL_ATTACH: { // serialAttach
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte relayPin = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->serialAttach( deviceId, relayPin);
break;
}
case SERIAL_RELAY: { // serialRelay
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
const byte* data = ioCmd+startPos+2;
byte dataSize = ioCmd[startPos+1];
startPos += 1 + ioCmd[startPos+1];
mrlComm->serialRelay( deviceId, dataSize, data);
break;
}
case ULTRASONIC_SENSOR_ATTACH: { // ultrasonicSensorAttach
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
byte triggerPin = ioCmd[startPos+1]; // bu8
startPos += 1;
byte echoPin = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->ultrasonicSensorAttach( deviceId, triggerPin, echoPin);
break;
}
case ULTRASONIC_SENSOR_START_RANGING: { // ultrasonicSensorStartRanging
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
long timeout = b32(ioCmd, startPos+1);
startPos += 4; //b32
mrlComm->ultrasonicSensorStartRanging( deviceId, timeout);
break;
}
case ULTRASONIC_SENSOR_STOP_RANGING: { // ultrasonicSensorStopRanging
byte deviceId = ioCmd[startPos+1]; // bu8
startPos += 1;
mrlComm->ultrasonicSensorStopRanging( deviceId);
break;
}
default:
publishError("unknown method " + String(method));
break;
} // end switch
// ack that we got a command (should we ack it first? or after we process the command?)
lastHeartbeatUpdate = millis();
publishAck(ioCmd[0]);
} // process Command
void Msg::add(const int value) {
sendBuffer[sendBufferSize] = (value & 0xFF);
sendBufferSize += 1;
}
void Msg::add16(const int value) {
sendBuffer[sendBufferSize] = ((value >> 8) & 0xFF);
sendBuffer[sendBufferSize + 1] = (value & 0xFF);
sendBufferSize += 2;
}
void Msg::add(unsigned long value) {
sendBuffer[sendBufferSize] = ((value >> 24) & 0xFF);
sendBuffer[sendBufferSize + 1] = ((value >> 16) & 0xFF);
sendBuffer[sendBufferSize + 2] = ((value >> 8) & 0xFF);
sendBuffer[sendBufferSize + 3] = (value & 0xFF);
sendBufferSize += 4;
}
int Msg::b16(const byte* buffer, const int start/*=0*/) {
return (buffer[start] << 8) + buffer[start + 1];
}
long Msg::b32(const byte* buffer, const int start/*=0*/) {
long result = 0;
for (int i = 0; i < 4; i++) {
result <<= 8;
result |= (buffer[start + i] & 0xFF);
}
return result;
}
unsigned long Msg::bu32(const byte* buffer, const int start/*=0*/) {
unsigned long result = 0;
for (int i = 0; i < 4; i++) {
result <<= 8;
result |= (buffer[start + i] & 0xFF);
}
return result;
}
void Msg::publishError(const String& message) {
publishMRLCommError(message.c_str(), message.length());
}
void Msg::publishDebug(const String& message) {
if (debug){
publishDebug(message.c_str(), message.length());
}
}
bool Msg::readMsg() {
// handle serial data begin
int bytesAvailable = serial->available();
if (bytesAvailable > 0) {
//publishDebug("RXBUFF:" + String(bytesAvailable));
// now we should loop over the available bytes .. not just read one by one.
for (int i = 0; i < bytesAvailable; i++) {
// read the incoming byte:
unsigned char newByte = serial->read();
//publishDebug("RX:" + String(newByte));
++byteCount;
// checking first byte - beginning of message?
if (byteCount == 1 && newByte != MAGIC_NUMBER) {
publishError(F("error serial"));
// reset - try again
byteCount = 0;
// return false;
}
if (byteCount == 2) {
// get the size of message
// todo check msg < 64 (MAX_MSG_SIZE)
if (newByte > 64) {
// TODO - send error back
byteCount = 0;
continue; // GroG - I guess we continue now vs return false on error conditions?
}
msgSize = newByte;
}
if (byteCount > 2) {
// fill in msg data - (2) headbytes -1 (offset)
ioCmd[byteCount - 3] = newByte;
}
// if received header + msg
if (byteCount == 2 + msgSize) {
// we've reach the end of the command, just return true .. we've got it
byteCount = 0;
return true;
}
}
} // if Serial.available
// we only partially read a command. (or nothing at all.)
return false;
}
void Msg::write(const unsigned char value) {
serial->write(value);
}
void Msg::write(const unsigned char* buffer, int len) {
serial->write(len);
serial->write(buffer, len);
}
void Msg::writebool(const bool value){
if (value){
write(0);
} else {
write(1);
}
}
void Msg::writeb16(const int b16){
write(b16 >> 8 & 0xFF);
write(b16 & 0xFF);
}
void Msg::writeb32(const long b32){
write(b32 >> 24 & 0xFF);
write(b32 >> 16 & 0xFF);
write(b32 >> 8 & 0xFF);
write(b32 & 0xFF);
}
void Msg::writebu32(const unsigned long bu32){
write(bu32 >> 24 & 0xFF);
write(bu32 >> 16 & 0xFF);
write(bu32 >> 8 & 0xFF);
write(bu32 & 0xFF);
}
byte* Msg::getBuffer() {
return sendBuffer;
}
int Msg::getBufferSize() {
return sendBufferSize;
}
void Msg::reset() {
sendBufferSize = 0;
}
void Msg::flush() {
return serial->flush();
}
void Msg::begin(HardwareSerial& hardwareSerial){
serial = &hardwareSerial;
}