PdePreprocessor restored to version 316b871

Added an "insideString" flag in scrubComments to avoid failing with strings like "Hello */*"
Added a handful of tests taking code from various issues in order to better avoid future regressions
Closes #1687
This commit is contained in:
Federico Fissore 2013-11-16 12:59:26 +01:00
parent 71bb7f7ae3
commit 139dd6bf6a
10 changed files with 1413 additions and 26 deletions

View File

@ -242,25 +242,24 @@ public class PdePreprocessor {
*/
public String strip(String in) {
// XXX: doesn't properly handle special single-quoted characters
List<Pattern> patterns = new ArrayList<Pattern>();
// single-quoted character
patterns.add(Pattern.compile("('.')", Pattern.MULTILINE));
// single and multi-line comment
patterns.add(Pattern.compile("('\\\\\"')", Pattern.MULTILINE));
patterns.add(Pattern.compile("(//.*?$)", Pattern.MULTILINE));
patterns.add(Pattern.compile("(/\\*[^*]*(?:\\*(?!/)[^*]*)*\\*/)", Pattern.MULTILINE));
// pre-processor directive
patterns.add(Pattern.compile("(^\\s*#.*?$)", Pattern.MULTILINE));
String p = "('.')";
p += "|('\\\\\"')";
// double-quoted string
patterns.add(Pattern.compile("(\"(?:[^\"\\\\]|\\\\.)*\")", Pattern.MULTILINE));
p += "|(\"(?:[^\"\\\\]|\\\\.)*\")";
String code = in;
for (Pattern p : patterns) {
Matcher matcher = p.matcher(code);
code = matcher.replaceAll(" ");
}
// single and multi-line comment
//p += "|" + "(//\\s*?$)|(/\\*\\s*?\\*/)";
p += "|(//.*?$)|(/\\*[^*]*(?:\\*(?!/)[^*]*)*\\*/)";
return code;
// pre-processor directive
p += "|" + "(^\\s*#.*?$)";
Pattern pattern = Pattern.compile(p, Pattern.MULTILINE);
Matcher matcher = pattern.matcher(in);
return matcher.replaceAll(" ");
}
/**
@ -333,17 +332,54 @@ public class PdePreprocessor {
* Replace all commented portions of a given String as spaces.
* Utility function used here and in the preprocessor.
*/
static public String scrubComments(String what) {
List<Pattern> patterns = new ArrayList<Pattern>();
patterns.add(Pattern.compile("('\\\\\"')", Pattern.MULTILINE));
patterns.add(Pattern.compile("(//.*?$)", Pattern.MULTILINE));
patterns.add(Pattern.compile("(/\\*[^*]*(?:\\*(?!/)[^*]*)*\\*/)", Pattern.MULTILINE));
public String scrubComments(String what) {
char p[] = what.toCharArray();
String result = what;
for (Pattern p : patterns) {
result = p.matcher(result).replaceAll("");
int index = 0;
boolean insideString = false;
while (index < p.length) {
if (p[index] == '\"') {
insideString = !insideString;
}
// for any double slash comments, ignore until the end of the line
if (!insideString && (p[index] == '/') &&
(index < p.length - 1) &&
(p[index+1] == '/')) {
p[index++] = ' ';
p[index++] = ' ';
while ((index < p.length) &&
(p[index] != '\n')) {
p[index++] = ' ';
}
// check to see if this is the start of a new multiline comment.
// if it is, then make sure it's actually terminated somewhere.
} else if (!insideString && (p[index] == '/') &&
(index < p.length - 1) &&
(p[index+1] == '*')) {
p[index++] = ' ';
p[index++] = ' ';
boolean endOfRainbow = false;
while (index < p.length - 1) {
if ((p[index] == '*') && (p[index+1] == '/')) {
p[index++] = ' ';
p[index++] = ' ';
endOfRainbow = true;
break;
} else {
// continue blanking this area
p[index++] = ' ';
}
}
if (!endOfRainbow) {
throw new RuntimeException(_("Missing the */ from the end of a " +
"/* comment */"));
}
} else { // any old character, move along
index++;
}
}
return result;
return new String(p);
}
}

View File

@ -0,0 +1,303 @@
/*
* The code is released under the GNU General Public License.
* Developed by Kristian Lauszus, TKJ Electronics 2013
* This is the algorithm for the Balanduino balancing robot.
* It can be controlled by either an Android app or a Processing application via Bluetooth.
* The Android app can be found at the following link: https://github.com/TKJElectronics/BalanduinoAndroidApp
* The Processing application can be found here: https://github.com/TKJElectronics/BalanduinoProcessingApp
* It can also be controlled by a PS3, Wii or a Xbox controller
* For details, see: http://balanduino.net/
*/
/* Use this to enable and disable the different options */
#define ENABLE_TOOLS
#define ENABLE_SPP
#define ENABLE_PS3
#define ENABLE_WII
#define ENABLE_XBOX
#define ENABLE_ADK
#include "Balanduino.h"
#include <Wire.h> // Official Arduino Wire library
#include <usbhub.h> // Some dongles can have a hub inside
#ifdef ENABLE_ADK
#include <adk.h>
#endif
// These are all open source libraries written by Kristian Lauszus, TKJ Electronics
// The USB libraries are located at the following link: https://github.com/felis/USB_Host_Shield_2.0
#include <Kalman.h> // Kalman filter library - see: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it/
#ifdef ENABLE_XBOX
#include <XBOXRECV.h>
#endif
#ifdef ENABLE_SPP
#include <SPP.h>
#endif
#ifdef ENABLE_PS3
#include <PS3BT.h>
#endif
#ifdef ENABLE_WII
#include <Wii.h>
#endif
// Create the Kalman library instance
Kalman kalman; // See https://github.com/TKJElectronics/KalmanFilter for source code
#if defined(ENABLE_SPP) || defined(ENABLE_PS3) || defined(ENABLE_WII) || defined(ENABLE_XBOX) || defined(ENABLE_ADK)
#define ENABLE_USB
USB Usb; // This will take care of all USB communication
#endif
#ifdef ENABLE_ADK
// Implementation for the Android Open Accessory Protocol. Simply connect your phone to get redirected to the Play Store
ADK adk(&Usb, "TKJ Electronics", // Manufacturer Name
"Balanduino", // Model Name
"Android App for Balanduino", // Description - user visible string
"0.5.0", // Version of the Android app
"https://play.google.com/store/apps/details?id=com.tkjelectronics.balanduino", // URL - web page to visit if no installed apps support the accessory
"1234"); // Serial Number - this is not used
#endif
#ifdef ENABLE_XBOX
XBOXRECV Xbox(&Usb); // You have to connect a Xbox wireless receiver to the Arduino to control it with a wireless Xbox controller
#endif
#if defined(ENABLE_SPP) || defined(ENABLE_PS3) || defined(ENABLE_WII)
USBHub Hub(&Usb); // Some dongles have a hub inside
BTD Btd(&Usb); // This is the main Bluetooth library, it will take care of all the USB and HCI communication with the Bluetooth dongle
#endif
#ifdef ENABLE_SPP
SPP SerialBT(&Btd, "Balanduino", "0000"); // The SPP (Serial Port Protocol) emulates a virtual Serial port, which is supported by most computers and mobile phones
#endif
#ifdef ENABLE_PS3
PS3BT PS3(&Btd); // The PS3 library supports all three official controllers: the Dualshock 3, Navigation and Move controller
#endif
#ifdef ENABLE_WII
WII Wii(&Btd); // The Wii library can communicate with Wiimotes and the Nunchuck and Motion Plus extension and finally the Wii U Pro Controller
//WII Wii(&Btd,PAIR); // You will have to pair with your Wiimote first by creating the instance like this and the press 1+2 on the Wiimote
// or press sync if you are using a Wii U Pro Controller
// Or you can simply send "CW;" to the robot to start the pairing sequence
// This can also be done using the Android or Processing application
#endif
void setup() {
/* Initialize UART */
Serial.begin(115200);
/* Read the PID values, target angle and other saved values in the EEPROM */
if (!checkInitializationFlags())
readEEPROMValues(); // Only read the EEPROM values if they have not been restored
/* Setup encoders */
pinMode(leftEncoder1, INPUT);
pinMode(leftEncoder2, INPUT);
pinMode(rightEncoder1, INPUT);
pinMode(rightEncoder2, INPUT);
attachInterrupt(0, leftEncoder, CHANGE);
attachInterrupt(1, rightEncoder, CHANGE);
/* Enable the motor drivers */
pinMode(leftEnable, OUTPUT);
pinMode(rightEnable, OUTPUT);
digitalWrite(leftEnable, HIGH);
digitalWrite(rightEnable, HIGH);
/* Setup motor pins to output */
sbi(pwmPortDirection, leftPWM);
sbi(leftPortDirection, leftA);
sbi(leftPortDirection, leftB);
sbi(pwmPortDirection, rightPWM);
sbi(rightPortDirection, rightA);
sbi(rightPortDirection, rightB);
/* Set PWM frequency to 20kHz - see the datasheet http://www.atmel.com/Images/doc8272.pdf page 128-135 */
// Set up PWM, Phase and Frequency Correct on pin 18 (OC1A) & pin 17 (OC1B) with ICR1 as TOP using Timer1
TCCR1B = _BV(WGM13) | _BV(CS10); // Set PWM Phase and Frequency Correct with ICR1 as TOP and no prescaling
ICR1 = PWMVALUE; // ICR1 is the TOP value - this is set so the frequency is equal to 20kHz
/* Enable PWM on pin 18 (OC1A) & pin 17 (OC1B) */
// Clear OC1A/OC1B on compare match when up-counting
// Set OC1A/OC1B on compare match when downcounting
TCCR1A = _BV(COM1A1) | _BV(COM1B1);
setPWM(leftPWM, 0); // Turn off PWM on both pins
setPWM(rightPWM, 0);
/* Setup buzzer pin */
pinMode(buzzer, OUTPUT);
#ifdef ENABLE_USB
if (Usb.Init() == -1) { // Check if USB Host is working
Serial.print(F("OSC did not start"));
digitalWrite(buzzer, HIGH);
while (1); // Halt
}
#endif
/* Attach onInit function */
// This is used to set the LEDs according to the voltage level and vibrate the controller to indicate the new connection
#ifdef ENABLE_PS3
PS3.attachOnInit(onInit);
#endif
#ifdef ENABLE_WII
Wii.attachOnInit(onInit);
#endif
#ifdef ENABLE_XBOX
Xbox.attachOnInit(onInit);
#endif
/* Setup IMU */
Wire.begin();
while (i2cRead(0x75, i2cBuffer, 1));
if (i2cBuffer[0] != 0x68) { // Read "WHO_AM_I" register
Serial.print(F("Error reading sensor"));
digitalWrite(buzzer, HIGH);
while (1); // Halt
}
i2cBuffer[0] = 19; // Set the sample rate to 400Hz - 8kHz/(19+1) = 400Hz
i2cBuffer[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling
i2cBuffer[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s
i2cBuffer[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g
while (i2cWrite(0x19, i2cBuffer, 4, false)); // Write to all four registers at once
while (i2cWrite(0x6B, 0x09, true)); // PLL with X axis gyroscope reference, disable temperature sensor and disable sleep mode
delay(100); // Wait for the sensor to get ready
/* Set Kalman and gyro starting angle */
while (i2cRead(0x3D, i2cBuffer, 4));
accY = ((i2cBuffer[0] << 8) | i2cBuffer[1]);
accZ = ((i2cBuffer[2] << 8) | i2cBuffer[3]);
// atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2
// We then convert it to 0 to 2π and then from radians to degrees
accAngle = (atan2((double)accY - cfg.accYzero, (double)accZ - cfg.accZzero) + PI) * RAD_TO_DEG;
kalman.setAngle(accAngle); // Set starting angle
pitch = accAngle;
gyroAngle = accAngle;
/* Find gyro zero value */
calibrateGyro();
pinMode(LED_BUILTIN, OUTPUT); // LED_BUILTIN is defined in pins_arduino.h in the hardware add-on
/* Beep to indicate that it is now ready */
digitalWrite(buzzer, HIGH);
delay(100);
digitalWrite(buzzer, LOW);
/* Setup timing */
kalmanTimer = micros();
pidTimer = kalmanTimer;
encoderTimer = kalmanTimer;
imuTimer = millis();
reportTimer = imuTimer;
ledTimer = imuTimer;
blinkTimer = imuTimer;
}
void loop() {
#ifdef ENABLE_WII
if (Wii.wiimoteConnected) // We have to read much more often from the Wiimote to decrease latency
Usb.Task();
#endif
/* Calculate pitch */
while (i2cRead(0x3D, i2cBuffer, 8));
accY = ((i2cBuffer[0] << 8) | i2cBuffer[1]);
accZ = ((i2cBuffer[2] << 8) | i2cBuffer[3]);
gyroX = ((i2cBuffer[6] << 8) | i2cBuffer[7]);
// atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2
// We then convert it to 0 to 2π and then from radians to degrees
accAngle = (atan2((double)accY - cfg.accYzero, (double)accZ - cfg.accZzero) + PI) * RAD_TO_DEG;
uint32_t timer = micros();
// This fixes the 0-360 transition problem when the accelerometer angle jumps between 0 and 360 degrees
if ((accAngle < 90 && pitch > 270) || (accAngle > 270 && pitch < 90)) {
kalman.setAngle(accAngle);
pitch = accAngle;
gyroAngle = accAngle;
} else {
gyroRate = ((double)gyroX - gyroXzero) / 131.0; // Convert to deg/s
double dt = (double)(timer - kalmanTimer) / 1000000.0;
gyroAngle += gyroRate * dt; // Gyro angle is only used for debugging
if (gyroAngle < 0 || gyroAngle > 360)
gyroAngle = pitch; // Reset the gyro angle when it has drifted too much
pitch = kalman.getAngle(accAngle, gyroRate, dt); // Calculate the angle using a Kalman filter
}
kalmanTimer = timer;
//Serial.print(accAngle);Serial.print('\t');Serial.print(gyroAngle);Serial.print('\t');Serial.println(pitch);
#ifdef ENABLE_WII
if (Wii.wiimoteConnected) // We have to read much more often from the Wiimote to decrease latency
Usb.Task();
#endif
/* Drive motors */
timer = micros();
// If the robot is laying down, it has to be put in a vertical position before it starts balancing
// If it's already balancing it has to be ±45 degrees before it stops trying to balance
if ((layingDown && (pitch < cfg.targetAngle - 10 || pitch > cfg.targetAngle + 10)) || (!layingDown && (pitch < cfg.targetAngle - 45 || pitch > cfg.targetAngle + 45))) {
layingDown = true; // The robot is in a unsolvable position, so turn off both motors and wait until it's vertical again
stopAndReset();
} else {
layingDown = false; // It's no longer laying down
updatePID(cfg.targetAngle, targetOffset, turningOffset, (double)(timer - pidTimer) / 1000000.0);
}
pidTimer = timer;
/* Update encoders */
timer = micros();
if (timer - encoderTimer >= 100000) { // Update encoder values every 100ms
encoderTimer = timer;
int32_t wheelPosition = getWheelsPosition();
wheelVelocity = wheelPosition - lastWheelPosition;
lastWheelPosition = wheelPosition;
//Serial.print(wheelPosition);Serial.print('\t');Serial.print(targetPosition);Serial.print('\t');Serial.println(wheelVelocity);
if (abs(wheelVelocity) <= 40 && !stopped) { // Set new targetPosition if braking
targetPosition = wheelPosition;
stopped = true;
}
batteryCounter++;
if (batteryCounter > 10) { // Measure battery every 1s
batteryCounter = 0;
batteryVoltage = (double)analogRead(VBAT) / 63.050847458; // VBAT is connected to analog input 5 which is not broken out. This is then connected to a 47k-12k voltage divider - 1023.0/(3.3/(12.0/(12.0+47.0))) = 63.050847458
if (batteryVoltage < 10.2 && batteryVoltage > 5) // Equal to 3.4V per cell - don't turn on if it's below 5V, this means that no battery is connected
digitalWrite(buzzer, HIGH);
else
digitalWrite(buzzer, LOW);
}
}
/* Read the Bluetooth dongle and send PID and IMU values */
#ifdef ENABLE_USB
readUsb();
#endif
#ifdef ENABLE_TOOLS
checkSerialData();
#endif
#if defined(ENABLE_TOOLS) || defined(ENABLE_SPP)
printValues();
#endif
#if defined(ENABLE_SPP) || defined(ENABLE_PS3) || defined(ENABLE_WII)
if (Btd.isReady()) {
timer = millis();
if ((Btd.watingForConnection && timer - blinkTimer > 1000) || (!Btd.watingForConnection && timer - blinkTimer > 100)) {
blinkTimer = timer;
ledState = !ledState;
digitalWrite(LED_BUILTIN, ledState); // Used to blink the built in LED, starts blinking faster upon an incoming Bluetooth request
}
} else if (ledState) { // The LED is on
ledState = !ledState;
digitalWrite(LED_BUILTIN, ledState); // This will turn it off
}
#endif
}

View File

@ -0,0 +1,281 @@
Kalman kalman;
USB Usb;
ADK adk(&Usb, ,
,
,
,
,
);
XBOXRECV Xbox(&Usb);
USBHub Hub(&Usb);
BTD Btd(&Usb);
SPP SerialBT(&Btd, , );
PS3BT PS3(&Btd);
WII Wii(&Btd);
void setup() {
Serial.begin(115200);
if (!checkInitializationFlags())
readEEPROMValues();
pinMode(leftEncoder1, INPUT);
pinMode(leftEncoder2, INPUT);
pinMode(rightEncoder1, INPUT);
pinMode(rightEncoder2, INPUT);
attachInterrupt(0, leftEncoder, CHANGE);
attachInterrupt(1, rightEncoder, CHANGE);
pinMode(leftEnable, OUTPUT);
pinMode(rightEnable, OUTPUT);
digitalWrite(leftEnable, HIGH);
digitalWrite(rightEnable, HIGH);
sbi(pwmPortDirection, leftPWM);
sbi(leftPortDirection, leftA);
sbi(leftPortDirection, leftB);
sbi(pwmPortDirection, rightPWM);
sbi(rightPortDirection, rightA);
sbi(rightPortDirection, rightB);
TCCR1B = _BV(WGM13) | _BV(CS10);
ICR1 = PWMVALUE;
TCCR1A = _BV(COM1A1) | _BV(COM1B1);
setPWM(leftPWM, 0);
setPWM(rightPWM, 0);
pinMode(buzzer, OUTPUT);
if (Usb.Init() == -1) {
Serial.print(F( ));
digitalWrite(buzzer, HIGH);
while (1);
}
PS3.attachOnInit(onInit);
Wii.attachOnInit(onInit);
Xbox.attachOnInit(onInit);
Wire.begin();
while (i2cRead(0x75, i2cBuffer, 1));
if (i2cBuffer[0] != 0x68) {
Serial.print(F( ));
digitalWrite(buzzer, HIGH);
while (1);
}
i2cBuffer[0] = 19;
i2cBuffer[1] = 0x00;
i2cBuffer[2] = 0x00;
i2cBuffer[3] = 0x00;
while (i2cWrite(0x19, i2cBuffer, 4, false));
while (i2cWrite(0x6B, 0x09, true));
delay(100);
while (i2cRead(0x3D, i2cBuffer, 4));
accY = ((i2cBuffer[0] << 8) | i2cBuffer[1]);
accZ = ((i2cBuffer[2] << 8) | i2cBuffer[3]);
accAngle = (atan2((double)accY - cfg.accYzero, (double)accZ - cfg.accZzero) + PI) * RAD_TO_DEG;
kalman.setAngle(accAngle);
pitch = accAngle;
gyroAngle = accAngle;
calibrateGyro();
pinMode(LED_BUILTIN, OUTPUT);
digitalWrite(buzzer, HIGH);
delay(100);
digitalWrite(buzzer, LOW);
kalmanTimer = micros();
pidTimer = kalmanTimer;
encoderTimer = kalmanTimer;
imuTimer = millis();
reportTimer = imuTimer;
ledTimer = imuTimer;
blinkTimer = imuTimer;
}
void loop() {
if (Wii.wiimoteConnected)
Usb.Task();
while (i2cRead(0x3D, i2cBuffer, 8));
accY = ((i2cBuffer[0] << 8) | i2cBuffer[1]);
accZ = ((i2cBuffer[2] << 8) | i2cBuffer[3]);
gyroX = ((i2cBuffer[6] << 8) | i2cBuffer[7]);
accAngle = (atan2((double)accY - cfg.accYzero, (double)accZ - cfg.accZzero) + PI) * RAD_TO_DEG;
uint32_t timer = micros();
if ((accAngle < 90 && pitch > 270) || (accAngle > 270 && pitch < 90)) {
kalman.setAngle(accAngle);
pitch = accAngle;
gyroAngle = accAngle;
} else {
gyroRate = ((double)gyroX - gyroXzero) / 131.0;
double dt = (double)(timer - kalmanTimer) / 1000000.0;
gyroAngle += gyroRate * dt;
if (gyroAngle < 0 || gyroAngle > 360)
gyroAngle = pitch;
pitch = kalman.getAngle(accAngle, gyroRate, dt);
}
kalmanTimer = timer;
if (Wii.wiimoteConnected)
Usb.Task();
timer = micros();
if ((layingDown && (pitch < cfg.targetAngle - 10 || pitch > cfg.targetAngle + 10)) || (!layingDown && (pitch < cfg.targetAngle - 45 || pitch > cfg.targetAngle + 45))) {
layingDown = true;
stopAndReset();
} else {
layingDown = false;
updatePID(cfg.targetAngle, targetOffset, turningOffset, (double)(timer - pidTimer) / 1000000.0);
}
pidTimer = timer;
timer = micros();
if (timer - encoderTimer >= 100000) {
encoderTimer = timer;
int32_t wheelPosition = getWheelsPosition();
wheelVelocity = wheelPosition - lastWheelPosition;
lastWheelPosition = wheelPosition;
if (abs(wheelVelocity) <= 40 && !stopped) {
targetPosition = wheelPosition;
stopped = true;
}
batteryCounter++;
if (batteryCounter > 10) {
batteryCounter = 0;
batteryVoltage = (double)analogRead(VBAT) / 63.050847458;
if (batteryVoltage < 10.2 && batteryVoltage > 5)
digitalWrite(buzzer, HIGH);
else
digitalWrite(buzzer, LOW);
}
}
readUsb();
checkSerialData();
printValues();
if (Btd.isReady()) {
timer = millis();
if ((Btd.watingForConnection && timer - blinkTimer > 1000) || (!Btd.watingForConnection && timer - blinkTimer > 100)) {
blinkTimer = timer;
ledState = !ledState;
digitalWrite(LED_BUILTIN, ledState);
}
} else if (ledState) {
ledState = !ledState;
digitalWrite(LED_BUILTIN, ledState);
}
}

View File

@ -0,0 +1,338 @@
#include <SoftwareSerial.h> // required to send and receive AT commands from the GPRS Shield
#include <Wire.h> // required for I2C communication with the RTC
// pin numbers for RTC
#define DS3231_I2C_ADDRESS 104 // 0x68 // Address for RTC
#define DS3231_TIME_CAL_ADDR 0 // 0x00
#define DS3231_ALARM1_ADDR 7 // 0x07
#define DS3231_ALARM2_ADDR 11 // 0x0B
#define DS3231_CONTROL_ADDR 14 // 0x0E
#define DS3231_STATUS_ADDR 15 // 0x0F
//#define DS3231_AGING_OFFSET_ADDR 16 // 0x10
#define DS3231_TEMPERATURE_ADDR 17 // 0x11
// Declarations for GPRS shield
SoftwareSerial GPRS( 7, 8 ); // A softwareSerial line is defined for the GPRS Shield
byte buffer[ 64 ]; // Buffer is used to transfer data from the GPRS line to the serial line
int count = 0, e = 0, count2 = 0, t = 0, q;
char temp, lastCaller[13] = "blank";
boolean callIncoming = false, done;
// Declarations for RTC
byte time[ 7 ]; // second, minute, hour, dow, day, month, year
byte time_A1[ 5 ]; // second_A1, minute_A1, hour_A1, day_A1, DY/DT
byte time_A2[ 4 ]; // minute_A2, hour_A2, day_A2, DY/DT
byte received[1]; // used to catch bytes sent from the clock
float temperature; // clock temperature is updated every 64 s
// Declarations for RemoteCallLogger
char telescopeNames[6][4];
/*
Code Exclusively for GPRS shield:
*/
//
// Default set of instructions for GPRS Shield power control
//
void setPowerStateTo( int newState )
{
if( newState != 1 && newState != 0 ) { // tests for an invalid state. In this case no change is made to powerstate
Serial.print( "Error: Invalid powerstate. Current powerstate = " );
Serial.print( getPowerState() );
Serial.print( "\n" );
}
else {
if( newState == getPowerState() ) { // if the requested powerstate is already in effect, no action is taken
Serial.print( "Powerstate = " );
Serial.print( newState );
Serial.print( " remains unchanged.\n" );
}
else {
powerUpOrDown(); // This is the only case where the powerstate is changed
Serial.print( "Powerstate changed from " );
Serial.print( 1 - newState );
Serial.print( " to " );
Serial.print( newState );
Serial.print( "\n" );
}
}
delay( 5000 ); // for startup
}
int getPowerState() // returns 0 if GPRS Shield is off, and 1 if GPRS Shield is on. This corresponds to the constant HIGH LOW enumeration
{
int ret;
if ( digitalRead(18) == 0 && digitalRead(19) == 0 ) // tests pins 18 and 19 for activity. See ExFoundImportantPins sketch to find out why
ret = 1;
else
ret = 0;
return ret;
}
void powerUpOrDown() // toggle the power of the shield
{
pinMode( 9, OUTPUT );
digitalWrite( 9, LOW );
delay( 1000 );
digitalWrite( 9, HIGH );
delay( 2000 );
digitalWrite( 9, LOW );
delay( 3000 );
}
//
// End of default power control
//
void clearBufferArray() // gives each element in the buffer array a null value
{
for( int i = 0; i < count; i++ )
buffer[ i ] = NULL;
}
void makeMissedCall( char num[] )
{
int i;
char in[ 18 ] = "ATD";
for( i = 3; i <= 14; i++ ) // AT command string containing telephone number is prepared
in[ i ] = num[ i - 3] ;
in[ 15 ] = ';';
in[ 16 ] = '\r';
in[ 17 ] = '\0';
GPRS.write( in ); // AT command requesting call is sent
delay( 10000 ); // enough time is given for GSM connection, and at least one ring.
GPRS.write( "ATH\r\0" ); // AT command requesting hangup is sent
delay( 1000 );
}
void sendTextMessage( char number[], char messg[] )
{
char temp[ 27 ] = "AT + CMGS = \"";
for( q = 0; q < 12; q++ ) // for-loop is used to prepare the AT command string containing the telephone number
temp[ q + 13 ] = number[ q ];
temp[ 25 ] = '\"';
temp[ 26 ] = '\0';
GPRS.println( "AT+CMGF=1\r" ); // AT command requesting SMS in text mode is sent
delay( 1000 );
GPRS.println( temp ); // AT command containing telephone number is sent
delay( 1000 );
GPRS.println( messg ); //the content of the message
delay( 1000 );
GPRS.println( (char) 26 ); //the ASCII code of the ctrl+z is 26. This character indicates the end of the message.
delay( 1000 );
}
void analise(byte incoming[], int length) // this function receives and analyses all text sent from the GPRS Shield to the serial line. It stores the cell number of the last caller.
{
e = 0; // Counter that represents a letter in the buffer
done = false; // Boolean that prevents unneccessary loop revolutions
while( e < length && !done){ // while e does not surpass the last letter index of the buffer...
temp = char( incoming[e] ); // store the character at index e in a temporary char
switch( temp ){ // inspect temp
case 'R':
{
if( length > e + 3 && !callIncoming ) { // This case responds to "RING"
if(char( incoming[e + 1] ) == 'I'
&& char( incoming[e + 2] ) == 'N'
&& char( incoming[e + 3] ) == 'G'){
GPRS.write("AT+CLCC\r"); // call information is requested
delay(500); // time is given for processing
GPRS.write("ATH\r"); // GPRS shield hangs up
callIncoming = true; // this ensures that a number cannot be stored in any other case than a missed call
done = true; // prevents the further operation of this while loop
}
}
}
break;
case '+':
{
if(char( buffer[ e + 1]) == '2' && length > e + 11 && callIncoming){ // this case responds to "+2", but only if the buffer contains enough characters for a valid cell number
for(t = 0; t < 12; t++) // and only if the callIncoming boolean had been triggered by a previous instance of this function
lastCaller[t] = char( buffer[ e + t ]); // the number of this caller is stored in lastCaller
lastCaller[12] = '\0';
callIncoming = false; // now we are ready for the next call
done = true; // prevents the further operation of this while loop
}
}
break;
case 'l':
Serial.println(lastCaller); // an easy way to test this function. Simply type "l" to see the value of lastCaller (default "blank")
break;
}
e++; // buffer index is incremented
}
}
/*
End of GPRS Shield code
*/
/*
Code exclusively for RTC
*/
byte decToBcd( byte b ) // converts a byte from a decimal format to a binary-coded decimal
{
return ( b / 10 << 4 ) + b % 10;
}
boolean getBit( byte addr, int pos ) // returns a single bit from a determined location in the RTC register
{
byte temp = getByte( addr );
return boolean( (temp >> pos) & B00000001 );
}
void setBit( byte addr, int pos, boolean newBit ) // ensures that a single bit from a determined location in the RTC register is a determined value
{
boolean oldBit = getBit( addr, pos ); // bits' current state is retrieved
byte temp = received[ 0 ]; // complete byte is retrieved. it is still left in received from the previous command
if ( oldBit != newBit ) // change is only made if the bit isnt already the correct value
{
if( newBit ) // if newBit is 1, then old bit must be 0, thus we must add an amount
temp += (B00000001 << pos); // 2 to the power of the bit position is added to the byte
else
temp -= (B00000001 << pos); // 2 to the power of the bit position is subtracted from the byte
}
setByte( addr, temp ); // the register is updated with the new byte
}
byte getByte( byte addr ) // returns a single byte from the given address in the RTC register
{
byte temp;
if( getBytes( addr, 1) ) // If one byte was read from the address:
temp = received[ 0 ]; // get that byte
else temp = -1; // -1 is returned as an error
return temp;
}
boolean getBytes( byte addr, int amount ) // updates the byte array "received" with the given amount of bytes, read from the given address
{ // ^ returns false if reading failed
boolean wireWorked = false;
Wire.beginTransmission( DS3231_I2C_ADDRESS ); // We transmit to the RTC
Wire.write( addr ); // We want to read from the given address
Wire.endTransmission(); // We want to receive, so we stop transmitting
Wire.requestFrom( DS3231_I2C_ADDRESS, amount ); // we request the given amount of bytes from the RTC
if( Wire.available() ){
received[amount]; // prepare the array for the amount of incoming bytes
for( int i = 0; i < amount; i++){
received[ i ] = Wire.read(); // we read the given amount of bytes
}
wireWorked = true; // everything went as planned
}
return wireWorked;
}
void setByte( byte addr, byte newByte ) // writes a given byte to a given address in the RTCs register. convenient
{
setBytes( addr, &newByte, 1); // call the setBytes function with the default amount = 1
}
void setBytes( byte addr, byte newBytes[], int amount ) // writes a given amount of bytes in a sequence starting from a given address
{
Wire.beginTransmission( DS3231_I2C_ADDRESS ); // We transmit to the RTC
Wire.write( addr ); // We want to start writing from the given address
for( int i = 0; i < amount; i++ )
Wire.write( newBytes[ i ] ); // we write each byte in sequence
Wire.endTransmission(); // we're done here
}
void getTime() // reads the current time from the register and updates the byte array containing the current time
{
if( getBytes( DS3231_TIME_CAL_ADDR, 7) ) // if 7 bytes were read in from the time address:
{
for(int i = 0; i < 7; i++) // place each byte in it's place
time[ i ] = received[ i ];
// The following conversions convert the values from binary-coded decimal format to regular binary:
time[ 0 ] = ( ( time[ 0 ] & B01110000 ) >> 4 ) * 10 + ( time[ 0 ] & B00001111 ); // second
time[ 1 ] = ( ( time[ 1 ] & B01110000 ) >> 4 ) * 10 + ( time[ 1 ] & B00001111 ); // minute
time[ 2 ] = ( ( time[ 2 ] & B00110000 ) >> 4 ) * 10 + ( time[ 2 ] & B00001111 ); // hour
time[ 4 ] = ( ( time[ 4 ] & B00110000 ) >> 4 ) * 10 + ( time[ 4 ] & B00001111 ); // day of month
time[ 5 ] = ( ( time[ 5 ] & B00010000 ) >> 4 ) * 10 + ( time[ 5 ] & B00001111 ); // month
time[ 6 ] = ( ( time[ 6 ] & B11110000 ) >> 4 ) * 10 + ( time[ 6 ] & B00001111 ); // year
}
}
void setTime( byte newTime[ 7 ] ) // sets the time in the RTC register to the given values
{
for(int i = 0; i < 7; i++)
newTime[i] = decToBcd(newTime[i]); // the time consists of 7 bytes, each which must be converted to binary-coded decimal
setBytes( DS3231_TIME_CAL_ADDR, newTime, 7 ); // bytes are sent to be written
}
void getRTCTemperature() // reads the temperature from the register and updates the global temperature float
{
//temp registers (11h-12h) get updated automatically every 64s
if( getBytes( DS3231_TEMPERATURE_ADDR, 2 ) ) // if 2 bytes were read from the temperature addresss
{
temperature = ( received[ 0 ] & B01111111 ); // assign the integer part of the integer
temperature += ( ( received[ 1 ] >> 6 ) * 0.25 ); // assign the fractional part of the temperature
}
}
void gprsListen()
{
if( GPRS.available() ) { // If the GPRS Shield is transmitting data to the Stalker...
while( GPRS.available() ) { // While there is still data left...
buffer[ count++ ] = GPRS.read(); // get the next byte of data
if ( count == 64 ) // we only handle a maximum of 64 bytes of data at a time
break;
}
Serial.write( buffer, count ); // Send the data to the serial line
analise( buffer, count );
clearBufferArray(); // clear the buffer
count = 0; // reset counter
}
if (Serial.available()) // if the Stalker is transmitting data....
GPRS.write(Serial.read()); // send the data to the GPRS Shield.
}
void printTime() // updates time, and prints it in a convenient format
{
getTime();
Serial.print( int( time[ 3 ] ) ); // dow
Serial.print( ' ' );
Serial.print( int( time[ 2 ] ) ); // hour
Serial.print( ':' );
Serial.print( int( time[ 1 ] ) ); // minute
Serial.print( ':' );
Serial.print( int( time[ 0 ] ) ); // second
Serial.print( ' ' );
Serial.print( int( time[ 4 ] ) ); // day
Serial.print( '/' );
Serial.print( int( time[ 5 ] ) ); // month
Serial.print( "/20" );
Serial.print( int( time[ 6 ] ) ); // year
Serial.println();
}
/*
End of RTC code
*/
void setup()
{
// GPRS Shield startup code
GPRS.begin( 9600 );
delay(1000);
setPowerStateTo(1);
delay(1000);
// RTC Startup code
Wire.begin();
delay(1000);
Serial.begin(9600);
delay(1000);
}
void loop()
{
gprsListen(); // GPRS Shield listener. Todo: replace w interrupt
getTime(); // Updates the time. Todo: replace w interrupt
}

View File

@ -0,0 +1,330 @@
SoftwareSerial GPRS( 7, 8 );
byte buffer[ 64 ];
int count = 0, e = 0, count2 = 0, t = 0, q;
char temp, lastCaller[13] = ;
boolean callIncoming = false, done;
byte time[ 7 ];
byte time_A1[ 5 ];
byte time_A2[ 4 ];
byte received[1];
float temperature;
char telescopeNames[6][4];
void setPowerStateTo( int newState )
{
if( newState != 1 && newState != 0 ) {
Serial.print( );
Serial.print( getPowerState() );
Serial.print( );
}
else {
if( newState == getPowerState() ) {
Serial.print( );
Serial.print( newState );
Serial.print( );
}
else {
powerUpOrDown();
Serial.print( );
Serial.print( 1 - newState );
Serial.print( );
Serial.print( newState );
Serial.print( );
}
}
delay( 5000 );
}
int getPowerState()
{
int ret;
if ( digitalRead(18) == 0 && digitalRead(19) == 0 )
ret = 1;
else
ret = 0;
return ret;
}
void powerUpOrDown()
{
pinMode( 9, OUTPUT );
digitalWrite( 9, LOW );
delay( 1000 );
digitalWrite( 9, HIGH );
delay( 2000 );
digitalWrite( 9, LOW );
delay( 3000 );
}
void clearBufferArray()
{
for( int i = 0; i < count; i++ )
buffer[ i ] = NULL;
}
void makeMissedCall( char num[] )
{
int i;
char in[ 18 ] = ;
for( i = 3; i <= 14; i++ )
in[ i ] = num[ i - 3] ;
in[ 15 ] = ;
in[ 16 ] = '\r';
in[ 17 ] = '\0';
GPRS.write( in );
delay( 10000 );
GPRS.write( );
delay( 1000 );
}
void sendTextMessage( char number[], char messg[] )
{
char temp[ 27 ] = ;
for( q = 0; q < 12; q++ )
temp[ q + 13 ] = number[ q ];
temp[ 25 ] = ;
temp[ 26 ] = '\0';
GPRS.println( );
delay( 1000 );
GPRS.println( temp );
delay( 1000 );
GPRS.println( messg );
delay( 1000 );
GPRS.println( (char) 26 );
delay( 1000 );
}
void analise(byte incoming[], int length)
{
e = 0;
done = false;
while( e < length && !done){
temp = char( incoming[e] );
switch( temp ){
case :
{
if( length > e + 3 && !callIncoming ) {
if(char( incoming[e + 1] ) ==
&& char( incoming[e + 2] ) ==
&& char( incoming[e + 3] ) == ){
GPRS.write( );
delay(500);
GPRS.write( );
callIncoming = true;
done = true;
}
}
}
break;
case :
{
if(char( buffer[ e + 1]) == && length > e + 11 && callIncoming){
for(t = 0; t < 12; t++)
lastCaller[t] = char( buffer[ e + t ]);
lastCaller[12] = '\0';
callIncoming = false;
done = true;
}
}
break;
case :
Serial.println(lastCaller);
break;
}
e++;
}
}
byte decToBcd( byte b )
{
return ( b / 10 << 4 ) + b % 10;
}
boolean getBit( byte addr, int pos )
{
byte temp = getByte( addr );
return boolean( (temp >> pos) & B00000001 );
}
void setBit( byte addr, int pos, boolean newBit )
{
boolean oldBit = getBit( addr, pos );
byte temp = received[ 0 ];
if ( oldBit != newBit )
{
if( newBit )
temp += (B00000001 << pos);
else
temp -= (B00000001 << pos);
}
setByte( addr, temp );
}
byte getByte( byte addr )
{
byte temp;
if( getBytes( addr, 1) )
temp = received[ 0 ];
else temp = -1;
return temp;
}
boolean getBytes( byte addr, int amount )
{
boolean wireWorked = false;
Wire.beginTransmission( DS3231_I2C_ADDRESS );
Wire.write( addr );
Wire.endTransmission();
Wire.requestFrom( DS3231_I2C_ADDRESS, amount );
if( Wire.available() ){
received[amount];
for( int i = 0; i < amount; i++){
received[ i ] = Wire.read();
}
wireWorked = true;
}
return wireWorked;
}
void setByte( byte addr, byte newByte )
{
setBytes( addr, &newByte, 1);
}
void setBytes( byte addr, byte newBytes[], int amount )
{
Wire.beginTransmission( DS3231_I2C_ADDRESS );
Wire.write( addr );
for( int i = 0; i < amount; i++ )
Wire.write( newBytes[ i ] );
Wire.endTransmission();
}
void getTime()
{
if( getBytes( DS3231_TIME_CAL_ADDR, 7) )
{
for(int i = 0; i < 7; i++)
time[ i ] = received[ i ];
time[ 0 ] = ( ( time[ 0 ] & B01110000 ) >> 4 ) * 10 + ( time[ 0 ] & B00001111 );
time[ 1 ] = ( ( time[ 1 ] & B01110000 ) >> 4 ) * 10 + ( time[ 1 ] & B00001111 );
time[ 2 ] = ( ( time[ 2 ] & B00110000 ) >> 4 ) * 10 + ( time[ 2 ] & B00001111 );
time[ 4 ] = ( ( time[ 4 ] & B00110000 ) >> 4 ) * 10 + ( time[ 4 ] & B00001111 );
time[ 5 ] = ( ( time[ 5 ] & B00010000 ) >> 4 ) * 10 + ( time[ 5 ] & B00001111 );
time[ 6 ] = ( ( time[ 6 ] & B11110000 ) >> 4 ) * 10 + ( time[ 6 ] & B00001111 );
}
}
void setTime( byte newTime[ 7 ] )
{
for(int i = 0; i < 7; i++)
newTime[i] = decToBcd(newTime[i]);
setBytes( DS3231_TIME_CAL_ADDR, newTime, 7 );
}
void getRTCTemperature()
{
if( getBytes( DS3231_TEMPERATURE_ADDR, 2 ) )
{
temperature = ( received[ 0 ] & B01111111 );
temperature += ( ( received[ 1 ] >> 6 ) * 0.25 );
}
}
void gprsListen()
{
if( GPRS.available() ) {
while( GPRS.available() ) {
buffer[ count++ ] = GPRS.read();
if ( count == 64 )
break;
}
Serial.write( buffer, count );
analise( buffer, count );
clearBufferArray();
count = 0;
}
if (Serial.available())
GPRS.write(Serial.read());
}
void printTime()
{
getTime();
Serial.print( int( time[ 3 ] ) );
Serial.print( );
Serial.print( int( time[ 2 ] ) );
Serial.print( );
Serial.print( int( time[ 1 ] ) );
Serial.print( );
Serial.print( int( time[ 0 ] ) );
Serial.print( );
Serial.print( int( time[ 4 ] ) );
Serial.print( );
Serial.print( int( time[ 5 ] ) );
Serial.print( );
Serial.print( int( time[ 6 ] ) );
Serial.println();
}
void setup()
{
GPRS.begin( 9600 );
delay(1000);
setPowerStateTo(1);
delay(1000);
Wire.begin();
delay(1000);
Serial.begin(9600);
delay(1000);
}
void loop()
{
gprsListen();
getTime();
}

View File

@ -0,0 +1,13 @@
CapacitiveSensorDue cs_13_8 = CapacitiveSensorDue(13,8);
void setup()
{
Serial.begin(9600);
}
void loop()
{
long total1 = cs_13_8.read(30);
Serial.println(total1);
delay(100);
}

View File

@ -13,10 +13,16 @@ public class PdePreprocessorTest {
public void testSourceWithQuoteAndDoubleQuotesEscapedAndFinalQuoteShouldNotRaiseException() throws Exception {
String s = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("RemoteCallLogger_v1e0.ino").getFile()));
String actualOutput = new PdePreprocessor().strip(s);
PdePreprocessor pdePreprocessor = new PdePreprocessor();
String actualOutput = pdePreprocessor.strip(s);
String expectedOutput = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("RemoteCallLogger_v1e0.stripped.ino").getFile()));
assertEquals(expectedOutput, actualOutput);
pdePreprocessor.writePrefix(s);
assertEquals(2, pdePreprocessor.getExtraImports().size());
assertEquals("SoftwareSerial.h", pdePreprocessor.getExtraImports().get(0));
assertEquals("Wire.h", pdePreprocessor.getExtraImports().get(1));
}
@Test
@ -24,8 +30,67 @@ public class PdePreprocessorTest {
String s = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("IncludeBetweenMultilineComment.ino").getFile()));
PdePreprocessor pdePreprocessor = new PdePreprocessor();
String actualOutput = pdePreprocessor.strip(s);
String expectedOutput = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("IncludeBetweenMultilineComment.stripped.ino").getFile()));
assertEquals(expectedOutput, actualOutput);
pdePreprocessor.writePrefix(s);
assertEquals(1, pdePreprocessor.getExtraImports().size());
assertEquals("CapacitiveSensorDue.h", pdePreprocessor.getExtraImports().get(0));
}
@Test
public void testPdePreprocessorRegressionBaladuino() throws Exception {
String s = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("Baladuino.ino").getFile()));
PdePreprocessor pdePreprocessor = new PdePreprocessor();
String actualOutput = pdePreprocessor.strip(s);
String expectedOutput = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("Baladuino.stripped.ino").getFile()));
assertEquals(expectedOutput, actualOutput);
pdePreprocessor.writePrefix(s);
assertEquals(9, pdePreprocessor.getExtraImports().size());
assertEquals("Balanduino.h", pdePreprocessor.getExtraImports().get(0));
assertEquals("Wire.h", pdePreprocessor.getExtraImports().get(1));
assertEquals("usbhub.h", pdePreprocessor.getExtraImports().get(2));
assertEquals("adk.h", pdePreprocessor.getExtraImports().get(3));
assertEquals("Kalman.h", pdePreprocessor.getExtraImports().get(4));
assertEquals("XBOXRECV.h", pdePreprocessor.getExtraImports().get(5));
assertEquals("SPP.h", pdePreprocessor.getExtraImports().get(6));
assertEquals("PS3BT.h", pdePreprocessor.getExtraImports().get(7));
assertEquals("Wii.h", pdePreprocessor.getExtraImports().get(8));
}
@Test
public void testStringWithCcomment() throws Exception {
String s = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("StringWithCcomment.ino").getFile()));
PdePreprocessor pdePreprocessor = new PdePreprocessor();
String actualOutput = pdePreprocessor.strip(s);
String expectedOutput = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("StringWithCcomment.stripped.ino").getFile()));
assertEquals(expectedOutput, actualOutput);
pdePreprocessor.writePrefix(s);
assertEquals(0, pdePreprocessor.getExtraImports().size());
}
@Test
public void testCharWithEscapedDoubleQuote() throws Exception {
String s = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("CharWithEscapedDoubleQuote.ino").getFile()));
PdePreprocessor pdePreprocessor = new PdePreprocessor();
String actualOutput = pdePreprocessor.strip(s);
String expectedOutput = FileUtils.readFileToString(new File(PdePreprocessorTest.class.getResource("CharWithEscapedDoubleQuote.stripped.ino").getFile()));
assertEquals(expectedOutput, actualOutput);
pdePreprocessor.writePrefix(s);
assertEquals(2, pdePreprocessor.getExtraImports().size());
assertEquals("SoftwareSerial.h", pdePreprocessor.getExtraImports().get(0));
assertEquals("Wire.h", pdePreprocessor.getExtraImports().get(1));
}
}

View File

@ -0,0 +1,9 @@
void setup() {
// put your setup code here, to run once:
Serial.println("Accept: */*");
}
void loop() {
// put your main code here, to run repeatedly:
}

View File

@ -0,0 +1,9 @@
void setup() {
Serial.println( );
}
void loop() {
}