小猪学arduino—使用esp8266WIFI模块实现双向通信

周末翻抽屉,发现一块n年前买的espduino板子,老实说其实当时是买错了,一直丢在那。今天刚好要在pc/pi上给arduino发指令,手上没有多余的esp8266模块,就拿这个板子来用吧,顺便把esp8266模块的使用方法整理一下。

*注:以下方法适用于任何使用esp8266模块的arduino板子,不论是集成还是外置esp8266的情形(开发版根据实际情况选择即可)。

esp8266模块使用方法如下:

1.安装依赖

brew install gnu-sed --with-default-names
brew install binutils coreutils automake autoconf wget gawk libtool help2man gperf grep

2.找到esp8266在arduino的最新releases(用于IDE识别开发版)

https://github.com/esp8266/Arduino/releases

3.附加开发版设置

*IDE和CH341驱动的安装方法详见:https://blog.yanjingang.com/?p=721

打开Arduino IDE,“Arduino-Preferences-附加开发版管理网址”,填写esp8266开发包配置地址:

http://arduino.esp8266.com/stable/package_esp8266com_index.json

https://github.com/esp8266/Arduino/releases/download/2.5.2/package_esp8266com_index.json

4.安装esp8266开发版插件

打开Arduino IDE,“工具-开发版-开发版管理器”,搜索esp8266,点击安装。安装完毕后重启IDE。

如果因墙的原因总是下载失败,可以配置vpn后重新安装即可

5.测试wifi通信

开发版选择“ESPDuino(ESP-13 Module)”,Reset Medth选“ESPduino V2”,选择端口后测试烧录。

5.1 arduino向外发送http请求:

//http请求示例
#include <Arduino.h>

#include <ESP8266WiFi.h>
#include <ESP8266WiFiMulti.h>

#include <ESP8266HTTPClient.h>

#include <WiFiClient.h>

ESP8266WiFiMulti WiFiMulti;

void setup() {

  Serial.begin(115200);
  // Serial.setDebugOutput(true);

  Serial.println();
  Serial.println();
  Serial.println();

  /*
  for (uint8_t t = 4; t > 0; t--) {
    Serial.printf("[SETUP] WAIT %d...\n", t);
    Serial.flush();
    delay(1000);
  }
  */

  WiFi.mode(WIFI_STA);
  WiFiMulti.addAP("MARS.Y", "lovezhu1314");   //wifi 名称/密码
}

void loop() {
  // wait for WiFi connection
  if ((WiFiMulti.run() == WL_CONNECTED)) {

    WiFiClient client;

    HTTPClient http;

    Serial.print("[HTTP] begin...\n");
    String url = "http://www.yanjingang.com/chengyu/api/s.php?word=qinnengbuzhuo";
    if (http.begin(client, url)) {  // HTTP

      Serial.printf("[HTTP] GET: %s\n", url.c_str());
      // start connection and send HTTP header
      int httpCode = http.GET();

      // httpCode will be negative on error
      if (httpCode > 0) {
        // HTTP header has been send and Server response header has been handled
        Serial.printf("[HTTP] HTTP Status: %d\n", httpCode);

        // file found at server
        if (httpCode == HTTP_CODE_OK || httpCode == HTTP_CODE_MOVED_PERMANENTLY) {
          String payload = http.getString();
          Serial.printf("[HTTP] HTTP Res: %s\n", payload.c_str());
        }
      } else {
        Serial.printf("[HTTP] GET failed, error: %s\n", http.errorToString(httpCode).c_str());
      }

      http.end();
      Serial.print("[HTTP] end...\n");
    } else {
      Serial.printf("[HTTP} Unable to connect\n");
    }
  }

  delay(10000);
}

测试效果:

 

5.2 arduino作为http server接收来自外部的请求:

//arduino作为http server接收外部请求
#include <ESP8266WiFi.h>
#include <WiFiClient.h>
#include <ESP8266WebServer.h>
#include <ESP8266mDNS.h>

#ifndef STASSID
#define STASSID "MARS.Y"
#define STAPSK  "lovezhu1314"
#endif

const char* ssid = STASSID;
const char* password = STAPSK;

ESP8266WebServer server(80);

const int led = 13;

