ESP32+L298N+MQTT+4G无线远程监控+四驱动小破车

ESP32+L298N+MQTT+4G无线远程监控+四驱动小破车

小车源代码

注意修改WIFI 信息

#include <analogWrite.h>
#include <WiFi.h>
#include <PubSubClient.h> 

#define led_one 18
// L298N Info GPIO
short m1_ena = 32;
short m1_in1 = 33;
short m1_in2 = 25;

short m2_enb = 26;
short m2_in3 = 27;
short m2_in4 = 14;

short m3_ena = 12;
short m3_in1 = 13;
short m3_in2 = 23;

short m4_enb = 22;
short m4_in3 = 21;
short m4_in4 = 19;

int car_state = 0; // 小车状态
int car_speed = 150; // 小车电机脉冲,
void car_init(); // 小车初始化
void car_stop(); // 小车停
void car_mqtt_control(); // 小车控制函数
void car_m1_go();
void car_m2_go();
void car_m3_go();
void car_m4_go();
void car_m1_back();
void car_m2_back();
void car_m3_back();
void car_m4_back();
void car_m1_stop();
void car_m2_stop();
void car_m3_stop();
void car_m4_stop();

void car_top_go(); // 全速前进 ↑
void car_back_back(); // 全速后退 ↓
void car_left(); // 左←
void car_right(); // 右→
void car_back_left(); // 左斜下 ↙
void car_back_right(); // 右斜下 ↘
void car_top_left(); // 左斜上 ↖
void car_top_right(); // 右斜上 ↗
void car_360();

// WIFI info 这是你家的wifi信息 SSID 网络频带在2.4 GHz 注意!!!
const char *SSID = "4G-UFI-AB87";
const char *PASSWORD = "1234567890";

// MQTT Info
// http://www.taichi-maker.com/public-mqtt-broker/ 免费的MQTT服务器
const char *MQTT_SERVERS = "broker-cn.emqx.io";
int MQTT_PROT =  1883; 

// MQTT 主题
const char *MQTT_TOPIC_LED = "xapi/car/led";
const char *MQTT_TOPIC_ONLINE = "xapi/car/online";
const char *MQTT_TOPIC_CONTROL = "xapi/car/control";
const char *MQTT_TOPIC_SPEED = "xapi/car/speed";
const char *MQTT_TOPIC_HEART = "xapi/car/heart";
const char *CLIENT_ID = "esp8266-457065e5-f063-474e-2saf-cacf5cb52af5";

WiFiClient espClient;
PubSubClient client(espClient);
void init_wifi();                                                        // 初始化wifi
void mqtt_reconnect();                                                   // 重新连接wifi
void mqtt_msg_callback(char *topic, byte *payload, unsigned int length); // mqtt 消息回调
void mqtt_heart(); // 心跳
void led_topic_fn(String data); // led topic 处理函数
void car_control_fn(String data);// 小车 topic 处理函数
void car_speed_fn(String data); // 速度控制

void setup() {
  Serial.begin(115200);
  pinMode(led_one, OUTPUT);
  car_init(); // 小车初始化
  init_wifi(); // wifi 初始化
  client.setServer(MQTT_SERVERS, MQTT_PROT); // 设置mqtt 服务和端口
  client.setCallback(mqtt_msg_callback);    // 设置mqtt 回调函数
}

void loop() {
  if (!client.connected())
  {
    mqtt_reconnect();
  }
  client.loop();
  car_mqtt_control();
  delay(500);
  mqtt_heart();
}
// car -----------------------------------
void car_init(){
  pinMode(m1_ena, OUTPUT);
  pinMode(m1_in1, OUTPUT);
  pinMode(m1_in2, OUTPUT);

  pinMode(m2_enb, OUTPUT);
  pinMode(m2_in3, OUTPUT);
  pinMode(m2_in4, OUTPUT);

  pinMode(m3_ena, OUTPUT);
  pinMode(m3_in1, OUTPUT);
  pinMode(m3_in2, OUTPUT);

  pinMode(m4_enb, OUTPUT);
  pinMode(m4_in3, OUTPUT);
  pinMode(m4_in4, OUTPUT);
}

void car_stop(){
  digitalWrite(m1_in1, LOW);
  digitalWrite(m1_in2, LOW);
  digitalWrite(m2_in3, LOW);
  digitalWrite(m2_in4, LOW);
  digitalWrite(m3_in1, LOW);
  digitalWrite(m3_in2, LOW);
  digitalWrite(m4_in3, LOW);
  digitalWrite(m4_in4, LOW);
}

// ------------------------- M1
void car_m1_go(){
  analogWrite(m1_ena, car_speed);
  digitalWrite(m1_in1, LOW);
  digitalWrite(m1_in2, HIGH);
}

void car_m1_back(){
  analogWrite(m1_ena, car_speed);
  digitalWrite(m1_in1, HIGH);
  digitalWrite(m1_in2, LOW);  
}

// ----------------------M2
void car_m2_go(){
  analogWrite(m2_enb, car_speed);
  digitalWrite(m2_in3, LOW);
  digitalWrite(m2_in4, HIGH);
}

void car_m2_back(){
  analogWrite(m2_enb, car_speed);
  digitalWrite(m2_in3, HIGH);
  digitalWrite(m2_in4, LOW);  
}

// ----------------------M3
void car_m3_go(){
  analogWrite(m3_ena, car_speed);
  digitalWrite(m3_in1, LOW);
  digitalWrite(m3_in2, HIGH);
}

