42210浏览
查看: 42210|回复: 3

[项目] ESP32 麦克纳姆轮 视频车

[复制链接]
本帖最后由 云天 于 2023-9-17 21:28 编辑

ESP32 麦克纳姆轮 视频车图2
【项目背景】
想做一个组装简易的麦克纳姆轮视频车,之前制作的小车,电机需要驱动模块,也需要单独的电源,主控也需要电源。所以硬件设备较多,不好布局,很多时候显得很凌乱。在DF商城上看到了“Romeo ESP32-S3 开发板” Romeo ESP32-S3是为机器人项目设计的一款开发板,可驱动4路电机、图像传输、远程控制。
【项目设计】
ESP32 麦克纳姆轮 视频车图3
使用“便携式多路可调电源”的USB-A电源口为主控电源供电,9V端口为电机驱动供电。使用“ESPAsyncWebServer库”及“AsyncTCP库”,利用“App Inventor2”的浏览器模块访问192.168.4.1,即可实现手机App驱动小车和查看摄像头数据。

【硬件组装】

1.所用到硬件
ESP32 麦克纳姆轮 视频车图4
2.安装电机
ESP32 麦克纳姆轮 视频车图93.安装挡板
ESP32 麦克纳姆轮 视频车图10
4.安装麦克纳姆轮
ESP32 麦克纳姆轮 视频车图8
5.安装主控,接电机线
ESP32 麦克纳姆轮 视频车图6
6.安装电源
ESP32 麦克纳姆轮 视频车图7
7.接电源线
ESP32 麦克纳姆轮 视频车图5
8.固定摄像头
ESP32 麦克纳姆轮 视频车图1
【制作APP】
1.界面设计
一个网页浏览框和一个按钮
ESP32 麦克纳姆轮 视频车图11
2.程序设计
手机连接“Romeo ESP32-S3 开发板”的WIFI热点,网页浏览框加载“192.168.4.1”。按钮用于当连接中断时,重新连接。
ESP32 麦克纳姆轮 视频车图12
【修改ESP32示例代码】
ESP32 麦克纳姆轮 视频车图13
控制页面增加四个方向按钮
  1.     <table id="mainTable" style="width:355px;margin:auto;table-layout:fixed" CELLSPACING=10>
  2.       <tr>
  3.         <img id="cameraImage" src="" style="width:355px;height:222px"></td>
  4.       </tr>
  5.       <tr>
  6.         <td class="button" ontouchstart='sendButtonInput("MoveCar","5")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↖</span></td>
  7.         <td class="button" ontouchstart='sendButtonInput("MoveCar","1")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇧</span></td>
  8.         <td class="button" ontouchstart='sendButtonInput("MoveCar","6")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↗</span></td>
  9.       </tr>
  10.       <tr>
  11.         <td class="button" ontouchstart='sendButtonInput("MoveCar","3")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇦</span></td>
  12.         <td class="button"></td>   
  13.         <td class="button" ontouchstart='sendButtonInput("MoveCar","4")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇨</span></td>
  14.       </tr>
  15.       <tr>
  16.         <td class="button" ontouchstart='sendButtonInput("MoveCar","7")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↙</span></td>
  17.         <td class="button" ontouchstart='sendButtonInput("MoveCar","2")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇩</span></td>
  18.         <td class="button" ontouchstart='sendButtonInput("MoveCar","8")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↘</span></td>
  19.       </tr>
  20.       <tr/><tr/>
  21.       <tr>
  22.         <td style="text-align:left"><b>Speed:</b></td>
  23.         <td colspan=2>
  24.          <div class="slidecontainer">
  25.             <input type="range" min="0" max="100" value="50" class="slider" id="Speed" oninput='sendButtonInput("Speed",value)'>
  26.           </div>
  27.         </td>
  28.       </tr>        
  29.     </table>
复制代码