void handleRoot() {
  digitalWrite(led, 1);
  server.send(200, "text/plain", "hello from esp8266!");
  Serial.println("get / root request!");
  digitalWrite(led, 0);
}

void handleNotFound() {
  digitalWrite(led, 1);
  String message = "File Not Found\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(404, "text/plain", message);
  digitalWrite(led, 0);
}

void setup(void) {
  pinMode(led, OUTPUT);
  digitalWrite(led, 0);
  Serial.begin(115200);
  WiFi.mode(WIFI_STA);
  WiFi.begin(ssid, password);
  Serial.println("");

  // 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");
  }

  server.on("/", handleRoot);

  server.on("/test", []() {
    server.send(200, "text/plain", "this works as well");
    Serial.println("get /test request!");
  });

  server.onNotFound(handleNotFound);

  server.begin();
  Serial.println("HTTP server started");
}

void loop(void) {
  server.handleClient();
  MDNS.update();
}

测试效果-server的ip和接收到的请求:(可以根据收到的请求执行相应硬件操作)

局域网向arduino发送请求:

5.3 arduino机器人头部云台接受外部指令控制(头部左转/右转/低头抬头):

vim head_control.ino

/*
 * arduino头部云台控制器(作为http server接收外部请求)
 * 当前云台舵机角度:http://172.20.10.7/head_control/getpos
 * 左转:http://172.20.10.7/head_control/left?degrees=10
 * 右转:http://172.20.10.7/head_control/right?degrees=10
 * 抬头:http://172.20.10.7/head_control/up?degrees=10
 * 低头:http://172.20.10.7/head_control/down?degrees=10
 */

#include <ESP8266WiFi.h>
#include <ESP8266WiFiMulti.h>
#include <ESP8266HTTPClient.h>
#include <WiFiClient.h>
#include <ESP8266WebServer.h>
#include <ESP8266mDNS.h>
#include <Servo.h>
#include <ArduinoUniqueID.h>

//wifi名称/密码配置
#ifndef STASSID
#define STASSID "MARS.Y"
#define STAPSK  "Lovezhu1314"
#endif
const char* ssid = STASSID;
const char* password = STAPSK;

//webserver,监听80端口
ESP8266WebServer server(80);  
//wifi client,负责向外发送http请求
ESP8266WiFiMulti WiFiMulti;
//头部云台舵机控制对象
Servo head_leftright,head_updown;  
//舵机端口
const int pin_lefright = 4;  //左右扭脸舵机引脚
const int pin_updown = 5;   //上下抬头低头舵机引脚
const int pos_init = 90;   //舵机初始角度
//指示灯
const int pin_led = 2;   //指示灯引脚


String getArduinoUniqueId();
//设备唯一ID
const String uniqid = getArduinoUniqueId();


void setup(void) {
  //0.控制台打印初始化
  Serial.begin(115200);
  
  //1.指示灯初始化
  pinMode(pin_led, OUTPUT);
  digitalWrite(pin_led, 0);

  //2.舵机初始化
  Serial.println("init servo...");
  head_leftright.attach(pin_lefright);
  head_updown.attach(pin_updown);  
  //初始左右/上下舵机角度为90度
  initServo();

  //3.wifi客户端初始化
  WiFi.mode(WIFI_STA);
  WiFiMulti.addAP(ssid, password);

  //4.webserver初始化
  WiFi.begin(ssid, password);
  while (WiFi.status() != WL_CONNECTED) { // Wait for connection
    delay(500);
    Serial.print(".");
  }
  String host = WiFi.localIP().toString();
  Serial.println("");
  Serial.print("Connected to ");
  Serial.println(ssid);
  Serial.print("IP address: ");
  Serial.println(host);
  if (MDNS.begin("esp8266")) {
    Serial.println("MDNS responder started");
  }
  //向服务端注册此设备信息 
  registerBoard(uniqid, ssid, host);
  //api init
  server.on("/head_control/getpos", getPos);  //当前舵机角度
  server.on("/head_control/left", headLeft);  //左扭脸api
  server.on("/head_control/right", headRight); //右扭脸api
  server.on("/head_control/up", headUp);  //抬头api
  server.on("/head_control/down", headDown);  //低头api
  server.onNotFound(urlNotFound);  //url错误
  server.on("/", []() {
    server.send(200, "text/plain", "Mars works!");
    Serial.println("get / root request!");
  });
  //start
  server.begin();
  Serial.println("HTTP server started");
}


