鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    FishBot遥控测试参考代码

    已定时 已固定 已锁定 已移动
    FishBot二驱机器人
    fishbot 遥控测试
    3
    8
    517
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • 小鱼小
      小鱼 技术大佬
      最后由 编辑

      #include <WiFi.h>
      #include <WebServer.h>
      #include <ArduinoJson.h>
      #include "web_control.h"
      #include "PidController.h"
      PidController pid_controller[4]; // PID 控制器数组,用于控制机器人的左右两个电机。
      #include "esp_system.h"
      String password = "88888888";
      
      String board_name()
      {
        char board_name[32];
        uint8_t macAddr[6];
        WiFi.STA.macAddress(macAddr);
        sprintf(board_name, "FISHBOT_%02X%02X", macAddr[4], macAddr[5]);
        static String bn;
        bn = String(board_name);
        return bn;
      }
      
      String board_id()
      {
        char board_id[16];
        uint8_t macAddr[6];
        // WiFi.STA.macAddress(macAddr);
        sprintf(board_id, "%02X%02X%02X%02X%02X%02X", macAddr[0], macAddr[1], macAddr[2], macAddr[3], macAddr[4], macAddr[5]);
        return String(board_id);
      }
      
      #include "Esp32McpwmMotor.h"
      extern Esp32McpwmMotor motor;
      
      #include "oled.h"
      extern Oled oled;
      
      const char *webpage PROGMEM = R"rawliteral(
      <!DOCTYPE html>
      <html lang="en">
      <head>
      <meta charset="UTF-8">
      <meta name="viewport" content="width=device-width, initial-scale=1.0">
      <title>FishBot Remote Controller</title>
      <style>
        body, html {
          height: 100%;
          margin: 0;
          display: flex;
          flex-direction: column;
          justify-content: center;
          align-items: center;
          background-color: #f0f0f5;
          font-family: Arial, sans-serif;
        }
        h1 {
          font-size: 2em;
          color: #333;
          margin: 10px 0 20px 0;
        }
        #control-panel {
          display: flex;
          flex-direction: column;
          align-items: center;
          background-color: #fff;
          padding: 20px;
          border-radius: 10px;
          box-shadow: 0 4px 8px rgba(0, 0, 0, 0.2);
        }
        #horizontal-controls {
          display: flex;
          justify-content: center;
          margin: 20px 0;
        }
        button {
          font-size: 1.5em;
          padding: 15px 30px;
          margin: 10px;
          border: none;
          border-radius: 8px;
          cursor: pointer;
          transition: transform 0.1s ease, opacity 0.2s;
        }
        button:active {
          transform: scale(0.95);
        }
        .blue-button {
          background-color: #4a90e2;
          color: #fff;
        }
        .red-button {
          background-color: #e94e4e;
          color: #fff;
        }
        .blue-button:hover, .red-button:hover {
          opacity: 0.9;
        }
      </style>
      <script>
      function startCommand(action) {
        fetch('/start', {
          method: 'POST',
          body: JSON.stringify({ action: action }),
          headers: { 'Content-Type': 'application/json' }
        });
      }
      
      function stopCommand() {
        fetch('/stop', {
          method: 'POST',
          headers: { 'Content-Type': 'application/json' }
        });
      }
      
      document.addEventListener('DOMContentLoaded', function() {
        const buttons = document.querySelectorAll('button');
        buttons.forEach(button => {
          button.addEventListener('mousedown', () => startCommand(button.dataset.action));
          button.addEventListener('mouseup', stopCommand);
          button.addEventListener('mouseleave', stopCommand);
          button.addEventListener('touchstart', (e) => {
            e.preventDefault();
            startCommand(button.dataset.action);
          });
          button.addEventListener('touchend', stopCommand);
        });
      });
      </script>
      </head>
      <body>
      <h1>FishBot网页遥控器</h1>
      <div id="control-panel">
        <button id="forward" class="blue-button" data-action="3">前</button>
        <div id="horizontal-controls">
          <button id="left" class="blue-button" data-action="1">左</button>
          <button id="right" class="blue-button" data-action="2">右</button>
        </div>
        <button id="backward" class="blue-button" data-action="5">后</button>
      </div>
      </body>
      </html>
      )rawliteral";
      
      WebServer server(80);
      
      // 函数原型声明
      void setMotorState(int action, bool continuous);
      void handleGet();
      void handlePost();
      
      bool stop_motor = false;
      // 停止所有电机
      void stopMotors()
      {
        stop_motor = true;
        motor.updateMotorSpeed(0, 0);
        motor.updateMotorSpeed(1, 0);
        motor.updateMotorSpeed(2, 0);
        motor.updateMotorSpeed(3, 0);
      }
      
      // 处理开始运动的请求
      void handleStart()
      {
        if (server.method() == HTTP_POST)
        {
          StaticJsonDocument<200> doc;
          deserializeJson(doc, server.arg("plain"));
          int action = doc["action"].as<int>();
          setMotorState(action, true); // 开始运动
          server.send(200, "text/plain", "Start action received.");
      
          // 添加调试输出
          Serial.print("Start action received: ");
          Serial.println(action);
        }
      }
      
      // 处理停止运动的请求
      void handleStop()
      {
        if (server.method() == HTTP_POST)
        {
          stopMotors(); // 停止所有电机
          server.send(200, "text/plain", "Stop action received.");
      
          // 添加调试输出
          Serial.println("Stop action received");
        }
      }
      
      #include "Esp32PcntEncoder.h"
      extern Esp32PcntEncoder encoders[4];
      
      // 初始化
      void setup_web_control()
      {
        for (int i = 0; i < 4; i++)
        {
          pid_controller[i].update_target(0.0);
          pid_controller[i].update_pid(0.625, 0.125, 0);
          pid_controller[i].out_limit(-100, 100);
        }
      
        bool ssid_hidden = false; // 设置为true可以隐藏SSID
        int channel = 1;          // 设置WiFi信道
        int max_connection = 5;   // 设置最大连接数
        // 设置ESP32为AP模式,使用上面定义的SSID和密码
        // char board_name[32];
        uint8_t macAddr[6];
        WiFi.AP.macAddress(macAddr);
        // sprintf(board_name, "FISHBOT_%02X%02X", macAddr[4], macAddr[5]);
        // String mboard_name;
        // mboard_name.concat("FISHBOT_");
        // char hexStr[3];
        // sprintf(hexStr, "%02X", macAddr[1]);
        // mboard_name.concat(hexStr);
        // sprintf(hexStr, "%02X", macAddr[2]);
        // mboard_name.concat(hexStr);
      
        oled._display.clearDisplay();
        oled._display.setCursor(0, 0); // 设置开始显示文字的坐标
        oled._display.println("Factory Test Passed");
        oled._display.println("ID:" + board_id());
        oled._display.println("--------------------");
        oled._display.println("--connect  control--");
        oled._display.println("Name:" + board_name());
        oled._display.println("Pswd:88888888");
        oled._display.println("Ip  :192.168.4.1");
        oled._display.display(); // 使更改的显示生效
      
        bool result = WiFi.softAP(board_name(), password, channel, ssid_hidden, max_connection);
        Serial.println("ESP32 is set as a WiFi Access Point with SSID: " + String(board_name()));
      
        if (result)
        {
          Serial.println("Access Point Started");
          IPAddress IP = WiFi.softAPIP();
          Serial.print("AP IP address: ");
          Serial.println(IP);
        }
        else
        {
          Serial.println("Access Point Failed to Start");
        }
      
        // 初始化Web服务器并设置主页响应
        server.on("/", handleGet);
        server.on("/command", handlePost); // 短按命令
        server.on("/start", handleStart);  // 开始运动的请求
        server.on("/stop", handleStop);    // 停止运动的请求
        server.begin();
        Serial.println("Web server started");
      }
      
      void loop_web_control()
      {
        server.handleClient();
      
        static uint32_t last_update_time = 0;
        static int32_t last_motor_ticks[4];
        static int32_t dticks[4];
        static float motor_speed[4];
      
        uint32_t current_time = millis();
        uint32_t dt = current_time - last_update_time;
      
        for (int index = 0; index < 4; index++)
        {
          // ticks数量计算
          dticks[index] = encoders[index].getTicks() - last_motor_ticks[index];
          last_motor_ticks[index] = encoders[index].getTicks();
          motor_speed[index] = (float)(dticks[index]);
          // 更新PID控制器
          if (!stop_motor)
            motor.updateMotorSpeed(index, pid_controller[index].update(motor_speed[index]));
        }
        last_update_time = current_time;
      
        // 打印四个电机的速度
        // Serial.print("Motor speeds: ");
        // for (int i = 0; i < 4; i++)
        // {
        //   // Serial.print(dticks[i]);
        //   Serial.print(motor_speed[i]);
        //   Serial.print(" ");
        // }
        // Serial.println();
      
        delay(10);
      }
      
      // 处理GET请求以返回HTML页面
      void handleGet()
      {
        if (server.method() == HTTP_GET)
        {
          server.send(200, "text/html", webpage);
        }
      }
      
      // 处理POST请求以控制电机
      void handlePost()
      {
        if (server.method() == HTTP_POST)
        {
          StaticJsonDocument<200> doc;
          deserializeJson(doc, server.arg("plain"));
          int action = doc["action"].as<int>();
          bool longPress = doc["longPress"].as<bool>(); // 长按标志
      
          setMotorState(action, longPress);
      
          if (!longPress)
          {
            delay(1000);  // 短按持续1秒
            stopMotors(); // 停止电机
          }
      
          server.send(200, "text/plain", "Action received.");
        }
      }
      
      void setMotorState(int action, bool continuous)
      {
        stop_motor = false;
        // 根据action设置电机状态
        switch (action)
        {
        case 1: // 左转
          pid_controller[0].update_target(-30);
          pid_controller[1].update_target(30);
          pid_controller[2].update_target(-30);
          pid_controller[3].update_target(30);
          break;
        case 2: // 右转
          pid_controller[0].update_target(30);
          pid_controller[1].update_target(-30);
          pid_controller[2].update_target(30);
          pid_controller[3].update_target(-30);
          break;
        case 3: // 前进
          pid_controller[0].update_target(30);
          pid_controller[1].update_target(30);
          pid_controller[2].update_target(30);
          pid_controller[3].update_target(30);
          break;
        case 5: // 后退
          pid_controller[0].update_target(-30);
          pid_controller[1].update_target(-30);
          pid_controller[2].update_target(-30);
          pid_controller[3].update_target(-30);
          break;
        default:
          stop_motor = true;
          stopMotors();
          break;
        }
      
        // 添加调试输出
        Serial.print("Motor action: ");
        Serial.println(action);
      
        // 如果不是长按,不需要在这里停止电机,因为会有单独的停止请求
      }
      

      新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

      1 条回复 最后回复 回复 引用 0
      • 小伊小
        机器人小伊
        最后由 编辑

        此回复已被删除!
        1 条回复 最后回复 回复 引用 0
        • 1
          1371455914x
          最后由 编辑

          源码工程在哪里?

          小鱼小 1 条回复 最后回复 回复 引用 0
          • 小鱼小
            小鱼 技术大佬 @1371455914x
            最后由 编辑

            @1371455914x 不提供源码工程

            新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

            1 1 条回复 最后回复 回复 引用 0
            • 1
              1371455914x @小鱼
              最后由 编辑

              @小鱼 web_control.h 这个类能提供一下不

              小鱼小 1 条回复 最后回复 回复 引用 0
              • 1
                1371455914x
                最后由 编辑

                这个代码是四轮机器人的

                小鱼小 1 条回复 最后回复 回复 引用 0
                • 小鱼小
                  小鱼 技术大佬 @1371455914x
                  最后由 编辑

                  @1371455914x

                  #include <WiFi.h>
                  #include <WebServer.h>
                  #include <ArduinoJson.h>
                  #include "web_control.h"
                  #include "PidController.h"
                  PidController pid_controller[2]; // PID 控制器数组,用于控制机器人的左右两个电机。
                  
                  String password = "88888888";
                  const int Trig = 27; // 设定SR04连接的Arduino引脚
                  const int Echo = 21;
                  extern double distance;
                  extern double mtime;
                  
                  String board_name()
                  {
                    char board_name[16];
                    uint8_t macAddr[6];
                    WiFi.macAddress(macAddr);
                    sprintf(board_name, "FISHBOT_%02X%02X", macAddr[4], macAddr[5]);
                    return String(board_name);
                  }
                  
                  String board_id()
                  {
                    char board_id[16];
                    uint8_t macAddr[6];
                    WiFi.macAddress(macAddr);
                    sprintf(board_id, "%02X%02X%02X%02X%02X%02X", macAddr[0], macAddr[1], macAddr[2], macAddr[3], macAddr[4], macAddr[5]);
                    return String(board_id);
                  }
                  
                  #include "Esp32McpwmMotor.h"
                  extern Esp32McpwmMotor motor;
                  
                  #include "oled.h"
                  extern Oled oled;
                  
                  const char *webpage PROGMEM = R"rawliteral(
                  <!DOCTYPE html>
                  <html lang="en">
                  <head>
                  <meta charset="UTF-8">
                  <meta name="viewport" content="width=device-width, initial-scale=1.0">
                  <title>FishBot Remote Controller</title>
                  <style>
                    body, html {
                      height: 100%;
                      margin: 0;
                      display: flex;
                      flex-direction: column;
                      justify-content: center;
                      align-items: center;
                      background-color: #f0f0f5;
                      font-family: Arial, sans-serif;
                    }
                    h1 {
                      font-size: 2em;
                      color: #333;
                      margin: 10px 0 20px 0;
                    }
                    #control-panel {
                      display: flex;
                      flex-direction: column;
                      align-items: center;
                      background-color: #fff;
                      padding: 20px;
                      border-radius: 10px;
                      box-shadow: 0 4px 8px rgba(0, 0, 0, 0.2);
                    }
                    #horizontal-controls {
                      display: flex;
                      justify-content: center;
                      margin: 20px 0;
                    }
                    button {
                      font-size: 1.5em;
                      padding: 15px 30px;
                      margin: 10px;
                      border: none;
                      border-radius: 8px;
                      cursor: pointer;
                      transition: transform 0.1s ease, opacity 0.2s;
                    }
                    button:active {
                      transform: scale(0.95);
                    }
                    .blue-button {
                      background-color: #4a90e2;
                      color: #fff;
                    }
                    .red-button {
                      background-color: #e94e4e;
                      color: #fff;
                    }
                    .blue-button:hover, .red-button:hover {
                      opacity: 0.9;
                    }
                  </style>
                  <script>
                  function startCommand(action) {
                    fetch('/start', {
                      method: 'POST',
                      body: JSON.stringify({ action: action }),
                      headers: { 'Content-Type': 'application/json' }
                    });
                  }
                  
                  function stopCommand() {
                    fetch('/stop', {
                      method: 'POST',
                      headers: { 'Content-Type': 'application/json' }
                    });
                  }
                  
                  document.addEventListener('DOMContentLoaded', function() {
                    const buttons = document.querySelectorAll('button');
                    buttons.forEach(button => {
                      button.addEventListener('mousedown', () => startCommand(button.dataset.action));
                      button.addEventListener('mouseup', stopCommand);
                      button.addEventListener('mouseleave', stopCommand);
                      button.addEventListener('touchstart', (e) => {
                        e.preventDefault();
                        startCommand(button.dataset.action);
                      });
                      button.addEventListener('touchend', stopCommand);
                    });
                  });
                  </script>
                  </head>
                  <body>
                  <h1>FishBot网页遥控器</h1>
                  <h5>长按遥控|松手停车</h5>
                  <div id="control-panel">
                    <button id="forward" class="blue-button" data-action="3">前</button>
                    <div id="horizontal-controls">
                      <button id="left" class="blue-button" data-action="1">左</button>
                      <button id="right" class="blue-button" data-action="2">右</button>
                    </div>
                    <button id="backward" class="blue-button" data-action="5">后</button>
                  </div>
                  </body>
                  </html>
                  )rawliteral";
                  
                  WebServer server(80);
                  // 函数原型声明
                  void setMotorState(int action, bool continuous);
                  void handleGet();
                  void handlePost();
                  
                  bool stop_motor = false;
                  // 停止所有电机
                  void stopMotors()
                  {
                    stop_motor = true;
                    motor.updateMotorSpeed(0, 0);
                    motor.updateMotorSpeed(1, 0);
                    for (int i = 0; i < 2; i++)
                    {
                      pid_controller[i].reset();
                    }
                  }
                  
                  // 处理开始运动的请求
                  void handleStart()
                  {
                    if (server.method() == HTTP_POST)
                    {
                      StaticJsonDocument<200> doc;
                      deserializeJson(doc, server.arg("plain"));
                      int action = doc["action"].as<int>();
                      setMotorState(action, true); // 开始运动
                      server.send(200, "text/plain", "Start action received.");
                  
                      // 添加调试输出
                      Serial.print("Start action received: ");
                      Serial.println(action);
                    }
                  }
                  
                  // 处理停止运动的请求
                  void handleStop()
                  {
                    if (server.method() == HTTP_POST)
                    {
                      stopMotors(); // 停止所有电机
                      server.send(200, "text/plain", "Stop action received.");
                  
                      // 添加调试输出
                      Serial.println("Stop action received");
                    }
                  }
                  int action;
                  
                  #include "Esp32PcntEncoder.h"
                  extern Esp32PcntEncoder encoders[2];
                  
                  void checkUltrasonicDistance()
                  {
                    digitalWrite(Trig, LOW);
                    delayMicroseconds(2);
                    digitalWrite(Trig, HIGH);
                    delayMicroseconds(10);
                    digitalWrite(Trig, LOW);
                  
                    mtime = pulseIn(Echo, HIGH);
                    distance = mtime * 0.034 / 2;
                  
                    if (distance != 0 && distance < 20)
                    {
                      if (stop_motor == false)
                      {
                        if (pid_controller[0].target_ == 30 && pid_controller[1].target_ == 30)
                        {
                          stopMotors();
                        }
                      }
                    }
                    Serial.print("Distance: ");
                    Serial.print(distance);
                    Serial.print(" Stop Motor: ");
                    Serial.print(stop_motor);
                  }
                  
                  void ultrasonicTask(void *parameter)
                  {
                    while (true)
                    {
                      checkUltrasonicDistance();
                      delay(100); // 每秒检测一次
                    }
                  }
                  
                  // 初始化
                  void setup_web_control()
                  {
                    pinMode(Trig, OUTPUT);
                    pinMode(Echo, INPUT); // 要检测引脚上输入的脉冲宽度,需要先设置为输入状态
                    xTaskCreate(
                        ultrasonicTask,   // 任务函数
                        "UltrasonicTask", // 任务名称
                        10000,            // 堆栈大小
                        NULL,             // 任务参数
                        1,                // 优先级
                        NULL              // 任务句柄
                    );
                  
                    for (int i = 0; i < 2; i++)
                    {
                      pid_controller[i].update_target(0.0);
                      pid_controller[i].update_pid(0.625, 0.125, 0);
                      pid_controller[i].out_limit(-100, 100);
                    }
                  
                    bool ssid_hidden = false; // 设置为true可以隐藏SSID
                    int channel = 1;          // 设置WiFi信道
                    int max_connection = 5;   // 设置最大连接数
                    oled._display.clearDisplay();
                    oled._display.setCursor(0, 0); // 设置开始显示文字的坐标
                    oled._display.println("Factory Test Passed");
                    oled._display.println("ID:" + board_id());
                    oled._display.println("--------------------");
                    oled._display.println("--connect  control--");
                    oled._display.println("Name:" + board_name());
                    oled._display.println("Pswd:88888888");
                    oled._display.println("Ip  :192.168.4.1");
                    oled._display.display(); // 使更改的显示生效
                  
                    bool result = WiFi.softAP(board_name(), password, channel, ssid_hidden, max_connection);
                    Serial.println("ESP32 is set as a WiFi Access Point with SSID: " + String(board_name()));
                  
                    if (result)
                    {
                      Serial.println("Access Point Started");
                      IPAddress IP = WiFi.softAPIP();
                      Serial.print("AP IP address: ");
                      Serial.println(IP);
                    }
                    else
                    {
                      Serial.println("Access Point Failed to Start");
                    }
                  
                    // 初始化Web服务器并设置主页响应
                    server.on("/", handleGet);
                    server.on("/command", handlePost); // 短按命令
                    server.on("/start", handleStart);  // 开始运动的请求
                    server.on("/stop", handleStop);    // 停止运动的请求
                    server.begin();
                    Serial.println("Web server started");
                  }
                  
                  void loop_web_control()
                  {
                    server.handleClient();
                  
                    static uint32_t last_update_time = 0;
                    static int32_t last_motor_ticks[2];
                    static int32_t dticks[2];
                    static float motor_speed[2];
                  
                    uint32_t current_time = millis();
                    uint32_t dt = current_time - last_update_time;
                  
                    for (int index = 0; index < 2; index++)
                    {
                      // ticks数量计算
                      dticks[index] = encoders[index].getTicks() - last_motor_ticks[index];
                      last_motor_ticks[index] = encoders[index].getTicks();
                      motor_speed[index] = (float)(dticks[index]);
                      // 更新PID控制器
                      if (!stop_motor)
                        motor.updateMotorSpeed(index, pid_controller[index].update(motor_speed[index]));
                    }
                    last_update_time = current_time;
                  
                    // 打印四个电机的速度
                    // Serial.print("Motor speeds: ");
                    // for (int i = 0; i < 2; i++)
                    // {
                    //   // Serial.print(dticks[i]);
                    //   Serial.print(motor_speed[i]);
                    //   Serial.print(" ");
                    // }
                    // Serial.println();
                  
                    delay(10);
                  }
                  
                  // 处理GET请求以返回HTML页面
                  void handleGet()
                  {
                    if (server.method() == HTTP_GET)
                    {
                      server.send(200, "text/html", webpage);
                    }
                  }
                  
                  // 处理POST请求以控制电机
                  void handlePost()
                  {
                    if (server.method() == HTTP_POST)
                    {
                      StaticJsonDocument<200> doc;
                      deserializeJson(doc, server.arg("plain"));
                      action = doc["action"].as<int>();
                      bool longPress = doc["longPress"].as<bool>(); // 长按标志
                  
                      setMotorState(action, longPress);
                  
                      if (!longPress)
                      {
                        delay(3500);  // 短按持续1秒
                        stopMotors(); // 停止电机
                      }
                  
                      server.send(200, "text/plain", "Action received.");
                    }
                  }
                  void setMotorState(int action, bool continuous)
                  {
                    stop_motor = false;
                    // 根据action设置电机状态
                    switch (action)
                    {
                    case 1: // 左转
                      pid_controller[0].update_target(-12);
                      pid_controller[1].update_target(12);
                      break;
                    case 2: // 右转
                      pid_controller[0].update_target(12);
                      pid_controller[1].update_target(-12);
                      break;
                    case 3: // 前进
                      pid_controller[0].update_target(30);
                      pid_controller[1].update_target(30);
                      break;
                    case 5: // 后退
                      pid_controller[0].update_target(-30);
                      pid_controller[1].update_target(-30);
                      break;
                    default:
                      stop_motor = true;
                      stopMotors();
                      break;
                    }
                  
                    // 添加调试输出
                    Serial.print("Motor action: ");
                    Serial.println(action);
                  
                    // 如果不是长按,不需要在这里停止电机,因为会有单独的停止请求
                  }
                  

                  二驱的

                  新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                  1 条回复 最后回复 回复 引用 0
                  • 小鱼小
                    小鱼 技术大佬 @1371455914x
                    最后由 编辑

                    @1371455914x 头文件

                    #ifndef __WEB_CONTROL_H__
                    #define __WEB_CONTROL_H__
                    
                    void loop_web_control();
                    void setup_web_control();
                    
                    #endif
                    

                    新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

                    1 条回复 最后回复 回复 引用 0
                    • 第一个帖子
                      最后一个帖子
                    皖ICP备16016415号-7
                    Powered by NodeBB | 鱼香ROS