根据麦克纳姆运动特点修改代码。轮麦克纳姆轮与普通轮子的区别在于麦克纳姆轮旋转时,由于存在斜向的从动轮,会同时产生一个斜向的力,当我们控制轮子旋转的速度与方向时,将斜向的力增强或抵消,从而实现小车的全向移动。可以完成横移、斜方向移动等普通小车无法完成的高难度动作,轮子的转动方向与小车的运动方向关系如下图:

  1. void moveCar(uint8_t inputValue,uint8_t speed)
  2. {
  3.   switch(inputValue)
  4.   {
  5.     case UP:
  6.       retreat(1,speed);
  7.       retreat(2,speed);
  8.       advance(3,speed);
  9.       advance(4,speed);
  10.       break;
  11.     case DOWN:
  12.       advance(1,speed);
  13.       advance(2,speed);
  14.       retreat(3,speed);
  15.       retreat(4,speed);
  16.       break;
  17.     case LEFT:
  18.       retreat(2,speed);
  19.       retreat(4,speed);
  20.       advance(1,speed);
  21.       advance(3,speed);
  22.       break;
  23.     case RIGHT:
  24.       retreat(1,speed);
  25.       retreat(3,speed);
  26.       advance(2,speed);
  27.       advance(4,speed);
  28.       break;
  29.     case Upper_Left:
  30.       breake(1);
  31.       retreat(2,speed);
  32.       advance(3,speed);
  33.       breake(4);
  34.       break;
  35.     case Upper_Right:
  36.       retreat(1,speed);
  37.       breake(2);
  38.       breake(3);
  39.       advance(4,speed);
  40.       break;
  41.     case Bottom_Left:
  42.       advance(1,speed);
  43.       breake(2);
  44.       breake(3);
  45.       retreat(4,speed);
  46.       break;
  47.     case Bottom_Right:
  48.       breake(1);
  49.       advance(2,speed);
  50.       retreat(3,speed);
  51.       breake(4);
  52.       break;
  53.     case STOP:
  54.       breake(1);
  55.       breake(2);
  56.       breake(3);
  57.       breake(4);
  58.       break;
  59.   }
  60. }
复制代码