void car_m3_back(){
  analogWrite(m3_ena, car_speed);
  digitalWrite(m3_in1, HIGH);
  digitalWrite(m3_in2, LOW);  
}

// -----------------------M4
void car_m4_go(){
  analogWrite(m4_enb, car_speed);
  digitalWrite(m4_in3, LOW);
  digitalWrite(m4_in4, HIGH);
}
void car_m4_back(){
  analogWrite(m4_enb, car_speed);
  digitalWrite(m4_in3, HIGH);
  digitalWrite(m4_in4, LOW);  
}

void car_m1_stop(){
  digitalWrite(m1_in1, LOW);
  digitalWrite(m1_in2, LOW);
}
void car_m2_stop(){
  digitalWrite(m2_in3, LOW);
  digitalWrite(m2_in4, LOW);
};
void car_m3_stop(){
  digitalWrite(m3_in1, LOW);
  digitalWrite(m3_in2, LOW);
};
void car_m4_stop(){
  digitalWrite(m4_in3, LOW);
  digitalWrite(m4_in4, LOW);  
};


// -----------------------小车组合移动
void car_top_go(){
  car_m1_go();
  car_m2_go();
  car_m3_go();
  car_m4_go();
}

void car_back_back(){
  car_m1_back();
  car_m2_back();
  car_m3_back();
  car_m4_back();
}

void car_top_left(){
  car_m1_stop();
  car_m4_stop();
  
  car_m2_go();
  car_m3_go();
}

void car_top_right(){
  car_m2_stop();
  car_m3_stop();
  
  car_m1_go();
  car_m4_go();
}


void car_back_left(){
  car_m1_stop();
  car_m4_stop();
  
  car_m2_back();
  car_m3_back();
}

void car_back_right(){
  car_m2_stop();
  car_m3_stop();
  
  car_m1_back();
  car_m4_back();
}

void car_left(){
  car_m2_back();
  car_m3_back();

  car_m1_go();
  car_m4_go();
}

void car_right(){
  car_m2_go();
  car_m3_go();

  car_m1_back();
  car_m4_back();
}

void car_360(){
  car_m1_go();
  car_m3_go();
  
  car_m2_back();
  car_m4_back();
}


void car_mqtt_control(){
  switch (car_state)
    {
    case 1:
      car_top_go();
      break;
    case 2:
      car_back_back();
      break;
    case 3:
      car_left();
      break;
    case 4:
      car_right();
      break;
    case 5:
      car_top_left();
      break;
    case 6:
      car_top_right();
      break;
    case 7:
      car_back_left();
      break;
    case 8:
      car_back_right();
      break;
    case 9:
      car_360();
      break;
    case 0:
      car_stop();
      break;
    default:
      car_stop();
      break;
  } 
}

// MQTT --------------------------------------
void led_topic_fn(String data){
    Serial.println("led-s");
    if (data == "1")
    {
      Serial.println("open_led");
      digitalWrite(led_one, HIGH);
    }
    else
    {
      Serial.println("close_led");
      digitalWrite(led_one, LOW);
    }
}

void car_control_fn(String data){
    Serial.println("方向-控制");
    car_speed = 150;
    car_state = data.toInt();
}

void car_speed_fn(String data){
   Serial.println("方向-速度");
   int msgData = data.toInt();
    if(msgData >= 255){
      car_speed = 255;
      return;
    }
    if(msgData <= 0){
      car_speed = 0;
      return;
    }
    car_speed = msgData;
}

void init_wifi(){
  Serial.println("Connecting to");
  Serial.println(SSID);

  WiFi.begin(SSID, PASSWORD);
  while (WiFi.status() != WL_CONNECTED)
  {
    delay(500);
    Serial.print(".");
  }
  Serial.println("");
  Serial.println("WiFi connected");
  Serial.println("IP address: ");
  Serial.println(WiFi.localIP());
}

void mqtt_reconnect()
{
  while (!client.connected())
  {
    Serial.print("Attempting MQTT connection...");

    // 第一步: 创建连接
    if (client.connect(CLIENT_ID))
    {
      Serial.println("connected");
      client.publish(MQTT_TOPIC_ONLINE, "cat_online"); // 发布
      client.subscribe(MQTT_TOPIC_LED);            // 监听 led 主题
      client.subscribe(MQTT_TOPIC_CONTROL); // 监听 小车控制
      client.subscribe(MQTT_TOPIC_SPEED); // 小车 速度
    }
    else
    {
      Serial.print("failed, rc=");
      Serial.print(client.state());
      Serial.println(" try again in 5 seconds");
      delay(5000);
    }
  }
}

void mqtt_msg_callback(char *topic, byte *payload, unsigned int length)
{
  Serial.print("Message arrived [");
  Serial.print(topic); // 打印主题信息
  Serial.print("] ");
  String data = "";
  for (unsigned int i = 0; i < length; i++)
  {
    Serial.print((char)payload[i]); // 打印主题内容
    data += String((char)payload[i]);
  }
  
  String topic_data = String(topic);   // String() 异步
  // led topic
  if (topic_data == MQTT_TOPIC_LED)
  {
      led_topic_fn(data);
  }

  // car topic
  if (topic_data == MQTT_TOPIC_CONTROL)
  {
      car_control_fn(data);
  }

  // car speed 
  if(topic_data == MQTT_TOPIC_SPEED ){
    car_speed_fn(data);
  }
  
  Serial.println();
}

void mqtt_heart(){
  if (client.connected())
  {
    client.publish(MQTT_TOPIC_HEART, "1");
  }
}
posted @ 2022-05-14 20:27  半截肥皂  阅读(1754)  评论(0编辑  收藏  举报