void loop(void) {
  /*loop*/
  server.handleClient();
  MDNS.update();
}


void registerBoard(String uniqid, String ssid, String host){
  /*向服务端注册此设备信息*/
  if ((WiFiMulti.run() == WL_CONNECTED)) {
    WiFiClient client;
    HTTPClient http;
    
    Serial.print("[HTTP] begin...\n");
    String url = "http://www.yanjingang.com/robot/api/register_board.php?id="+uniqid+"&ssid="+ssid+"&host="+host+"";
    if (http.begin(client, url)) {  // HTTP

      Serial.printf("[HTTP] GET: %s\n", url.c_str());
      // start connection and send HTTP header
      int httpCode = http.GET();

      // httpCode will be negative on error
      if (httpCode > 0) {
        // HTTP header has been send and Server response header has been handled
        Serial.printf("[HTTP] HTTP Status: %d\n", httpCode);

        // file found at server
        if (httpCode == HTTP_CODE_OK || httpCode == HTTP_CODE_MOVED_PERMANENTLY) {
          String payload = http.getString();
          Serial.printf("[HTTP] HTTP Res: %s\n", payload.c_str());
        }
      } else {
        Serial.printf("[HTTP] GET failed, error: %s\n", http.errorToString(httpCode).c_str());
      }

      http.end();
      Serial.print("[HTTP] end...\n");
    } else {
      Serial.printf("[HTTP} Unable to connect\n");
    }
  }
}

void initServo(){
  /*初始左右/上下舵机角度为90度*/
  int pos_leftright = head_leftright.read();
  int pos_updown = head_updown.read();
  //初始左右/上下舵机角度为90度
  if(pos_leftright < pos_init){
    for (int pos = pos_leftright; pos <= pos_init; pos += 1) 
    { // 每次步进一度
      head_leftright.write(pos);        // 指定舵机转向的角度
      delay(10);                 // 等待15ms让舵机到达指定位置
    }
  }else{
    for (int pos = pos_leftright; pos >= pos_init; pos -= 1) 
    {
      head_leftright.write(pos);        // 指定舵机转向的角度
      delay(10);                 // 等待15ms让舵机到达指定位置
    }
  }
  if(pos_updown < pos_init){
    for (int pos = pos_updown; pos <= pos_init; pos += 1) 
    {
      head_updown.write(pos);        // 指定舵机转向的角度
      delay(10);                 // 等待15ms让舵机到达指定位置
    }
  }else{
    for (int pos = pos_updown; pos >= pos_init; pos -= 1) 
    {
      head_updown.write(pos);        // 指定舵机转向的角度
      delay(10);                 // 等待15ms让舵机到达指定位置
    }
  }
}



String getArduinoUniqueId(){
  /*获得arduino板子硬件唯一ID*/  
  String uniqid = "";
  for (size_t i = 0; i < UniqueIDsize; i++)
  {
    if( i > 0 and i < UniqueIDsize){
      uniqid = uniqid + "-";
    }
    if (UniqueID[i] < 0x10){
      uniqid = uniqid + "0";
    }
    uniqid = uniqid + String(UniqueID[i], HEX);
  }
  return uniqid;
}

String getArg(String arg){
  /*获取url中的指定参数值*/
  for (uint8_t i = 0; i < server.args(); i++) {
    if(server.argName(i) == arg){
      return server.arg(i);
    }
  }
  return "";
}

int getIntArg(String arg){
  /*获取url中的参数值(数值)*/
  for (uint8_t i = 0; i < server.args(); i++) {
    if(server.argName(i) == arg){
      return server.arg(i).toInt();
    }
  }
  return 0;
}




void getPos() {
  /*获得头部两个舵机当前的角度*/
  //舵机当前角度
  int pos_leftright = int(head_leftright.read());
  int pos_updown = int(head_updown.read());
  server.send(200, "text/plain", "{\"id\":\"" + uniqid + "\",\"pos_leftright\":" + String(pos_leftright) + ",\"pos_updown\":" + String(pos_updown) + "}");
}

