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

    运行 fishbot_motion_control_microros 源码出现 [E][WiFiUdp.cpp:185] endPacket(): could not send data: 12

    已定时 已固定 已锁定 已移动
    FishBot二驱机器人
    源码 求助
    2
    7
    288
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • N
      nbb3210
      最后由 编辑

      背景

      嵌入式入门 ing
      硬件: Fishbot 二驱机器人
      软件代码: https://github.com/fishros/fishbot_motion_control_microros.git
      ROS 版本: humble

      问题

      修改 fishbot_config.h 中 WIFI_SERVER_IP, WIFI_SERVER_PORT, WIFI_STA_SSID, WIFI_STA_PSWK 后烧录代码,Serial Monitor 出现,且 ros-agent 无日志打印

      [ 33525][E][WiFiUdp.cpp:185] endPacket(): could not send data: 12
      [ 33632][E][WiFiUdp.cpp:185] endPacket(): could not send data: 12
      

      尝试解决方案

      排查内存问题

      根据 github issus [E][WiFiUdp.cpp:183] endPacket(): could not send data: 12 · Issue #845 · espressif/arduino-esp32 说 errno 12 is ENOMEM, 内存问题。
      在fishbot_motion_control_microros/lib/MicroRosRwm/micro_ros_transport_wifi_udp.cpp 的 platformio_transport_write_wifi_udp 添加打印日志

      
        size_t platformio_transport_write_wifi_udp(struct uxrCustomTransport *transport, const uint8_t *buf, size_t len, uint8_t *errcode)
        {
          (void)errcode;
          struct micro_ros_agent_locator *locator = (struct micro_ros_agent_locator *)transport->args;
      
          // 记录发送前的可用内存
          uint32_t freeHeapBefore = ESP.getFreeHeap();
          Serial.printf("[WiFiUDP] Before send - Free heap: %u bytes\n", freeHeapBefore);
      
          size_t sent = 0;
          int retry_count = 0;
          const int MAX_RETRIES = 3;
          
          while (sent == 0 && retry_count < MAX_RETRIES) {
            // If we're retrying, add a small delay with yield to let the system process other tasks
            if (retry_count > 0) {
              delay(50 * retry_count);
              
              // 每次重试前记录可用内存
              Serial.printf("[WiFiUDP] Retry %d - Free heap: %u bytes\n", retry_count, ESP.getFreeHeap());
            }
            
            if (true == udp_client.beginPacket(locator->address, locator->port)) {
              // Write the data to the UDP buffer
              sent = udp_client.write(buf, len);
              
              // 记录写入数据后的可用内存
              Serial.printf("[WiFiUDP] After write - Free heap: %u bytes, wrote %d bytes\n", ESP.getFreeHeap(), sent);
              
              // Check if write was successful
              if (sent != len) {
                retry_count++;
                continue;
              }
              
              // Try to send the packet
              bool endResult = udp_client.endPacket();
              
              // 记录endPacket后的可用内存
              uint32_t freeHeapAfter = ESP.getFreeHeap();
              Serial.printf("[WiFiUDP] After endPacket - Free heap: %u bytes, result: %s\n", 
                           freeHeapAfter, endResult ? "success" : "failed");
              Serial.printf("[WiFiUDP] Memory change: %d bytes\n", (int)freeHeapAfter - (int)freeHeapBefore);
              
              if (!endResult) {
                sent = 0;  // Reset sent count on failure
                
                // Give the system some time to free resources
                yield();
                
                // Close and reopen the UDP connection to free resources
                if (retry_count == MAX_RETRIES - 1) {
                  udp_client.stop();
                  delay(100);
                  udp_client.begin(locator->port);
                }
                
                retry_count++;
              }
            } else {
              retry_count++;
            }
          }
      
          // Flush the client
          udp_client.flush();
          
          // If we still couldn't send after all retries
          if (sent == 0) {
            Serial.printf("[WiFiUDP] Send completely failed - Final free heap: %u bytes\n", ESP.getFreeHeap());
          }
      
          return sent;
        }
      

      Monitor 输出如下,且 ros-agent 无日志打印

      [WiFiUDP] Before send - Free heap: 126924 bytes
      [WiFiUDP] After write - Free heap: 126924 bytes, wrote 16 bytes
      [473117][E][WiFiUdp.cpp:185] endPacket(): could not send data: 12
      [WiFiUDP] After endPacket - Free heap: 126924 bytes, result: failed
      [WiFiUDP] Memory change: 0 bytes
      

      写个简单的连接 wifi 和发送 UDP 包逻辑

      /**
       * @file main.cpp
       * @brief 极简WiFi连接和UDP发送示例
       */
      #include <Arduino.h>
      #include <WiFi.h>
      #include <WiFiUdp.h>
      
      // WiFi配置
      const char* ssid = "xxx";
      const char* password = "xxx";
      
      // UDP服务器配置
      const char* udpServerIP = "192.168.110.124";
      const int udpServerPort = 8888;
      
      // UDP实例
      WiFiUDP udp;
      
      // 函数声明
      void setupWiFi();
      bool sendUdpPacket(const char* message);
      
      void setup() {
        // 初始化串口
        Serial.begin(115200);
        delay(1000);
        Serial.println("\n\n极简WiFi和UDP测试程序启动");
      
        // 连接WiFi
        setupWiFi();
      
        // 如果WiFi连接成功,初始化UDP
        if (WiFi.status() == WL_CONNECTED) {
          Serial.println("初始化UDP...");
          udp.begin(8889); // 本地端口(与服务器端口不同)
          
          // 发送初始测试包
          sendUdpPacket("测试连接 - ESP32已连接");
        }
      }
      
      void loop() {
        // 检查WiFi连接状态
        if (WiFi.status() != WL_CONNECTED) {
          Serial.println("WiFi连接断开,尝试重连...");
          setupWiFi();
        }
        
        // 每2秒发送一个UDP数据包
        static unsigned long lastSendTime = 0;
        if (WiFi.status() == WL_CONNECTED && millis() - lastSendTime > 2000) {
          lastSendTime = millis();
          
          // 创建带时间戳的消息
          char message[64];
          snprintf(message, sizeof(message), "ESP32测试包 时间:%lu秒 内存:%u字节", 
                   millis()/1000, ESP.getFreeHeap());
          
          // 发送UDP包
          bool success = sendUdpPacket(message);
          if (success) {
            Serial.println("UDP包发送成功");
          } else {
            Serial.println("UDP包发送失败");
          }
        }
        
        delay(100); // 防止循环过快
      }
      
      void setupWiFi() {
        Serial.printf("正在连接WiFi: %s\n", ssid);
        
        // 重置WiFi
        WiFi.disconnect(true);
        delay(100);
        
        // 设置为站点模式
        WiFi.mode(WIFI_STA);
        WiFi.setSleep(WIFI_PS_NONE); // 禁用WiFi睡眠模式,提高稳定性
        
        // 开始连接
        WiFi.begin(ssid, password);
        
        // 等待连接完成
        int attempts = 0;
        while (WiFi.status() != WL_CONNECTED && attempts < 20) {
          delay(500);
          Serial.print(".");
          attempts++;
        }
        
        if (WiFi.status() == WL_CONNECTED) {
          Serial.println("\nWiFi连接成功!");
          Serial.print("IP地址: ");
          Serial.println(WiFi.localIP());
          Serial.print("信号强度: ");
          Serial.print(WiFi.RSSI());
          Serial.println(" dBm");
        } else {
          Serial.println("\nWiFi连接失败!");
        }
      }
      
      bool sendUdpPacket(const char* message) {
        // 确保WiFi已连接
        if (WiFi.status() != WL_CONNECTED) {
          Serial.println("WiFi未连接,无法发送UDP包");
          return false;
        }
        
        // 记录发送前的内存
        uint32_t freeHeapBefore = ESP.getFreeHeap();
        Serial.printf("发送前内存: %u字节\n", freeHeapBefore);
        
        // 初始化UDP包
        if (!udp.beginPacket(udpServerIP, udpServerPort)) {
          Serial.println("无法初始化UDP包");
          return false;
        }
        
        // 写入数据
        size_t bytesWritten = udp.write((const uint8_t*)message, strlen(message));
        if (bytesWritten != strlen(message)) {
          Serial.printf("UDP写入不完整: %d/%d字节\n", bytesWritten, strlen(message));
          return false;
        }
        
        // 发送数据包
        bool result = udp.endPacket();
        
        // 记录发送后的内存
        uint32_t freeHeapAfter = ESP.getFreeHeap();
        Serial.printf("发送后内存: %u字节 (变化: %d)\n", 
                     freeHeapAfter, (int)freeHeapAfter - (int)freeHeapBefore);
        
        if (!result) {
          Serial.println("UDP包发送失败 (endPacket错误)");
        }
        
        // 在发送后小延迟,避免发送过快
        delay(50);
        
        return result;
      }
      

      Monitor 输出如下,且 ros-agent 有日志

      发送前内存: 168836字节
      ��送后内存: 168596字节 (变化: -240)
      UDP包发送成功
      发送前内存: 168836字节
      ��送后内存: 168596字节 (变化: -240)
      UDP包发送成功
      发送前内存: 168836字节
      ��送后内存: 168596字节 (变化: -240)
      UDP包发送成功
      
      小鱼小 1 条回复 最后回复 回复 引用 1
      • 小鱼小
        小鱼 技术大佬 @nbb3210
        最后由 编辑

        @nbb3210 直接修改配置大概率无效,配置是写在flash中的,而不是代码,建议用配置助手修改

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

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

          @小鱼 在 运行 fishbot_motion_control_microros 源码出现 [E][WiFiUdp.cpp:185] endPacket(): could not send data: 12 中说:

          配置是写在flash中的,而不是代码,建议用配置助手修改

          可是无论是日志还是显示屏,都显示为我自己设置的 server_ip, wifi, 我理解是有效的

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

            @nbb3210 那就检查路由问题

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

            N 2 条回复 最后回复 回复 引用 0
            • N
              nbb3210 @小鱼
              最后由 编辑

              此回复已被删除!
              1 条回复 最后回复 回复 引用 0
              • N
                nbb3210 @小鱼
                最后由 nbb3210 编辑

                @小鱼 打扰了,原来是改了 fishbot_config.h 中的 ip 不生效,我是 mac os,用不了配置助手,请问如何覆盖 flash

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

                  @nbb3210 用源码版本的配置助手,到github开源库

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

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