esp8266 改造遥控小车

sean 编辑于2021-06-07 13:51硬件相关

esp8266本身有wifi,加上一个电机驱动板就可以改造无线电机驱动小车。碰巧之前遥控小车无线遥控板被撞坏了,于是就用这套板改造了一下:

这个是这块电机驱动板的接口和node mcu esp8266的接口对应:

目前的代码是单通道的操作,比较笨拙,以后有时间调成易操作性,上代码:

/******************* WiFi Robot Remote Control Mode ********************/
#include <ESP8266WiFi.h>
#include <ESP8266WiFiMulti.h>
#include <ESP8266WebServer.h>

ESP8266WiFiMulti wifimulti;

// connections for drive Motors
int PWM_A = 5;      //GPIO5 ,D1   A后轮
int PWM_B = 4;   //GPIO4   ,D2    B前轮
int DIR_A = 0;      //GPIO0, D3
int DIR_B = 2;     //GPIO2, D4

int Light_right_pin = 16; //GPIO16, D0   这三个针的 GVO,都是不是对应的,我买的廉价板,vcc, gnd,out,都是反着的,所以接线也比较特殊,后面看到
int Light_left_pin = 14; //GPIO14, D5   开灯低点平不要奇怪。
int Beep_pin = 12; //GPIO15, D6

String command;          // String to store app command state.
int SPEED = 1020;        // 330 - 1023.
int speed_Coeff = 3 ;    //转弯系数

int forward_count;
int backward_count;
int forward_left_count;
int forward_right_count;
int backward_left_count;
int backward_right_count;
int beep_count;
int left_count; //计数器,指令执行次数,防止无限循环。
int right_count;


ESP8266WebServer server(80);      // Create a webserver object that listens for HTTP request on port 80

String webPage = "";


unsigned long previousMillis = 0;


String sta_ssid = "jiji3";      // set Wifi networks you want to connect to maxmum 32 characters
String sta_password = "2ad23aacb82f";  // set password for Wifi networks  maxmum 32 characters

String sta1_ssid = "jiji2";
String sta1_password = "c0126288c079";

String sta2_ssid = "abc";
String sta2_password = "abc";

String  my_passwd = "abcd";