void headLeft() {
  /*往左扭脸*/
  digitalWrite(pin_led, 1);
  //舵机当前角度
  int pos_leftright = int(head_leftright.read());
  server.send(200, "text/plain", "{\"id\":\"" + uniqid + "\",\"pos\":" + String(pos_leftright) + "}");
  //参数中的度数
  int degrees = getIntArg("degrees");
  Serial.printf("turn left %d\n", degrees);
  for (int pos = pos_leftright; pos <= pos_leftright+degrees; pos += 1) { // 每次步进一度
    head_leftright.write(pos);        // 指定舵机转向的角度
    delay(10);                       // 等待15ms让舵机到达指定位置
  }
  digitalWrite(pin_led, 0);
}

void headRight() {
  /*往右扭脸*/
  digitalWrite(pin_led, 1);
  //舵机当前角度
  int pos_leftright = int(head_leftright.read());
  server.send(200, "text/plain", "{\"id\":\"" + uniqid + "\",\"pos\":" + String(pos_leftright) + "}");
  //参数中的度数
  int degrees = getIntArg("degrees");
  Serial.printf("turn right %d\n", degrees);
  for (int pos = pos_leftright; pos >= pos_leftright-degrees; pos -= 1) { // 每次步进一度
    head_leftright.write(pos);        // 指定舵机转向的角度
    delay(10);                       // 等待15ms让舵机到达指定位置
  }
  digitalWrite(pin_led, 0);
}


void headUp() {
  /*抬头*/
  digitalWrite(pin_led, 1);
  //舵机当前角度
  int pos_updown = int(head_updown.read());
  server.send(200, "text/plain", "{\"id\":\"" + uniqid + "\",\"pos\":" + String(pos_updown) + "}");
  //参数中的度数
  int degrees = getIntArg("degrees");
  Serial.printf("turn left %d\n", degrees);
  for (int pos = pos_updown; pos <= pos_updown+degrees; pos += 1) { // 每次步进一度
    head_updown.write(pos);        // 指定舵机转向的角度
    delay(10);                       // 等待15ms让舵机到达指定位置
  }
  digitalWrite(pin_led, 0);
}

void headDown() {
  /*低头*/
  digitalWrite(pin_led, 1);
  //舵机当前角度
  int pos_updown = int(head_updown.read());
  server.send(200, "text/plain", "{\"id\":\"" + uniqid + "\",\"pos\":" + String(pos_updown) + "}");
  //参数中的度数
  int degrees = getIntArg("degrees");
  Serial.printf("turn right %d\n", degrees);
  for (int pos = pos_updown; pos >= pos_updown-degrees; pos -= 1) { // 每次步进一度
    head_updown.write(pos);        // 指定舵机转向的角度
    delay(10);                       // 等待15ms让舵机到达指定位置
  }
  digitalWrite(pin_led, 0);
}


void urlNotFound() {
  /*访问的url不存在*/
  digitalWrite(pin_led, 1);
  String message = "File Not Found\n\n";
  message += "BOARD_ID: ";
  message += uniqid;
  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(404, "text/plain", message);
  digitalWrite(pin_led, 0);
}

 

访问api即可控制机器人头部:(degrees:转动度数)

* 左转:http://172.20.10.7/head_control/left?degrees=10
* 右转:http://172.20.10.7/head_control/right?degrees=10
* 抬头:http://172.20.10.7/head_control/up?degrees=10
* 低头:http://172.20.10.7/head_control/down?degrees=10

由于模块可能每次连接的wifi网段可能不同,一个最简单的方法就是当server启动时,把自己的设备id和ip发给一个固定的api,需要访问server的程序从这个api处获取指定设备id最新的ip地址即可。

 

5.4 摄像头追踪人脸效果:

 

另外生产环境中请求最好使用https以避免被轻易的嗅探。

yan 19.7.14 23:45

 

参考:

Esp8266-Arduino 环境安装

Mac 下搭建esp8266交叉编译环境

ESPduino基本使用手册.pdf

POST Nest API用于获取ESP8266或Arduino的访问令牌

ESP8266官方HTTPClient examples

ESP8266官方WebServer examples

欢迎关注下方“非著名资深码农“公众号进行交流~

发表评论

邮箱地址不会被公开。