【ESP32 完整代码】
  1. #include "esp_camera.h"
  2. #include <Arduino.h>
  3. #include <WiFi.h>
  4. #include <AsyncTCP.h>
  5. #include <ESPAsyncWebServer.h>
  6. #include <iostream>
  7. #include <sstream>
  8. #include "DFRobot_AXP313A.h"
  9. #include "driver/mcpwm.h"
  10. #include "soc/mcpwm_struct.h"
  11. #include "soc/mcpwm_reg.h"
  12. DFRobot_AXP313A axp;
  13. #define M1_EN 12
  14. #define M1_PN 13
  15. #define M2_EN 14
  16. #define M2_PN 21
  17. #define M3_EN 9
  18. #define M3_PN 10
  19. #define M4_EN 47
  20. #define M4_PN 11
  21. #define UP 1
  22. #define DOWN 2
  23. #define LEFT 3
  24. #define RIGHT 4
  25. #define Upper_Left 5
  26. #define Upper_Right 6
  27. #define Bottom_Left 7
  28. #define Bottom_Right 8
  29. #define STOP 0
  30. #define FORWARD 1
  31. #define BACKWARD -1
  32. //Camera related constants
  33. #define PWDN_GPIO_NUM     -1
  34. #define RESET_GPIO_NUM    -1
  35. #define XCLK_GPIO_NUM     45
  36. #define SIOD_GPIO_NUM     1
  37. #define SIOC_GPIO_NUM     2
  38. #define Y9_GPIO_NUM       48
  39. #define Y8_GPIO_NUM       46
  40. #define Y7_GPIO_NUM       8
  41. #define Y6_GPIO_NUM       7
  42. #define Y5_GPIO_NUM       4
  43. #define Y4_GPIO_NUM       41
  44. #define Y3_GPIO_NUM       40
  45. #define Y2_GPIO_NUM       39
  46. #define VSYNC_GPIO_NUM    6
  47. #define HREF_GPIO_NUM     42
  48. #define PCLK_GPIO_NUM     5
  49. const char* ssid     = "******";
  50. const char* password = "*******";
  51. AsyncWebServer server(80);
  52. AsyncWebSocket wsCamera("/Camera");
  53. AsyncWebSocket wsCarInput("/CarInput");
  54. uint32_t cameraClientId = 0;
  55. uint8_t Speed = 50;
  56. const char* htmlHomePage PROGMEM = R"HTMLHOMEPAGE(
  57. <!DOCTYPE html>
  58. <html>
  59.   <head>
  60.   <meta name="viewport" content="width=device-width, initial-scale=1, maximum-scale=1, user-scalable=no">
  61.     <style>
  62.     .arrows {
  63.       font-size:30px;
  64.       color:red;
  65.     }
  66.     td.button {
  67.       background-color:black;
  68.       border-radius:25%;
  69.       box-shadow: 5px 5px #888888;
  70.     }
  71.     td.button:active {
  72.       transform: translate(5px,5px);
  73.       box-shadow: none;
  74.     }
  75.     .noselect {
  76.       -webkit-touch-callout: none; /* iOS Safari */
  77.         -webkit-user-select: none; /* Safari */
  78.          -khtml-user-select: none; /* Konqueror HTML */
  79.            -moz-user-select: none; /* Firefox */
  80.             -ms-user-select: none; /* Internet Explorer/Edge */
  81.                 user-select: none; /* Non-prefixed version, currently
  82.                                       supported by Chrome and Opera */
  83.     }
  84.     .slidecontainer {
  85.       width: 100%;
  86.     }
  87.     .slider {
  88.       -webkit-appearance: none;
  89.       width: 100%;
  90.       height: 15px;
  91.       border-radius: 5px;
  92.       background: #d3d3d3;
  93.       outline: none;
  94.       opacity: 0.7;
  95.       -webkit-transition: .2s;
  96.       transition: opacity .2s;
  97.     }
  98.     .slider:hover {
  99.       opacity: 1;
  100.     }
  101.     .slider::-webkit-slider-thumb {
  102.       -webkit-appearance: none;
  103.       appearance: none;
  104.       width: 25px;
  105.       height: 25px;
  106.       border-radius: 50%;
  107.       background: red;
  108.       cursor: pointer;
  109.     }
  110.     .slider::-moz-range-thumb {
  111.       width: 25px;
  112.       height: 25px;
  113.       border-radius: 50%;
  114.       background: red;
  115.       cursor: pointer;
  116.     }
  117.     </style>
  118.   </head>
  119.   <body class="noselect" align="center" style="background-color:white">
  120.     <table id="mainTable" style="width:355px;margin:auto;table-layout:fixed" CELLSPACING=10>
  121.       <tr>
  122.         <img id="cameraImage" src="" style="width:355px;height:222px"></td>
  123.       </tr>
  124.       <tr>
  125.         <td class="button" ontouchstart='sendButtonInput("MoveCar","5")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↖</span></td>
  126.         <td class="button" ontouchstart='sendButtonInput("MoveCar","1")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇧</span></td>
  127.         <td class="button" ontouchstart='sendButtonInput("MoveCar","6")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↗</span></td>
  128.       </tr>
  129.       <tr>
  130.         <td class="button" ontouchstart='sendButtonInput("MoveCar","3")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇦</span></td>
  131.         <td class="button"></td>   
  132.         <td class="button" ontouchstart='sendButtonInput("MoveCar","4")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇨</span></td>
  133.       </tr>
  134.       <tr>
  135.         <td class="button" ontouchstart='sendButtonInput("MoveCar","7")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↙</span></td>
  136.         <td class="button" ontouchstart='sendButtonInput("MoveCar","2")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >⇩</span></td>
  137.         <td class="button" ontouchstart='sendButtonInput("MoveCar","8")' ontouchend='sendButtonInput("MoveCar","0")'><span class="arrows" >↘</span></td>
  138.       </tr>
  139.       <tr/><tr/>
  140.       <tr>
  141.         <td style="text-align:left"><b>Speed:</b></td>
  142.         <td colspan=2>
  143.          <div class="slidecontainer">
  144.             <input type="range" min="0" max="100" value="50" class="slider" id="Speed" oninput='sendButtonInput("Speed",value)'>
  145.           </div>
  146.         </td>
  147.       </tr>        
  148.     </table>
  149.     <script>
  150.       var webSocketCameraUrl = "ws:\/\/" + window.location.hostname + "/Camera";
  151.       var webSocketCarInputUrl = "ws:\/\/" + window.location.hostname + "/CarInput";      
  152.       var websocketCamera;
  153.       var websocketCarInput;
  154.       function initCameraWebSocket()
  155.       {
  156.         websocketCamera = new WebSocket(webSocketCameraUrl);
  157.         websocketCamera.binaryType = 'blob';
  158.         websocketCamera.onopen    = function(event){};
  159.         websocketCamera.onclose   = function(event){setTimeout(initCameraWebSocket, 2000);};
  160.         websocketCamera.onmessage = function(event)
  161.         {
  162.           var imageId = document.getElementById("cameraImage");
  163.           imageId.src = URL.createObjectURL(event.data);
  164.         };
  165.       }
  166.       function initCarInputWebSocket()
  167.       {
  168.         websocketCarInput = new WebSocket(webSocketCarInputUrl);
  169.         websocketCarInput.onopen    = function(event)
  170.         {
  171.           sendButtonInput("Speed", document.getElementById("Speed").value);
  172.         };
  173.         websocketCarInput.onclose   = function(event){setTimeout(initCarInputWebSocket, 2000);};
  174.         websocketCarInput.onmessage = function(event){};        
  175.       }
  176.       function initWebSocket()
  177.       {
  178.         initCameraWebSocket ();
  179.         initCarInputWebSocket();
  180.       }
  181.       function sendButtonInput(key, value)
  182.       {
  183.         var data = key + "," + value;
  184.         websocketCarInput.send(data);
  185.       }
  186.       window.onload = initWebSocket;
  187.       document.getElementById("mainTable").addEventListener("touchend", function(event){
  188.         event.preventDefault()
  189.       });      
  190.     </script>
  191.   </body>   
  192. </html>
  193. )HTMLHOMEPAGE";
  194. void advance(uint8_t motorNumber,uint8_t speed)
  195. {
  196.   switch(motorNumber)
  197.   {
  198.     case 1:
  199.       mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);//给PH一个持续的高电平
  200.       mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  201.       mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  202.       break;
  203.     case 2:
  204.       mcpwm_set_signal_high(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的高电平
  205.       mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  206.       mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  207.       break;
  208.     case 3:
  209.       mcpwm_set_signal_high(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_B);//给PH一个持续的高电平
  210.       mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  211.       mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  212.       break;
  213.     case 4:
  214.       mcpwm_set_signal_high(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的高电平
  215.       mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  216.       mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  217.       break;
  218.   }
  219. }
  220. void retreat(uint8_t motorNumber,uint8_t speed)
  221. {
  222.   switch(motorNumber)
  223.   {
  224.     case 1:
  225.       mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_B);//给PH一个持续的低电平
  226.       mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  227.       mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  228.       break;
  229.     case 2:
  230.       mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的低电平
  231.       mcpwm_set_duty_type(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  232.       mcpwm_set_duty(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  233.       break;
  234.     case 3:
  235.       mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_B);//给PH一个持续的低电平
  236.       mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  237.       mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  238.       break;
  239.     case 4:
  240.       mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_B);//给PH一个持续的低电平
  241.       mcpwm_set_duty_type(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,MCPWM_DUTY_MODE_0);
  242.       mcpwm_set_duty(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A,speed);//EN引脚输出占空比为“speed”的PWM波
  243.       break;
  244.   }
  245. }
  246. void breake(uint8_t motorNumber)
  247. {
  248.   switch(motorNumber)
  249.   {
  250.     case 1:
  251.       mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_0,MCPWM_GEN_A);
  252.       break;
  253.     case 2:
  254.       mcpwm_set_signal_low(MCPWM_UNIT_0,MCPWM_TIMER_1,MCPWM_GEN_A);
  255.       break;
  256.     case 3:
  257.       mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_0,MCPWM_GEN_A);
  258.       break;
  259.     case 4:
  260.       mcpwm_set_signal_low(MCPWM_UNIT_1,MCPWM_TIMER_1,MCPWM_GEN_A);
  261.       break;
  262.   }
  263. }
  264. void moveCar(uint8_t inputValue,uint8_t speed)
  265. {
  266.   switch(inputValue)
  267.   {
  268.     case UP:
  269.       retreat(1,speed);
  270.       retreat(2,speed);
  271.       advance(3,speed);
  272.       advance(4,speed);
  273.       break;
  274.     case DOWN:
  275.       advance(1,speed);
  276.       advance(2,speed);
  277.       retreat(3,speed);
  278.       retreat(4,speed);
  279.       break;
  280.     case LEFT:
  281.       retreat(2,speed);
  282.       retreat(4,speed);
  283.       advance(1,speed);
  284.       advance(3,speed);
  285.       break;
  286.     case RIGHT:
  287.       retreat(1,speed);
  288.       retreat(3,speed);
  289.       advance(2,speed);
  290.       advance(4,speed);
  291.       break;
  292.     case Upper_Left:
  293.       breake(1);
  294.       retreat(2,speed);
  295.       advance(3,speed);
  296.       breake(4);
  297.       break;
  298.     case Upper_Right:
  299.       retreat(1,speed);
  300.       breake(2);
  301.       breake(3);
  302.       advance(4,speed);
  303.       break;
  304.     case Bottom_Left:
  305.       advance(1,speed);
  306.       breake(2);
  307.       breake(3);
  308.       retreat(4,speed);
  309.       break;
  310.     case Bottom_Right:
  311.       breake(1);
  312.       advance(2,speed);
  313.       retreat(3,speed);
  314.       breake(4);
  315.       break;
  316.     case STOP:
  317.       breake(1);
  318.       breake(2);
  319.       breake(3);
  320.       breake(4);
  321.       break;
  322.   }
  323. }
  324. void handleRoot(AsyncWebServerRequest *request)
  325. {
  326.   request->send_P(200, "text/html", htmlHomePage);
  327. }
  328. void handleNotFound(AsyncWebServerRequest *request)
  329. {
  330.     request->send(404, "text/plain", "File Not Found");
  331. }
  332. void onCarInputWebSocketEvent(AsyncWebSocket *server,
  333.                       AsyncWebSocketClient *client,
  334.                       AwsEventType type,
  335.                       void *arg,
  336.                       uint8_t *data,
  337.                       size_t len)
  338. {                     
  339.   switch (type)
  340.   {
  341.     case WS_EVT_CONNECT:
  342.       Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str());
  343.       break;
  344.     case WS_EVT_DISCONNECT:
  345.       Serial.printf("WebSocket client #%u disconnected\n", client->id());
  346.       moveCar(STOP,0);
  347.       //ledcWrite(PWMLightChannel, 0);
  348.       //panServo.write(90);
  349.       //tiltServo.write(90);      
  350.       break;
  351.     case WS_EVT_DATA:
  352.       AwsFrameInfo *info;
  353.       info = (AwsFrameInfo*)arg;
  354.       if (info->final && info->index == 0 && info->len == len && info->opcode == WS_TEXT)
  355.       {
  356.         std::string myData = "";
  357.         myData.assign((char *)data, len);
  358.         std::istringstream ss(myData);
  359.         std::string key, value;
  360.         std::getline(ss, key, ',');
  361.         std::getline(ss, value, ',');
  362.         Serial.printf("Key [%s] Value[%s]\n", key.c_str(), value.c_str());
  363.         int valueInt = atoi(value.c_str());     
  364.         if (key == "MoveCar")
  365.         {
  366.           moveCar(valueInt,Speed);        
  367.         }
  368.         else if (key == "Speed")
  369.         {
  370.           Speed = valueInt;
  371.         }
  372.         /*else if (key == "Light")
  373.         {
  374.           //ledcWrite(PWMLightChannel, valueInt);         
  375.         }
  376.         else if (key == "Pan")
  377.         {
  378.           //panServo.write(valueInt);
  379.         }
  380.         else if (key == "Tilt")
  381.         {
  382.           //tiltServo.write(valueInt);   
  383.         }  */           
  384.       }
  385.       break;
  386.     case WS_EVT_PONG:
  387.     case WS_EVT_ERROR:
  388.       break;
  389.     default:
  390.       break;  
  391.   }
  392. }
  393. void onCameraWebSocketEvent(AsyncWebSocket *server,
  394.                       AsyncWebSocketClient *client,
  395.                       AwsEventType type,
  396.                       void *arg,
  397.                       uint8_t *data,
  398.                       size_t len)
  399. {                     
  400.   switch (type)
  401.   {
  402.     case WS_EVT_CONNECT:
  403.       Serial.printf("WebSocket client #%u connected from %s\n", client->id(), client->remoteIP().toString().c_str());
  404.       cameraClientId = client->id();
  405.       break;
  406.     case WS_EVT_DISCONNECT:
  407.       Serial.printf("WebSocket client #%u disconnected\n", client->id());
  408.       cameraClientId = 0;
  409.       break;
  410.     case WS_EVT_DATA:
  411.       break;
  412.     case WS_EVT_PONG:
  413.     case WS_EVT_ERROR:
  414.       break;
  415.     default:
  416.       break;  
  417.   }
  418. }
  419. void setupCamera()
  420. {
  421.   camera_config_t config;
  422.   config.ledc_channel = LEDC_CHANNEL_0;
  423.   config.ledc_timer = LEDC_TIMER_0;
  424.   config.pin_d0 = Y2_GPIO_NUM;
  425.   config.pin_d1 = Y3_GPIO_NUM;
  426.   config.pin_d2 = Y4_GPIO_NUM;
  427.   config.pin_d3 = Y5_GPIO_NUM;
  428.   config.pin_d4 = Y6_GPIO_NUM;
  429.   config.pin_d5 = Y7_GPIO_NUM;
  430.   config.pin_d6 = Y8_GPIO_NUM;
  431.   config.pin_d7 = Y9_GPIO_NUM;
  432.   config.pin_xclk = XCLK_GPIO_NUM;
  433.   config.pin_pclk = PCLK_GPIO_NUM;
  434.   config.pin_vsync = VSYNC_GPIO_NUM;
  435.   config.pin_href = HREF_GPIO_NUM;
  436.   config.pin_sscb_sda = SIOD_GPIO_NUM;
  437.   config.pin_sscb_scl = SIOC_GPIO_NUM;
  438.   config.pin_pwdn = PWDN_GPIO_NUM;
  439.   config.pin_reset = RESET_GPIO_NUM;
  440.   config.xclk_freq_hz = 20000000;
  441.   config.frame_size = FRAMESIZE_UXGA;
  442.   config.pixel_format = PIXFORMAT_JPEG; // for streaming
  443.   //config.pixel_format = PIXFORMAT_RGB565; // for face detection/recognition
  444.   config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
  445.   config.fb_location = CAMERA_FB_IN_PSRAM;
  446.   config.jpeg_quality = 12;
  447.   config.fb_count = 1;
  448.     // if PSRAM IC present, init with UXGA resolution and higher JPEG quality
  449.   //                      for larger pre-allocated frame buffer.
  450.   if(config.pixel_format == PIXFORMAT_JPEG){
  451.     if(psramFound()){
  452.       config.jpeg_quality = 10;
  453.       config.fb_count = 2;
  454.       config.grab_mode = CAMERA_GRAB_LATEST;
  455.     } else {
  456.       // Limit the frame size when PSRAM is not available
  457.       config.frame_size = FRAMESIZE_SVGA;
  458.       config.fb_location = CAMERA_FB_IN_DRAM;
  459.     }
  460.   } else {
  461.     // Best option for face detection/recognition
  462.     config.frame_size = FRAMESIZE_240X240;
  463. #if CONFIG_IDF_TARGET_ESP32S3
  464.     config.fb_count = 2;
  465. #endif
  466.   }
  467.   // camera init
  468.   esp_err_t err = esp_camera_init(&config);
  469.   if (err != ESP_OK)
  470.   {
  471.     Serial.printf("Camera init failed with error 0x%x", err);
  472.     return;
  473.   }  
  474.   if (psramFound())
  475.   {
  476.     heap_caps_malloc_extmem_enable(20000);  
  477.     Serial.printf("PSRAM initialized. malloc to take memory from psram above this size");   
  478.   }  
  479. }
  480. void sendCameraPicture()
  481. {
  482.   if (cameraClientId == 0)
  483.   {
  484.     return;
  485.   }
  486.   unsigned long  startTime1 = millis();
  487.   //capture a frame
  488.   camera_fb_t * fb = esp_camera_fb_get();
  489.   if (!fb)
  490.   {
  491.       Serial.println("Frame buffer could not be acquired");
  492.       return;
  493.   }
  494.   unsigned long  startTime2 = millis();
  495.   wsCamera.binary(cameraClientId, fb->buf, fb->len);
  496.   esp_camera_fb_return(fb);
  497.   //Wait for message to be delivered
  498.   while (true)
  499.   {
  500.     AsyncWebSocketClient * clientPointer = wsCamera.client(cameraClientId);
  501.     if (!clientPointer || !(clientPointer->queueIsFull()))
  502.     {
  503.       break;
  504.     }
  505.     delay(1);
  506.   }
  507.   unsigned long  startTime3 = millis();  
  508.   Serial.printf("Time taken Total: %d|%d|%d\n",startTime3 - startTime1, startTime2 - startTime1, startTime3-startTime2 );
  509. }
  510. //初始化需要产生PWM信号的引脚
  511. void mcpwm_init(void)
  512. {
  513.   //配置mcpwm信息
  514.   mcpwm_config_t pwm_config;
  515.   pwm_config.frequency = 1000;
  516.   pwm_config.cmpr_a = 0;
  517.   pwm_config.cmpr_b = 0;
  518.   pwm_config.counter_mode = MCPWM_UP_COUNTER;
  519.   pwm_config.duty_mode = MCPWM_DUTY_MODE_0;
  520.   //A速度  B方向
  521.   mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0A,M1_EN);//电机1 GPIO
  522.   mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM0B,M1_PN);
  523.   mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_0,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  524.   mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM1A,M2_EN);//电机2 GPIO
  525.   mcpwm_gpio_init(MCPWM_UNIT_0,MCPWM1B,M2_PN);
  526.   mcpwm_init(MCPWM_UNIT_0,MCPWM_TIMER_1,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  527.   mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM0A,M3_EN);//电机3 GPIO
  528.   mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM0B,M3_PN);
  529.   mcpwm_init(MCPWM_UNIT_1,MCPWM_TIMER_0,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  530.   mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM1A,M4_EN);//电机4 GPIO
  531.   mcpwm_gpio_init(MCPWM_UNIT_1,MCPWM1B,M4_PN);
  532.   mcpwm_init(MCPWM_UNIT_1,MCPWM_TIMER_1,&pwm_config);//初始化mcpwm的某一个单元并绑定时钟
  533. }
  534. void setup(void)
  535. {
  536.   Serial.begin(115200);
  537.   while(axp.begin() != 0){
  538.     Serial.println("init error");
  539.     delay(1000);
  540.   }
  541.   axp.enableCameraPower(axp.eOV2640);//设置摄像头供电
  542.   mcpwm_init();
  543.   WiFi.softAP(ssid, password);
  544.   IPAddress IP = WiFi.softAPIP();
  545.   Serial.print("AP IP address: ");
  546.   Serial.println(IP);
  547.   server.on("/", HTTP_GET, handleRoot);
  548.   server.onNotFound(handleNotFound);
  549.   wsCamera.onEvent(onCameraWebSocketEvent);
  550.   server.addHandler(&wsCamera);
  551.   wsCarInput.onEvent(onCarInputWebSocketEvent);
  552.   server.addHandler(&wsCarInput);
  553.   server.begin();
  554.   Serial.println("HTTP server started");
  555.   setupCamera();
  556. }
  557. void loop()
  558. {
  559.   wsCamera.cleanupClients();
  560.   wsCarInput.cleanupClients();
  561.   sendCameraPicture();
  562.   //Serial.printf("SPIRam Total heap %d, SPIRam Free Heap %d\n", ESP.getPsramSize(), ESP.getFreePsram());
  563. }
复制代码

ESP32 麦克纳姆轮 视频车图14ESP32 麦克纳姆轮 视频车图15ESP32 麦克纳姆轮 视频车图16
【演示视频】


_深蓝_  中级技师 来自手机

发表于 2023-9-24 15:14:52

云片出品,必属精品!!!
回复

使用道具 举报

Amos Young  中级技师

发表于 2023-10-4 14:54:38

这个创意有趣,云天老师好帅!
回复

使用道具 举报

曾剑波  初级技匠

发表于 2023-11-8 00:48:30

这个不错哦!值得研究一下
回复

使用道具 举报

您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

为本项目制作心愿单
购买心愿单
心愿单 编辑
[[wsData.name]]

硬件清单

  • [[d.name]]
btnicon
我也要做!
点击进入购买页面
上海智位机器人股份有限公司 沪ICP备09038501号-4

© 2013-2024 Comsenz Inc. Powered by Discuz! X3.4 Licensed

mail