void setup() {
  Serial.begin(115200);    // set up Serial library at 115200 bps
  Serial.println();
  Serial.println("*WiFi Robot Remote Control Mode*");
  Serial.println("--------------------------------------");
  webPage += "<html>";
  webPage += "<head>";
  webPage += "<meta http-equiv=content-type content=text/html; charset=UTF-8>";
  webPage += "</head>";
  webPage += "<div align=\"center\"><h1>QQNO.1 控制台</h1>";
  webPage += "<a href=\"?state=beep\"><button style=\"height:200px;width:200px\"><font size=\"20\">鸣笛</font></button></a>";
  webPage += "<a href=\"?state=lighton\"><button style=\"height:200px;width:200px\"><font size=\"20\">开灯</font></button></a>";
  webPage += "<a href=\"?state=lightoff\"><button style=\"height:200px;width:200px\"><font size=\"20\">关灯</font></button></a>";
  webPage += "</div>";
  webPage += "<div align=\"center\"><h1>方向控制</h1>";
  webPage += "<a href=\"?state=forwardleft\"><button style=\"height:200px;width:200px\"><font size=\"20\">左前</font></button></a>";
  webPage += "<a href=\"?state=forward\"><button style=\"height:200px;width:200px\"><font size=\"20\">前进</font></button></a>";
  webPage += "<a href=\"?state=forwardright\"><button style=\"height:200px;width:200px\"><font size=\"20\">右前</font></button></a>";
  webPage += "<br>";
  webPage += "<a href=\"?state=left\"><button style=\"height:200px;width:200px\"><font size=\"20\">左转</font></button></a>";
  webPage += "<a href=\"?state=stop\"><button style=\"height:200px;width:200px\"><font size=\"20\">停止</font></button></a>";
  webPage += "<a href=\"?state=right\"><button style=\"height:200px;width:200px\"><font size=\"20\">右转</font></button></a><br>";
  webPage += "<a href=\"?state=backwardleft\"><button style=\"height:200px;width:200px\"><font size=\"20\">左后</font></button></a>";
  webPage += "<a href=\"?state=backward\"><button style=\"height:200px;width:200px\"><font size=\"20\">后退</font></button></a>";
  webPage += "<a href=\"?state=backwardright\"><button style=\"height:200px;width:200px\"><font size=\"20\">右后</font></button></a>";
  webPage += "</div>";
  //webPage += "<div align=\"center\"><h1>速度更改</h1>";
  //webPage += "<a href=\"?state=1\"><button style=\"height:200px;width:200px\"><font size=\"20\">1</font></button></a>";
  //webPage += "<a href=\"?state=2\"><button style=\"height:200px;width:200px\"><font size=\"20\">2</font></button></a>";
  //webPage += "<a href=\"?state=3\"><button style=\"height:200px;width:200px\"><font size=\"20\">3</font></button></a><br>";
  //webPage += "<a href=\"?state=4\"><button style=\"height:200px;width:200px\"><font size=\"20\">4</font></button></a>";
  //webPage += "<a href=\"?state=5\"><button style=\"height:200px;width:200px\"><font size=\"20\">5</font></button></a>";
  //webPage += "<a href=\"?state=6\"><button style=\"height:200px;width:200px\"><font size=\"20\">6</font></button></a><br>";
  //webPage += "<a href=\"?state=7\"><button style=\"height:200px;width:200px\"><font size=\"20\">7</font></button></a>";
  //webPage += "<a href=\"?state=8\"><button style=\"height:200px;width:200px\"><font size=\"20\">8</font></button></a>";
  //webPage += "<a href=\"?state=9\"><button style=\"height:200px;width:200px\"><font size=\"20\">9</font></button></a>";
  //webPage += "</div>";
  webPage += "</html>";


  pinMode(Light_right_pin, OUTPUT);
  digitalWrite(Light_right_pin, HIGH);

  pinMode(Light_left_pin, OUTPUT);
  digitalWrite(Light_left_pin, HIGH);

  pinMode(Beep_pin, OUTPUT);
  digitalWrite(Beep_pin, HIGH);

  //pinMode(Beep_pin, OUTPUT);

  // Set all the motor control pins to outputs
  pinMode(PWM_A, OUTPUT);
  pinMode(PWM_B, OUTPUT);
  pinMode(DIR_A, OUTPUT);
  pinMode(DIR_B, OUTPUT);

  // Turn off motors - Initial state
  digitalWrite(DIR_A, LOW);
  digitalWrite(DIR_B, LOW);
  analogWrite(PWM_A, 0);
  analogWrite(PWM_B, 0);


  // set NodeMCU Wifi hostname based on chip mac address
  // String chip_id = String(ESP.getChipId(), HEX);
  //int i = chip_id.length()-4;
  //chip_id = chip_id.substring(i);
  //chip_id = "QQNO.2-" + chip_id;
  String  chip_id = "QQNO.1";
  String hostname(chip_id);

  Serial.println();
  Serial.println("Hostname: " + hostname);


  // first, set NodeMCU as STA mode to connect with a Wifi network
  //WiFi.mode(WIFI_STA);
  //WiFi.begin(sta_ssid.c_str(), sta_password.c_str());
  wifimulti.addAP(sta_ssid.c_str(), sta_password.c_str());
  wifimulti.addAP(sta1_ssid.c_str(), sta1_password.c_str());
  wifimulti.addAP(sta2_ssid.c_str(), sta2_password.c_str());


  // try to connect with Wifi network about 10 seconds
  unsigned long currentMillis = millis();
  previousMillis = currentMillis;
  //while (WiFi.status() != WL_CONNECTED && currentMillis - previousMillis <= 10000) {
  while (wifimulti.run() != WL_CONNECTED && currentMillis - previousMillis <= 7000) {
    delay(500);
    Serial.print(".");
    currentMillis = millis();
  }


  // if failed to connect with Wifi network set NodeMCU as AP mode
  if (wifimulti.run() == WL_CONNECTED) {
    Serial.println("");
    Serial.println("*WiFi-STA-Mode*");
    Serial.print("IP: ");
    Serial.println(WiFi.localIP());
    Serial.println("");
    Serial.print("Conneced to: ");
    Serial.println(WiFi.SSID());
    //digitalWrite(wifiLedPin, LOW);    // Wifi LED on when connected to Wifi as STA mode
    delay(3000);
  } else {
    WiFi.mode(WIFI_AP);
    WiFi.softAP(hostname.c_str(), my_passwd.c_str());
    IPAddress myIP = WiFi.softAPIP();
    Serial.println("");
    Serial.println("WiFi failed connected to " + sta_ssid + " or " + sta1_ssid);
    Serial.println("");
    Serial.println("*WiFi-AP-Mode*");
    Serial.print("AP IP address: ");
    Serial.println(myIP);
    //digitalWrite(wifiLedPin, HIGH);   // Wifi LED off when status as AP mode
    delay(3000);
  }

  server.on ( "/", root_handle );       // call the 'handleRoot' function when a client requests URI "/"
  server.onNotFound (root_handle );    // when a client requests an unknown URI (i.e. something other than "/"), call function "handleNotFound"
  server.begin();                           // actually start the server
}


void loop() {
  server.handleClient();        // listen for HTTP requests from clients
  command = server.arg("state");          // check HTPP request, if has arguments "State" then saved the value

  if (command == "forward" && forward_count == 1) Forward();          // check string then call a function or set a value
  else if (command == "backward" && backward_count == 1) Backward();
  else if (command == "forwardleft" && forward_left_count == 1) ForwardLeft();
  else if (command == "forwardright" && forward_right_count == 1) ForwardRight();
  else if (command == "backwardleft" && backward_left_count == 1) BackwardLeft();
  else if (command == "backwardright" && backward_right_count == 1) BackwardRight();
  else if (command == "right" && right_count == 1) TurnRight();
  else if (command == "left" && left_count == 1) TurnLeft();
  else if (command == "stop") Stop();
  else if (command == "lighton")TurnOnLight();
  else if (command == "lightoff")TurnOffLight();
  else if (command == "beep" && beep_count ==1)Beep();
}

