-
-
Save billbonney/0bbb90699f6d36f853d1 to your computer and use it in GitHub Desktop.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
/* | |
* Serial_Comm_Nano.ino | |
* | |
*/ | |
///@file Serial_Comm_Nano.ino | |
///@brief AT-command compatible cellular/GPRS/IP modem initialization & communication for SIM900D -> Arduino -> ArduCopter | |
///@author Robert Haddad | |
///@date 25-10-2014 | |
#include <SoftwareSerial.h> // Include SoftwareSerial Library | |
//Serial Communication Ports | |
#define rxPin 4 // TX from GSM Modem to RX on Arduino | |
#define txPin 5 // RX from GSM Modem to TX on Arduino | |
#define LED 12 // All Good LED Turns green when data is being sent over UDP Connection | |
#define ERR 11 // Error LED Turns Red when error is encountered, turns off if all is okay | |
#define powerKey 3 // Set PWRKEY pin | |
#define resetPin 2 // Set reset pin | |
boolean isReady = false; // GSM modem is Ready to receive AT Commands flag | |
int count = 0; // Counter for instances of an error (For monitor/debug only); | |
String checker = ""; | |
// set up a new serial port for GSM Module | |
SoftwareSerial mySerial = SoftwareSerial(rxPin, txPin); // Initialize mySerial SoftwareSerial | |
// Setup procedure | |
void setup() | |
{ | |
pinMode(rxPin, INPUT); // Set pin mode to input for Software serial RX Pin | |
pinMode(txPin, OUTPUT); // Set pin mode to output for Software serial TX Pin | |
pinMode(LED, OUTPUT); // All Good LED | |
pinMode(ERR, OUTPUT); // Warning LED | |
digitalWrite(LED,LOW); // Set All Good LED to Off | |
digitalWrite(ERR,LOW); // Set Warning LED to Off | |
digitalWrite(resetPin, HIGH); // Set reset pin to high | |
// Set Data Rate for Serial Ports | |
mySerial.begin(57600); // Start GSM Module Serial Communication @ 57,600 Baud Rate | |
pinMode(resetPin, OUTPUT); // Set reset pin to output | |
// Wait 3 Seconds for power on (Add Auto on feature through GSM module power button pin | |
startUPWait(); | |
// Initializing GSM Module | |
mySerial.print("AT\r"); | |
while(!isReady){ | |
if(mySerial.available()){ | |
String b=mySerial.readString(); | |
if(b.indexOf("+CREG: 1") > 0 || b.indexOf("+CREG: 2") > 0){ | |
isReady = true; | |
//while(!sendATCommand("AT+IPR=57600","OK",100)); // Uncomment to set Modem Baudrate | |
//while(!sendATCommand("AT&W","OK",100)); // Uncomment to write settings to non-volatile memory | |
while(!sendATCommand("AT V1 E1 X1 S0=0","OK",100)); // Set error response and do not pickup on ring | |
while(!sendATCommand("AT+CREG=2","OK",100)); // Set various notice messages and parameters | |
while(!sendATCommand("AT+CMEE=2","OK",100)); | |
while(!sendATCommand("AT+CR=1","OK",100)); | |
while(!sendATCommand("AT+CRC=1","OK",100)); | |
while(!sendATCommand("AT+CSNS=4","OK",100)); | |
while(!sendATCommand("AT+CSMINS=1","OK",100)); | |
while(!sendATCommand("AT+CSCLK=0","OK",100)); | |
while(!sendATCommand("AT+CIURC=1","OK",100)); | |
while(!sendATCommand("AT+CGEREP=2","OK",100)); | |
while(!sendATCommand("AT+CIPMUX=0","OK",100)); // Single channel communication (ie only one socket can be opened) | |
while(!sendATCommand("AT+CIPMODE=1","OK",100)); // Transparent bridge mode | |
while(!sendATCommand("AT+CIPCCFG=8,10,400,0","OK",100)); // GPRS params | |
mySerial.print("AT+CMUX=0,0,4,32768,10,3,30,10,2\r"); // GPRS/IP params | |
delay(2000); | |
while(!sendATCommand("AT+CGATT?","OK",1000)); // Make sure GPRS is Attached | |
while(!sendATCommand("AT+CSTT= \"zain\",\"\",\"\"","OK",1000)); // AT+CSTT="APN","username","password" - login to service provider/carrier | |
while(!sendATCommand("AT+CIICR","OK",1000)); // Connect! | |
while(!sendATCommand("AT+CIFSR",".",100)); // Get IP address (for info only); | |
while(!sendATCommand("AT+CLPORT=\"UDP\",8888","OK",100)); // Prep UDP Port 8888 | |
while(!sendATCommand("AT+CIPSTART=\"UDP\",\"drone.dyndns.biz\",8888","OK",1000)); // AT+CIPSTART="protocol","ip address or domain","port #" | |
Serial.begin(57600); // Start Serial port for communication with Ardupilot | |
digitalWrite(LED,HIGH); // Turn on All Good LED | |
digitalWrite(ERR,LOW); // Turn off Warning LED | |
delay(1000); | |
digitalWrite(LED,LOW); | |
} else { | |
digitalWrite(ERR,HIGH); // Turn on Warning LED | |
digitalWrite(LED,LOW); // Turn off All Good LED | |
} | |
} | |
} | |
} | |
// AT Command Sender | |
boolean sendATCommand(String input, String output, int wait){ // AT Command, Expected Result, Delay before issue command | |
boolean resp = false; | |
mySerial.print(input + "\r"); // Send input command to modem | |
delay(wait); // Delay function time "wait" variable | |
while(!resp){ | |
if(mySerial.available()){ // Check if response is available | |
String b=mySerial.readString(); // Store response string in "b" | |
mySerial.read(); // Clear buffer again | |
if(b.indexOf(output) > 0){ // True if expected result is returned | |
resp = true; | |
count = 0; | |
digitalWrite(LED,HIGH); // Green LED ON | |
digitalWrite(ERR,LOW); // Warning LED OFF | |
digitalWrite(LED,LOW); // Green LED OFF | |
return resp; | |
} else if(b.indexOf("DEACT") > 0 || b.indexOf("NORMAL POWER DOWN") > 0){ // Check if lost connection or modem power down | |
if(powerUpOrDown()){ // Reset comm hardware | |
digitalWrite(resetPin,LOW); // Restart Modem | |
} | |
} else { | |
digitalWrite(ERR,HIGH); // Warning LED ON | |
count++; | |
return resp; | |
} | |
} | |
} | |
} | |
//Start Up Wait Period with LEDs | |
void startUPWait(){ | |
digitalWrite(LED,HIGH); | |
digitalWrite(ERR,LOW); | |
delay(500); | |
digitalWrite(LED,LOW); | |
digitalWrite(ERR,HIGH); | |
delay(500); | |
digitalWrite(LED,HIGH); | |
digitalWrite(ERR,LOW); | |
delay(500); | |
digitalWrite(LED,LOW); | |
digitalWrite(ERR,HIGH); | |
delay(500); | |
digitalWrite(LED,HIGH); | |
digitalWrite(ERR,HIGH); | |
delay(1000); | |
digitalWrite(LED,LOW); | |
digitalWrite(ERR,LOW); | |
} | |
// Main Loop | |
void loop(){ | |
digitalWrite(LED,HIGH); // Keep Green LED ON while connected | |
// Relay All GSM Module communication to Autopilot | |
if(mySerial.available()){ | |
char b=mySerial.read(); | |
Serial.write(b); | |
// Check For Disconnection | |
checker += b; | |
if(checker.indexOf("\n") > 0 || checker.indexOf("\r") > 0){ // Check for new line | |
if(checker.indexOf("DEACT") > 0 || checker.indexOf("NORMA") > 0){ // Check for lost connection or Modem power down | |
digitalWrite(LED,LOW); // Green LED OFF | |
digitalWrite(ERR,HIGH); // Warning LED ON | |
if(powerUpOrDown()){ // Reset Comm Hardware | |
digitalWrite(resetPin,LOW); // Reset Modem | |
} | |
} | |
checker = ""; | |
} | |
digitalWrite(ERR,HIGH); // Flash Warning LED on data send/receive | |
digitalWrite(ERR,LOW); | |
//Serial.print(b); | |
} | |
// Relay all Autopilot communication to GSM module and USB (USB for monitor/debug only) | |
if(Serial.available()){ | |
char c=Serial.read(); | |
mySerial.write(c); | |
digitalWrite(ERR,HIGH); // Flash Warning LED on data send/receive | |
digitalWrite(ERR,LOW); | |
} | |
} | |
boolean powerUpOrDown() // Cycle power on Modem | |
{ | |
boolean powered = false; | |
pinMode(powerKey, OUTPUT); | |
digitalWrite(powerKey,LOW); | |
delay(1000); | |
digitalWrite(powerKey,HIGH); | |
delay(2000); | |
digitalWrite(powerKey,LOW); | |
delay(3000); | |
powered = true; | |
return powered; | |
} |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment