/*
* THIS IS WRITTEN FOR NodeMCU ESP-12E Development Board V.1.0 with Motor Shield
* It has only 1 analog port. Not used on this example.
* I have to use AnalogWrite to make servo work as PWM
* COPY RIGHT to Hyun Ja, but you may use freely as it fits to you.
* I bare absolutely no responsibility for you on using this code.
* 코드의 소유권은 제작자 Hyun Ja 에게 있는데 무상으로 사용하세요.
* 사용시 발생하는 일에 책임 무. 마음껏 변경해서 실험하세요.
*/
#include <Servo.h>
#include <ESP8266WiFi.h>
#include <WiFiClient.h>
#include <ESP8266WebServer.h>
#include <ESP8266mDNS.h>
// #include "esp12_accesspoint.ino"
/* Set these to your desired credentials. */
const char* ssid = "당신의 집 와이파이 아이디"; // Your home wifi ID
const char* password = "당신의 집 와이파이 패스워드"; // Your home wifi password
ESP8266WebServer server(80);
int P2B_NEWLINE = 11; // < -- Beginning of Command to BOT (ESP-BOT)
int P2B_COM_TYPE = 12; // 0..9 -- First 2 letters following "<"
// Total Command Types : 10 x 10 = 100
int P2B_DATA = 12; // Data section
int P2B_ENDING = 13; // > -- End of Message Signal
int P2B_STAT_NONE = 1; // Do nothing until '<' has received
int P2B_STAT_CMD = 2; // Accepting Command
int P2B_STAT_DATA = 3; // Accepting Command data
int P2B_STAT_END = 4; // '>' has receieve, it is the end of command;
char p2b_command[3];
char p2b_data[20];
int p2b_pin = 0;
int p2b_value = 0;
int p2b_status = 0;
int iD0 = 16; // GPIO 16; 'Head-Light (On/Off)';
int iD1 = 5; // GPIO 5; 'L298-L-Dir1'; // Motor A on Motor Board
int iD2 = 4; // GPIO 4; 'L298-R-Dir1'; // Motor B on Motor Board
int iD3 = 0; // GPIO 0; 'L298-L-Dir2'; // Motor A on Motor Board
int iD4 = 2; // GPIO 2; 'L298-R-Dir2'; // Motor B on Motor Board
int iD5 = 14; // GPIO 14; 'PWM (Right Wheel)';
int iD6 = 12; // GPIO 12; 'PWM (Left Wheel)';
int iD7 = 13; // GPIO 13; ' ';
int iD8 = 15; // GPIO 15; ' ';
int iD9 = 3; // GPIO 3; '(IN) Back Bumper';
int iD10 = 1; // GPIO 1; '(*) Built-in Blue LED';
int iD11 = 9; // GPIO 9; '(IN) Front Left';
int iD12 = 10; // GPIO 10; '(IN) Front Right';
int iA0 = 0; // ADC0; '(AD) Battery Level';
// These are PWM Speed control using PWM
int speadServoLeft = 0; // define the spead Left Servo Wheel (0 = disable pwm) using GPIO-5
int speadServoRight = 0; // define the spead Right Servo Wheel (0 = disable pwm) using GPIO-4
int speedLeftDC = 0; // Control Speed of Left DC Motor Wheel using GPIO-0
int speedRightDC = 0; // Control Speed of Right DC Motor Wheel using GPIO-12
// The only Analog Port will be used to check battery level
int analog_BatteryLevel = 0;
// Head Light using relay
int HeadLight = iD0; // using GPIO = 16 to turn on/off relay
int servo1pin=7; // define the pin to be used for servo1
int servo1speed=89; // middle value for servo 0 ~ 179
int runmode = 3; // 1 : Remote Joy, 3 : Serial Comm. Test Mode
int analog_JoyX = 0; // Value sent from PC
int analog_JoyY = 0; // Value sent from PC
int p_analog_JoyX = 0; // Previous Analog 0
int p_analog_JoyY = 0; // Previous Analog 1
int i = 0; // dumb int
int j = 0; // dumb int
int k = 0; // dumb int
int lp =0; // dumb last position ofinput command string
char inputString[200]; // a string to hold incoming data
boolean stringComplete = false; // whether the string is complete
char inChar;
String tempStr;
int inlen = 0; // Length of inputString
char remoteString[50];
int param1 = -1; // value from PC Command (Param 1)
int param2 = -1; // value from PC Command (Param 2)
boolean SecondParam = false; // Now gettign second parameter (after ,)
// twelve servo objects can be created on most boards
Servo LeftServoWheel; // create servo object to control a servo
Servo RightServoWheel; // create servo object to control a servo
int UseServoWheel = 1; // 1 : Use servo, 2 : Use DC Motor Wheels
void ClearP2BCommand()
{
p2b_command[0] = 0; // null
p2b_command[1] = 0; // null
for (int i=0; i <= 19; i++){
p2b_data[i] = 0; // null
}
p2b_pin = 0;
p2b_value = 0;
param1 = -1; // set as none, 0 could be value
param2 = -1; // set as none, 0 could be value
SecondParam = false;
}
void SetP2BDigitalDirection(int pinno, int mode) // Set INPUT or OUTPUT
{
if (mode == 0) {
pinMode(pinno, INPUT);
} else {
pinMode(pinno, OUTPUT);
}
}
// This function is only useful if the pin is set to OUTPUT
void WriteP2BDigitalValue(int pinno, int value)
{
digitalWrite(pinno, value); // Value can only be 0 or 1 (turn Off(0) / On(1) )
}
/* Just a little test message. Go to http://192.168.4.1 in a web browser
* connected to this access point to see it.
*/
void handleRoot() {
server.send(200, "text", "You are connected IoP [Wifi Things to Internet]");
}
void handleWebCommands() {
String message = "Handling Web Commands\n\n";
message += "URI: ";
message += server.uri();
message += "\nMethod: ";
message += ( server.method() == HTTP_GET ) ? "GET" : "POST";
message += "\nArguments: ";
message += server.args();
message += "\n";
for ( uint8_t i = 0; i < server.args(); i++ ) {
message += " " + server.argName ( i ) + ": " + server.arg ( i ) + "\n";
}
//server.send ( 2004, "text/plain", message );
// Top portion is the debugging section
ClearP2BCommand();
p2b_command[0] = server.uri()[1];
p2b_command[1] = server.uri()[2];
message += "Command : ";
message += p2b_command;
message += "\n";
if (server.args() == 1) {
param1 = (byte(server.arg(0)[0]) - 48) * 100; // 48 = ord(0)
param1 = param1 + (byte(server.arg(0)[1]) - 48) * 10; // 48 = ord(0)
param1 = param1 + (byte(server.arg(0)[2]) - 48);
};
message += "Param1 : ";
message += server.arg(0);
message += "\n";
server.send ( 2004, "text/plain", message );
ExecuteLogicalCommand();
}
void setup()
{
Serial.begin(115200); // for communication
// Setting up Access Point and as a Web Server
Serial.println();
Serial.print("Configuring access point...");
// Wait for connection
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print("?");
};
Serial.println("");
Serial.print("Connected to ");
Serial.println(ssid);
Serial.print("IP address: ");
Serial.println(WiFi.localIP());
if (MDNS.begin("esp8266")) {
Serial.println("MDNS responder started");
};
if (UseServoWheel == 1) {
LeftServoWheel.attach(iD5); // GPIO 14
RightServoWheel.attach(iD6); // GPIO 12
pinMode(iD2,OUTPUT); // Main Light using : Motor B Port
pinMode(iD4,OUTPUT); // Main Light using : Motor B Port
} else {
pinMode(iD1,OUTPUT); // L298-L-Dir1 // Motor A
pinMode(iD2,OUTPUT); // L298-R-Dir1 // Motor B
pinMode(iD3,OUTPUT); // L298-L-Dir2 // Motor A
pinMode(iD4,OUTPUT); // L298-R-Dir2 // Motor B
};
pinMode(HeadLight, OUTPUT); // iD0
digitalWrite(HeadLight, HIGH); // Off for Begining (HIGH = off, LOW = on
server.on("/", handleRoot);
server.onNotFound(handleWebCommands);
server.begin();
Serial.println("HTTP server started");
}
void stop()//
{
if (UseServoWheel == 1) {
LeftServoWheel.write(0); // Stop
RightServoWheel.write(0); // Stop
} else {
digitalWrite(speedLeftDC, LOW);// Disable the pin, to stop the motor. this should be done to avid damaging the motor.
digitalWrite(speedRightDC,LOW);
};
delay(50);
}
void run_left_wheel() {
if (UseServoWheel == 1) {
LeftServoWheel.write(speadServoLeft);
} else {
if (speedLeftDC > 0) {
analogWrite(iD3,abs(speedLeftDC));//input a simulation value to set the speed
digitalWrite(iD4, LOW);
digitalWrite(iD5, HIGH); //turn DC Motor A move anticlockwise
} else {
analogWrite(iD3,abs(speedLeftDC));//input a simulation value to set the speed
digitalWrite(iD4, HIGH);
digitalWrite(iD5, LOW); //turn DC Motor A move clockwise
};
};
}
void run_right_wheel() {
if (UseServoWheel == 1) {
RightServoWheel.write(speadServoRight);
} else {
if (speedRightDC > 0) {
analogWrite(iD6,abs(speedRightDC));
digitalWrite(iD7,LOW); //turn DC Motor B move anticlockwise
digitalWrite(iD8,HIGH);
} else {
analogWrite(iD6,abs(speedRightDC));
digitalWrite(iD7,HIGH); //turn DC Motor B move clockwise
digitalWrite(iD8,LOW);
};
};
}
void ExecuteLogicalCommand()
{
// tempStr = "<!";
// tempStr += (char)p2b_command[0];
// tempStr += (char)p2b_command[1];
// tempStr += "::";
// tempStr += param1;
// tempStr += ">";
// Serial.println(tempStr);
// ST : STOP WHEELS : Params (none)
if (((char)p2b_command[0] == 'S') and ((char)p2b_command[1] == 'T')) { // No need params
tempStr = "<*";
tempStr += "ST=";
tempStr += param1;
tempStr += ">";
Serial.println(tempStr);
stop();
};
// MW : MOVE WHEELS : Params ( Left Speed, Right Speed )
if (((char)p2b_command[0] == 'M') and ((char)p2b_command[1] == 'W')) { // Need two params
tempStr = "<*";
tempStr += "MW=";
tempStr += param1;
tempStr += ",";
tempStr += param2;
tempStr += ">";
Serial.println(tempStr);
speedLeftDC = param1-512;
speadServoLeft = (param1 / 5);
run_left_wheel();
speedRightDC = param2-512;
speadServoRight = (param2 / 5);
run_left_wheel();
};
// HL : TURN ON HEADLIGHT : Params ( On(1) or Off(0) )
if (((char)p2b_command[0] == 'H') and ((char)p2b_command[1] == 'L')) {
tempStr = "<*";
tempStr += "HL=";
tempStr += param1;
tempStr += ">";
Serial.println(tempStr);
digitalWrite(HeadLight, param1);
};
// ML : TURN ON MAIN LIGHT : Params ( On(1) or Off(0) )
if (((char)p2b_command[0] == 'M') and ((char)p2b_command[1] == 'L')) {
tempStr = "<*";
tempStr += "ML=";
tempStr += param1;
tempStr += ">";
Serial.println(tempStr);
if (param1 == 1) {
digitalWrite(iD2, 0);
digitalWrite(iD4, 0);
} else {
digitalWrite(iD2, 1);
digitalWrite(iD4, 1);
}
};
// RS + Speed : Right-wheel Speed = value
if (((char)p2b_command[0] == 'R') and ((char)p2b_command[1] == 'S')) {
speedRightDC = param1-512;
speadServoRight = (param1 / 5);
if (UseServoWheel == 1) {
tempStr = "<*";
tempStr += "RS=";
tempStr += speadServoRight;
tempStr += ">";
Serial.println(tempStr);
};
run_right_wheel();
};
// LS + Speed : Right-wheel Speed = value
if (((char)p2b_command[0] == 'L') and ((char)p2b_command[1] == 'S')) {
speedLeftDC = param1-512;
speadServoLeft = (param1 / 5);
if (UseServoWheel == 1) {
tempStr = "<*";
tempStr += "LS=";
tempStr += speadServoLeft;
tempStr += ">";
Serial.println(tempStr);
};
run_left_wheel();
};
}
void loop()
{
server.handleClient();
if (runmode == 1) { // : Remote Joystick Mode
speedLeftDC = ((analog_JoyX-512) / 2);
speedRightDC = ((analog_JoyY-512) / 2);
if (speedLeftDC > 0) {
run_left_wheel();
};
if (speedRightDC > 0) {
run_right_wheel();
};
delay(100);
}; // if (runmode == 1) : Remote Joystick Mode
while (Serial.available()) {
// get the new byte:
inChar = (char)Serial.read();
// add it to the inputString:
inputString[i] = inChar;
i++;
// if the incoming character is a newline, set a flag
if ((inChar == '#') or (inChar == '<')) {
p2b_status = P2B_STAT_CMD;
ClearP2BCommand();
j = i-1;
} else if (inChar == '>') { // so the main loop can do something about it:
p2b_command[0] = inputString[j+1];
p2b_command[1] = inputString[j+2];
Serial.print("<"); // command
Serial.print(p2b_command);
Serial.print(":");
// this will set the params 1 and/or param2
param1 = (byte(inputString[j+4]) - 48) * 100; // 48 = ord(0)
param1 = param1 + (byte(inputString[j+5]) - 48) * 10; // 48 = ord(0)
param1 = param1 + (byte(inputString[j+6]) - 48);
Serial.print(param1);
if (inputString[j+7] == ',') {
SecondParam = true;
param2 = (byte(inputString[j+8]) - 48) * 100; // 48 = ord(0)
param2 = param2 + (byte(inputString[j+9]) - 48) * 10; // 48 = ord(0)
param2 = param2 + (byte(inputString[j+10]) - 48);
Serial.print(',');
Serial.print(param2);
}
Serial.println(">");
ExecuteLogicalCommand();
i = 0; // refresh counter
stringComplete = true;
p2b_status = P2B_STAT_NONE;
} else {
lp = i-1; // set last position on each entry;
}
}
if (stringComplete) {
for (i=0;i<=199;i++) {
inputString[i] = 0;
};
// clear the string:
for (i=0;i<=199;i++) {
inputString[i] = 0;
};
i = 0;
stringComplete = false;
};
}
'NodeMCU' 카테고리의 다른 글
Wireless 바코드 스캔 피드백 (0) | 2016.04.11 |
---|---|
GY-88을 NodeMCU (ESP-12E) 모듈과 I2C로 연결해서 사용하기 (0) | 2016.03.10 |
NodeMCU w/ Motor Sheild 예문의 실제 실험 사진들 (0) | 2015.11.09 |