void root_handle() {
  server.send ( 200, "text/html", webPage );       // Send HTTP status 200 (Ok) and send some text to the browser/client
  left_count = 1;
  right_count = 1;
  backward_count = 1;
  forward_count = 1;
  forward_left_count = 1;
  forward_right_count = 1;
  backward_left_count = 1;
  backward_right_count = 1;
  beep_count = 1;
}

//void handle_404() {
//  server.send(404, "text/plain", "404: Not found"); // Send HTTP status 404 (Not Found) when there's no handler for the URI in the request
//}

// function to stop motors
void Stop() {
  digitalWrite(DIR_A, LOW); //A后轮
  digitalWrite(DIR_B, LOW); //B前轮
  analogWrite(PWM_A, 0);
  analogWrite(PWM_B, 0);
}



// function to move forward
void Forward() {
  digitalWrite(DIR_A, HIGH); //A后轮
  digitalWrite(DIR_B, HIGH); //B前轮
  analogWrite(PWM_A, SPEED);
  analogWrite(PWM_B, 0);

  delay(400);
  if (forward_count > 0)
  {
    forward_count -= 1;
  }
  if (forward_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

void ForwardLeft() {
  digitalWrite(DIR_A, HIGH); //A后轮
  digitalWrite(DIR_B, LOW); //B前轮
  analogWrite(PWM_A, SPEED);
  analogWrite(PWM_B, SPEED);

  delay(400);
  if (forward_left_count > 0)
  {
    forward_left_count -= 1;
  }
  if (forward_left_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

void ForwardRight() {
  digitalWrite(DIR_A, HIGH); //A后轮
  digitalWrite(DIR_B, HIGH); //B前轮
  analogWrite(PWM_A, SPEED);
  analogWrite(PWM_B, SPEED);

  delay(400);
  if (forward_right_count > 0)
  {
    forward_right_count -= 1;
  }
  if (forward_right_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

// function to move backward
void Backward() {
  digitalWrite(DIR_A, LOW);
  digitalWrite(DIR_B, LOW);
  analogWrite(PWM_A, SPEED);
  analogWrite(PWM_B, 0);

  delay(400);
  if (backward_count > 0)
  {
    backward_count -= 1;
  }
  if (backward_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

void BackwardRight() {
  digitalWrite(DIR_A, LOW); //A后轮
  digitalWrite(DIR_B, HIGH); //B前轮
  analogWrite(PWM_A, SPEED);
  analogWrite(PWM_B, SPEED);

  delay(400);
  if (backward_right_count > 0)
  {
    backward_right_count -= 1;
  }
  if (backward_right_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

void BackwardLeft() {
  digitalWrite(DIR_A, LOW); //A后轮
  digitalWrite(DIR_B, LOW); //B前轮
  analogWrite(PWM_A, SPEED);
  analogWrite(PWM_B, SPEED);

  delay(400);
  if (backward_left_count > 0)
  {
    backward_left_count -= 1;
  }
  if (backward_left_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

// function to turn right
void TurnRight() {
  digitalWrite(DIR_A, HIGH);
  digitalWrite(DIR_B, HIGH);
  analogWrite(PWM_A, 0); //后轮停转
  analogWrite(PWM_B, SPEED);
  delay(300);
  if (right_count > 0)
  {
    right_count -= 1;
  }
  if (right_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }



}


// function to turn left
void TurnLeft() {
  digitalWrite(DIR_A, HIGH);
  digitalWrite(DIR_B, LOW);
  analogWrite(PWM_A, 0); //后轮停转
  analogWrite(PWM_B, SPEED);
  delay(300);
  if (left_count > 0)
  {
    left_count -= 1;
  }
  if (left_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
  }
}

void TurnOnLight() {
  digitalWrite(Light_right_pin, LOW);
  digitalWrite(Light_left_pin, LOW);
  delay(300);
}

void TurnOffLight() {
  digitalWrite(Light_right_pin, HIGH);
  digitalWrite(Light_left_pin, HIGH);
  delay(300);
}

void Beep() {
  digitalWrite(Beep_pin, LOW);
  delay(600);
  digitalWrite(Beep_pin, HIGH);
  delay(300);
  digitalWrite(Beep_pin, LOW);
  delay(600);
  if (beep_count > 0)
  {
    beep_count -= 1;
  }
  if (beep_count == 0) {
    analogWrite(PWM_A, 0);
    analogWrite(PWM_B, 0);
    digitalWrite(Beep_pin, HIGH);
  }
}

关于本站

肥龙软件分享的软件是本站作者开发的免费,无广告,安全可靠,绝不附带任何无关软件,绝不困绑任何插件的实用软件。如果您感觉好用,可以捐赠我们,这样我们可以有更积极的动力去改进升级软件,维持服务器运转,感谢您的捐助,谢谢!

致谢 赞赏/捐助名单

2024-8-13 **军 ¥16.8

更新时间:2024.8.31

联系作者(邮箱)
分类