Newer
Older
getSurreal
committed
<<<<<<< HEAD
getSurreal
committed
=======
getSurreal
committed
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
Copyright 2014 James LeRoy getSurreal
https://github.com/getSurreal/XV_Lidar_Controller
<<<<<<< HEAD
Modified to add CRC checking - Doug Hilton, WD0UG November, 2015 mailto: six.speed (at) yahoo (dot) com
See README for additional information
=======
James LeRoy
committed
James LeRoy
committed
The F() macro in the Serial statements tells the compiler to keep your strings in PROGMEM
#include <TimerThree.h> // used for ultrasonic PWM motor control
<<<<<<< HEAD
const int SHOW_ALL_ANGLES = 360; // value means 'display all angle data, 0..359'
=======
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
James LeRoy
committed
char version[6];
int motor_pwm_pin; // pin connected to mosfet for motor speed control
double rpm_setpoint; // desired RPM (uses double to be compatible with PID library)
double rpm_min;
double rpm_max;
double pwm_max; // max analog value. probably never needs to change from 1023
double pwm_min; // min analog pulse value to spin the motor
int sample_time; // how often to calculate the PID values
boolean motor_enable; // to spin the laser or not. No data when not spinning
boolean raw_data; // to retransmit the seiral data to the USB port
boolean show_dist; // controlled by ShowDist and HideDist commands
boolean show_rpm; // controlled by ShowRPM and HideRPM commands
James LeRoy
committed
unsigned int show_angle; // controlled by ShowAngle (0 - 359, 360 shows all)
getSurreal
committed
<<<<<<< HEAD
/*
* EEPROM_ID
* Used to validate that the EEPROM is initialized
* Important to increment the number anytime variables are added or removed
* or when the default values are changed
*/
const byte EEPROM_ID = 0x05;
getSurreal
committed
=======
getSurreal
committed
const byte EEPROM_ID = 0x05; // used to validate EEPROM initialized
getSurreal
committed
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
unsigned long now;
unsigned long motor_check_timer = millis();
getSurreal
committed
<<<<<<< HEAD
getSurreal
committed
=======
getSurreal
committed
unsigned long motor_check_interval = 200;
getSurreal
committed
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
unsigned int rpm_err_thresh = 10; // 2 seconds (10 * 200ms) to shutdown motor with improper RPM and high voltage
unsigned int rpm_err = 0;
James LeRoy
committed
unsigned long curMillis;
unsigned long lastMillis = millis();
PID rpmPID(&motor_rpm, &pwm_val, &xv_config.rpm_setpoint, xv_config.Kp, xv_config.Ki, xv_config.Kd, DIRECT);
uint8_t inByte = 0; // incoming serial byte
<<<<<<< HEAD
uint8_t motor_rph_high_byte = 0;
uint8_t motor_rph_low_byte = 0;
uint16_t dist[N_DATA_QUADS] = {0, 0, 0, 0}; // thre are (4) distances, one for each data quad
uint16_t quality[N_DATA_QUADS] = {0, 0, 0, 0}; // same with 'quality'
=======
uint16_t data_status = 0;
uint16_t data_4deg_index = 0;
uint16_t data_loop_index = 0;
uint8_t motor_rph_high_byte = 0;
uint8_t motor_rph_low_byte = 0;
uint8_t data0, data2;
uint16_t dist, quality;
uint16_t motor_rph = 0;
uint16_t angle;
#if defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY) // if Teensy 2.0
const int ledPin = 11;
#endif
#if defined(__MK20DX256__) // if Teensy 3.1
const int ledPin = 13;
#endif
James LeRoy
committed
boolean ledState = LOW;
if ( xv_config.id != EEPROM_ID) { // verify EEPROM values have been initialized
<<<<<<< HEAD
pinMode(xv_config.motor_pwm_pin, OUTPUT);
Serial.begin(115200); // USB serial
Serial1.begin(115200); // XV LDS data
/*
* Timer3.initialize(30)
* sets PWM frequency to 32.768kHz for quite ultrasonic motor control
* PWM duty cycle is 0-1023
*/
Timer3.initialize(30);
=======
#if defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY) // if Teensy 2.0
Serial1.begin(115200); // XV LDS data
#endif
#if defined(__MK20DX256__) // if Teensy 3.1
Timer3.initialize(30); // set PWM frequency to 32.768kHz
rpmPID.SetOutputLimits(xv_config.pwm_min, xv_config.pwm_max);
rpmPID.SetSampleTime(xv_config.sample_time);
rpmPID.SetTunings(xv_config.Kp, xv_config.Ki, xv_config.Kd);
rpmPID.SetMode(AUTOMATIC);
James LeRoy
committed
pinMode(ledPin, OUTPUT);
<<<<<<< HEAD
eState = eState_Find_COMMAND;
for (ixPacket = 0; ixPacket < PACKET_LENGTH; ixPacket++) // Initialize
Packet[ixPacket] = 0;
ixPacket = 0;
=======
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
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
<<<<<<< HEAD
boolean bPacketOkay; // true = packet is okay (CRC valid)
sCmd.readSerial(); // check for incoming serial commands
if (Serial1.available() > 0) { // read byte from LIDAR and relay to USB
inByte = Serial1.read(); // get incoming byte:
if (xv_config.raw_data)
Serial.print(inByte, BYTE); // relay
// Switch, based on 'eState':
// State 1: We're scanning for 0xFA (COMMAND) in the input stream
// State 2: Build a complete data packet
if (eState == eState_Find_COMMAND) { // flush input until we get COMMAND byte
if (inByte == COMMAND) {
eState++; // switch to 'build a packet' state
Packet[ixPacket++] = inByte; // store 1st byte of data into 'Packet'
}
}
else { // eState == eState_Build_Packet
Packet[ixPacket++] = inByte; // keep storing input into 'Packet'
if (ixPacket == PACKET_LENGTH) { // we've got all the input bytes, so we're done building this packet
bPacketOkay = (eValidatePacket() == 0); // Check packet CRC
startingAngle = processIndex(bPacketOkay); // get the starting angle of this group (of 4)
processSpeed(bPacketOkay); // process the speed
// process each of the (4) sets of data in the packet
for (int ix = 0; ix < N_DATA_QUADS; ix++) // process the distance
processDistance(bPacketOkay, ix);
for (int ix = 0; ix < N_DATA_QUADS; ix++) // process the signal strength (quality)
processSignalStrength(bPacketOkay, ix);
if (bPacketOkay) {
if (xv_config.show_dist) { // show distance command is active
if (xv_config.show_angle == SHOW_ALL_ANGLES
|| (xv_config.show_angle >= startingAngle && xv_config.show_angle < startingAngle + N_DATA_QUADS)) {
for (int ix = 0; ix < N_DATA_QUADS; ix++) {
if ((xv_config.show_angle == SHOW_ALL_ANGLES)
|| (xv_config.show_angle == startingAngle + ix)) {
Serial.print(startingAngle + ix);
Serial.print(F(": "));
Serial.print(int(dist[ix]));
Serial.print(F(" ("));
Serial.print(quality[ix]);
Serial.println(F(")"));
}
} // or (int ix = 0; ix < N_DATA_QUADS; ix++)
} // if (xv_config.show_angle == SHOW_ALL_ANGLES ...
} // if (xv_config.show_dist)
} // if (bPacketOkay)
// initialize a bunch of stuff before we switch back to State 1
for (int ix = 0; ix < N_DATA_QUADS; ix++) {
dist[ix] = 0;
quality[ix] = 0;
}
for (ixPacket = 0; ixPacket < PACKET_LENGTH; ixPacket++) // clear out this packet
Packet[ixPacket] = 0;
ixPacket = 0;
eState = eState_Find_COMMAND; // This packet is done -- look for next COMMAND byte
} // if (ixPacket == PACKET_LENGTH)
} // if (eState == eState_Find_COMMAND)
} // if (Serial1.available() > 0)
if (xv_config.motor_enable) {
=======
sCmd.readSerial(); // check for incoming serial commands
// read byte from LIDAR and relay to USB
if (Serial1.available() > 0) {
inByte = Serial1.read(); // get incoming byte:
if (xv_config.raw_data) {
Serial.print(inByte, BYTE); // relay
getSurreal
committed
if (xv_config.motor_enable) {
if (pwm_val != pwm_last) {
Timer3.pwm(xv_config.motor_pwm_pin, pwm_val); // replacement for analogWrite()
pwm_last = pwm_val;
}
getSurreal
committed
<<<<<<< HEAD
<<<<<<< HEAD
} // if (xv_config.motor_enable)
} // loop
/*
* processIndex - Process the packet element 'index'
* index is the index byte in the 90 packets, going from A0 (packet 0, readings 0 to 3) to F9
* (packet 89, readings 356 to 359).
* Enter with: bValidData = true if packet is okay (good CRC)
* Uses: Packet
* ledState gets toggled if angle = 0
* ledPin = which pin the LED is connected to
* ledState = LED on or off
* xv_config.show_dist = true if we're supposed to show distance
* curMillis = milliseconds, now
* lastMillis = milliseconds, last time through this subroutine
* Calls: digitalWrite() - used to toggle LED pin
* Serial.print
* Returns: The first angle (of 4) in the current 'index' group
*/
uint16_t processIndex(boolean bValidData) {
uint16_t angle = 0;
if (bValidData) {
uint16_t data_4deg_index = Packet[OFFSET_TO_INDEX] - INDEX_LO;
angle = data_4deg_index * N_DATA_QUADS; // 1st angle in the set of 4
=======
getSurreal
committed
=======
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
}
}
void decodeData(unsigned char inByte) {
switch (data_status) {
case 0: // no header
if (inByte == 0xFA) {
data_status = 1;
data_loop_index = 1;
}
break;
case 1: // find 2nd FA
if (data_loop_index == 22) { // Theres 22 bytes in each packet. Time to start over
if (inByte == 0xFA) {
data_status = 2;
data_loop_index = 1;
}
else { // if not FA search again
data_status = 0;
}
}
else {
data_loop_index++;
}
break;
case 2: // read data out
if (data_loop_index == 22) { // Theres 22 bytes in each packet. Time to start over
if (inByte == 0xFA) {
data_loop_index = 1;
}
else { // if not FA search again
data_status = 0;
}
}
else {
readData(inByte);
data_loop_index++;
}
break;
}
}
void readData(unsigned char inByte) {
switch (data_loop_index) {
case 1: // 4 degree index
data_4deg_index = inByte - 0xA0;
angle = data_4deg_index * 4; // 1st angle in the set of 4
getSurreal
committed
<<<<<<< HEAD
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
=======
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
if (angle == 0) {
James LeRoy
committed
if (ledState) {
ledState = LOW;
James LeRoy
committed
else {
ledState = HIGH;
}
digitalWrite(ledPin, ledState);
if (xv_config.show_dist) {
curMillis = millis();
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
<<<<<<< HEAD
if (xv_config.show_angle == SHOW_ALL_ANGLES) {
/*
Serial.print(F("Time Interval: "));
Serial.println(curMillis - lastMillis);
*/
}
lastMillis = curMillis;
}
} // if (angle == 0)
} // if (bValidData)
return angle;
}
/*
* processSpeed- Process the packet element 'speed'
* speed is two-bytes of information, little-endian. It represents the speed, in 64th of RPM (aka value
* in RPM represented in fixed point, with 6 bits used for the decimal part).
* Enter with: bValidData = true if packet is okay (good CRC)
* Uses: Packet
* angle = if 0 then enable display of RPM and PWM
* xv_config.show_rpm = true if we're supposed to display RPM and PWM
* Calls: Serial.print
*/
void processSpeed(boolean bValidData) {
if (bValidData) {
motor_rph_low_byte = Packet[OFFSET_TO_SPEED_LSB];
motor_rph_high_byte = Packet[OFFSET_TO_SPEED_MSB];
=======
James LeRoy
committed
Serial.print(F("Time Interval: "));
Serial.println(curMillis - lastMillis);
lastMillis = curMillis;
}
}
//Serial.print(int(data_4deg_index));
James LeRoy
committed
//Serial.println(F(" "));
James LeRoy
committed
case 2: // speed in RPH low byte
motor_rph_low_byte = inByte;
break;
James LeRoy
committed
case 3: // speed in RPH high byte
motor_rph_high_byte = inByte;
motor_rph = (motor_rph_high_byte << 8) | motor_rph_low_byte;
motor_rpm = float( (motor_rph_high_byte << 8) | motor_rph_low_byte ) / 64.0;
James LeRoy
committed
Serial.print(F("RPM: "));
Serial.println(pwm_val);
}
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
<<<<<<< HEAD
} // if (bValidData)
}
/*
* Data 0 to Data 3 are the 4 readings. Each one is 4 bytes long, and organized as follows :
* byte 0 : <distance 7:0>
* byte 1 : <"invalid data" flag> <"strength warning" flag> <distance 13:8>
* byte 2 : <signal strength 7:0>
* byte 3 : <signal strength 15:8>
*/
/*
* processDistance- Process the packet element 'distance'
* Enter with: bValidData = true if packet is okay (good CRC)
* iQuad = which one of the (4) readings to process, value = 0..3
* Uses: Packet
* dist[] = distance to object
* Calls: N/A
*/
void processDistance(boolean bValidData, int iQuad) {
uint8_t dataL, dataM;
dist[iQuad] = 0; // initialize
if (bValidData) {
int iOffset = (iQuad * N_DATA_QUADS) + OFFSET_TO_4_DATA_READINGS + OFFSET_DATA_DISTANCE_LSB;
// byte 0 : <distance 7:0>
// byte 1 : <"invalid data" flag> <"strength warning" flag> <distance 13:8>
dataL = Packet[iOffset]; // first half of distance data
dataM = Packet[iOffset + 1]; // get MSB of distance data + flags
if ((dataM & 0x80) == 0) // check for Invalid Flag
dist[iQuad] = dataL | ((dataM & 0x3F) << 8);
} // if (bValidData)
}
/*
* processSignalStrength- Process the packet element 'signal strength'
* Enter with: bValidData = true if packet is okay (good CRC)
* iQuad = which one of the (4) readings to process, value = 0..3
* Uses: Packet
* quality[] = signal quality
* Calls: N/A
*/
void processSignalStrength(boolean bValidData, int iQuad) {
uint8_t dataL, dataM;
quality[iQuad] = 0; // initialize
if (bValidData) {
int iOffset = (iQuad * N_DATA_QUADS) + OFFSET_TO_4_DATA_READINGS + OFFSET_DATA_SIGNAL_LSB;
dataL = Packet[iOffset]; // signal strength LSB
dataM = Packet[iOffset + 1];
quality[iQuad] = dataL | (dataM << 8);
} // if (bValidData)
}
/*
* eValidatePacket - Validate 'Packet'
* Enter with: 'Packet' is ready to check
* Uses: CalcCRC
* Exits with: 0 = Packet is okay
* Error: non-zero = Packet is no good
*/
byte eValidatePacket() {
unsigned long chk32;
unsigned long checksum;
const int bytesToCheck = PACKET_LENGTH - 2;
const int CalcCRC_Len = bytesToCheck / 2;
unsigned int CalcCRC[CalcCRC_Len];
byte b1a, b1b, b2a, b2b;
int ix;
for (int ix = 0; ix < CalcCRC_Len; ix++) // initialize 'CalcCRC' array
CalcCRC[ix] = 0;
// Perform checksum validity test
for (ix = 0; ix < bytesToCheck; ix += 2) // build 'CalcCRC' array
CalcCRC[ix / 2] = Packet[ix] + ((Packet[ix + 1]) << 8);
chk32 = 0;
for (ix = 0; ix < CalcCRC_Len; ix++)
chk32 = (chk32 << 1) + CalcCRC[ix];
checksum = (chk32 & 0x7FFF) + (chk32 >> 15);
checksum &= 0x7FFF;
b1a = checksum & 0xFF;
b1b = Packet[OFFSET_TO_CRC_L];
b2a = checksum >> 8;
b2b = Packet[OFFSET_TO_CRC_M];
if ((b1a == b1b) && (b2a == b2b))
return 0; // okay
else
return 1; // non-zero = bad CRC
=======
James LeRoy
committed
case 4:
data0 = inByte; // first half of distance data
break;
James LeRoy
committed
case 5:
if ((inByte & 0x80) >> 7) { // check for Invalid Flag
dist = 0;
}
else {
dist = data0 | (( inByte & 0x3F) << 8);
}
break;
James LeRoy
committed
case 6:
data2 = inByte; // first half of quality data
break;
James LeRoy
committed
case 7:
quality = (inByte << 8) | data2;
James LeRoy
committed
if (xv_config.show_dist) {
if (xv_config.show_angle == 360 or xv_config.show_angle == angle) {
Serial.print(angle);
James LeRoy
committed
Serial.print(F(": "));
Serial.print(int(dist));
James LeRoy
committed
Serial.print(F(" ("));
Serial.print(quality);
James LeRoy
committed
Serial.println(F(")"));
James LeRoy
committed
data0 = inByte;
break;
James LeRoy
committed
case 9:
if ((inByte & 0x80) >> 7) { // check for Invalid Flag
dist = 0;
}
else {
dist = data0 | (( inByte & 0x3F) << 8);
}
break;
James LeRoy
committed
case 10:
data2 = inByte; // first half of quality data
break;
James LeRoy
committed
case 11:
quality = (inByte << 8) | data2;
James LeRoy
committed
if (xv_config.show_dist) {
if (xv_config.show_angle == 360 or xv_config.show_angle == angle) {
Serial.print(angle);
James LeRoy
committed
Serial.print(F(": "));
Serial.print(int(dist));
James LeRoy
committed
Serial.print(F(" ("));
Serial.print(quality);
James LeRoy
committed
Serial.println(F(")"));
}
}
break;
James LeRoy
committed
data0 = inByte;
break;
James LeRoy
committed
case 13:
if ((inByte & 0x80) >> 7) { // check for Invalid Flag
dist = 0;
}
else {
dist = data0 | (( inByte & 0x3F) << 8);
}
break;
James LeRoy
committed
case 14:
data2 = inByte; // first half of quality data
break;
James LeRoy
committed
case 15:
quality = (inByte << 8) | data2;
James LeRoy
committed
if (xv_config.show_dist) {
if (xv_config.show_angle == 360 or xv_config.show_angle == angle) {
Serial.print(angle);
James LeRoy
committed
Serial.print(F(": "));
Serial.print(int(dist));
James LeRoy
committed
Serial.print(F(" ("));
Serial.print(quality);
James LeRoy
committed
Serial.println(F(")"));
}
}
break;
James LeRoy
committed
data0 = inByte;
break;
James LeRoy
committed
case 17:
if ((inByte & 0x80) >> 7) { // check for Invalid Flag
dist = 0;
}
else {
dist = data0 | (( inByte & 0x3F) << 8);
}
break;
James LeRoy
committed
case 18:
data2 = inByte; // first half of quality data
break;
James LeRoy
committed
case 19:
quality = (inByte << 8) | data2;
James LeRoy
committed
if (xv_config.show_dist) {
if (xv_config.show_angle == 360 or xv_config.show_angle == angle) {
Serial.print(angle);
James LeRoy
committed
Serial.print(F(": "));
Serial.print(int(dist));
James LeRoy
committed
Serial.print(F(" ("));
Serial.print(quality);
James LeRoy
committed
Serial.println(F(")"));
}
}
break;
xv_config.id = 0x05;
strcpy(xv_config.version, "1.2.2");
getSurreal
committed
<<<<<<< HEAD
xv_config.motor_pwm_pin = 9; // pin connected N-Channel Mosfet (only pin controlled with Timer3)
getSurreal
committed
=======
xv_config.motor_pwm_pin = 9; // pin connected N-Channel Mosfet
getSurreal
committed
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
xv_config.rpm_min = 200;
xv_config.rpm_max = 300;
xv_config.pwm_min = 100;
xv_config.sample_time = 20;
xv_config.Kp = 2.0;
xv_config.Ki = 1.0;
xv_config.Kd = 0.0;
getSurreal
committed
xv_config.motor_enable = true;
xv_config.raw_data = true;
James LeRoy
committed
xv_config.show_dist = false;
xv_config.show_rpm = false;
xv_config.show_angle = 360;
sCmd.addCommand("Help", help);
sCmd.addCommand("help", help);
sCmd.addCommand("ShowConfig", showConfig);
sCmd.addCommand("show", show);
sCmd.addCommand("SaveConfig", saveConfig);
sCmd.addCommand("ResetConfig", initEEPROM);
sCmd.addCommand("SetRPM", setRPM);
sCmd.addCommand("SetKp", setKp);
sCmd.addCommand("SetKi", setKi);
sCmd.addCommand("SetKd", setKd);
sCmd.addCommand("SetSampleTime", setSampleTime);
sCmd.addCommand("ShowRPM", showRPM);
sCmd.addCommand("HideRPM", hideRPM);
sCmd.addCommand("ShowDist", showDist);
sCmd.addCommand("HideDist", hideDist);
<<<<<<< HEAD
sCmd.addCommand("ShowAngle", showAngle);
sCmd.addCommand("HideAngle", hideDist);
sCmd.addCommand("MotorOff", motorOff);
sCmd.addCommand("MotorOn", motorOn);
sCmd.addCommand("HideRaw", hideRaw);
sCmd.addCommand("ShowRaw", showRaw);
=======
sCmd.addCommand("ShowAngle", showAngle);
sCmd.addCommand("MotorOff", motorOff);
sCmd.addCommand("MotorOn", motorOn);
sCmd.addCommand("HideRaw", hideRaw);
sCmd.addCommand("ShowRaw", showRaw);
James LeRoy
committed
xv_config.show_rpm = true;
if (xv_config.raw_data == true) {
hideRaw();
}
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Showing RPM data"));
Serial.println(F(" "));
James LeRoy
committed
xv_config.show_rpm = false;
Serial.println(F(" "));
Serial.print(F("Hiding RPM data"));
Serial.println(F(" "));
void showDist() {
James LeRoy
committed
xv_config.show_dist = true;
if (xv_config.raw_data == true) {
hideRaw();
}
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Showing Distance data"));
Serial.println(F(" "));
}
void hideDist() {
James LeRoy
committed
xv_config.show_dist = false;
Serial.println(F(" "));
Serial.print(F("Hiding Distance data"));
Serial.println(F(" "));
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
void show() {
boolean syntax_error = false;
String arg1 = sCmd.next(); // 1st argument
if (arg1 != "") {
/*
* show rpm
*/
if (arg1 == "rpm") {
String arg2 = sCmd.next();
if (arg2 != "") {
syntax_error = true; // should not be any more arguements for rpm
}
else {
xv_config.show_rpm = true;
if (xv_config.raw_data == true) {
hideRaw();
}
Serial.println(F(" "));
Serial.print(F("Showing RPM data"));
Serial.println(F(" "));
}
}
/*
* no matching commands
*/
else {
syntax_error = true;
}
} // if (arg != NULL)
else {
syntax_error = true; // no arguments passed
}
if (syntax_error) {
Serial.println(F(" "));
Serial.print(F("Invalid Command"));
Serial.println(F(" "));
}
}
void showAngle() {
double sVal = 0.0;
char *arg;
boolean syntax_error = false;
arg = sCmd.next();
if (arg != NULL) {
sVal = atoi(arg); // Converts a char string to a int
if (sVal < 0 or sVal > 360) {
syntax_error = true;
}
}
else {
syntax_error = true;
}
arg = sCmd.next();
if (arg != NULL) {
syntax_error = true;
}
if (syntax_error) {
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Incorrect syntax. Example: ShowAngle 0 (0 - 359 or 360 for all)"));
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Showing Only Angle: "));
Serial.println(sVal);
James LeRoy
committed
Serial.println(F(" "));
xv_config.show_angle = sVal;
getSurreal
committed
xv_config.motor_enable = false;
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Motor off"));
Serial.println(F(" "));
}
void motorOn() {
getSurreal
committed
xv_config.motor_enable = true;
Timer3.pwm(xv_config.motor_pwm_pin, pwm_val);
rpm_err = 0; // reset rpm error
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Motor on"));
Serial.println(F(" "));
void motorCheck() { // Make sure the motor RPMs are good else shut it down
now = millis();
getSurreal
committed
<<<<<<< HEAD
getSurreal
committed
=======
getSurreal
committed
if (now - motor_check_timer > motor_check_interval){
getSurreal
committed
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
if ((motor_rpm < xv_config.rpm_min or motor_rpm > xv_config.rpm_max) and pwm_val > 1000) {
rpm_err++;
}
else {
rpm_err = 0;
}
if (rpm_err > rpm_err_thresh) {
getSurreal
committed
<<<<<<< HEAD
getSurreal
committed
=======
getSurreal
committed
motorOff();
getSurreal
committed
>>>>>>> 9423c3c07ba8665de06a1a0f3cdad7d726b30174
ledState = LOW;
digitalWrite(ledPin, ledState);
}
motor_check_timer = millis();
}
}
void hideRaw() {
xv_config.raw_data = false;
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Raw lidar data disabled"));
Serial.println(F(" "));
void showRaw() {
xv_config.raw_data = true;
hideDist();
hideRPM();
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Lidar data enabled"));
Serial.println(F(" "));
char *arg;
boolean syntax_error = false;
arg = sCmd.next();
if (arg != NULL) {
if (sVal < xv_config.rpm_min) {
sVal = xv_config.rpm_min;
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("RPM too low. Setting to minimum "));
Serial.print(xv_config.rpm_min);
James LeRoy
committed
Serial.println(F(" "));
if (sVal > xv_config.rpm_max) {
sVal = xv_config.rpm_max;
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("RPM too high. Setting to maximum "));
Serial.print(xv_config.rpm_max);
James LeRoy
committed
Serial.println(F(" "));
}
else {
syntax_error = true;
}
arg = sCmd.next();
if (arg != NULL) {
syntax_error = true;
}
if (syntax_error) {
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Incorrect syntax. Example: SetRPM 300"));
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("New RPM setpoint: "));
Serial.println(sVal);
James LeRoy
committed
Serial.print(F("Old RPM setpoint"));
Serial.println(xv_config.rpm_setpoint);
James LeRoy
committed
Serial.println(F(" "));
}
}
void setKp() {
char *arg;
boolean syntax_error = false;
arg = sCmd.next();
if (arg != NULL) {
}
else {
syntax_error = true;
}
arg = sCmd.next();
if (arg != NULL) {
syntax_error = true;
}
if (syntax_error) {
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Setting Kp to: "));
James LeRoy
committed
Serial.println(F(" "));
xv_config.Kp = sVal;
rpmPID.SetTunings(xv_config.Kp, xv_config.Ki, xv_config.Kd);
void setKi() {
char *arg;
boolean syntax_error = false;
arg = sCmd.next();
if (arg != NULL) {
}
else {
syntax_error = true;
}
arg = sCmd.next();
if (arg != NULL) {
syntax_error = true;
}
if (syntax_error) {
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Setting Ki to: "));
James LeRoy
committed
Serial.println(F(" "));
xv_config.Ki = sVal;
rpmPID.SetTunings(xv_config.Kp, xv_config.Ki, xv_config.Kd);
}
}
void setKd() {
char *arg;
boolean syntax_error = false;
arg = sCmd.next();
if (arg != NULL) {
}
else {
syntax_error = true;
}
arg = sCmd.next();
if (arg != NULL) {
syntax_error = true;
}
if (syntax_error) {
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Incorrect syntax. Example: SetKd 0.001"));
James LeRoy
committed
Serial.println(F(" "));
James LeRoy
committed
Serial.println(F(" "));
Serial.print(F("Setting Kd to: "));
James LeRoy
committed
Serial.println(F(" "));
xv_config.Kd = sVal;
rpmPID.SetTunings(xv_config.Kp, xv_config.Ki, xv_config.Kd);
void setSampleTime() {
double sVal = 0.0;
char *arg;
boolean syntax_error = false;
arg = sCmd.next();
if (arg != NULL) {
sVal = atoi(arg); // Converts a char string to an integer
}
else {