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

    在loop中运行rcl_publish时,core1会报错panic,导致无法正常发布消息

    已定时 已固定 已锁定 已移动 已解决
    FishBot二驱机器人
    core1 panic 发布失败
    3
    5
    358
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • G
      Gerry
      最后由 Gerry 编辑

      学到https://fishros.com/d2lros2/#/humble/chapt16/15.%E9%87%87%E7%94%A8MicroROS%E5%8F%91%E5%B8%83%E9%87%8C%E7%A8%8B%E8%AE%A1课程,照着写完代码后运行,ros topic list 发现没有/odm, 打开串口发现报错:(core1 panic)
      0ea51e81-a9a9-4f23-81cc-5d12ce349e46-图片.png

      经过进一步排查,发现是loop中的rcl_publish(&odom_publisher, &odom_msg, NULL); 一句有问题(删掉就不会导致内核1反复报错重启), 于是我加上报错打印:
      if(rcl_publish(&odom_publisher, &odom_msg, NULL) != RCL_RET_OK)
      {
      Serial.printf("Failed to publish: %s\n", rcl_get_error_string().str);
      }
      运行后果然:
      edd0e393-0390-4797-85cb-b630c862ff82-图片.png
      看来是 rcl_publish 未能够成功发布;
      于是我将这句话(rcl_publish(&odom_publisher, &odom_msg, NULL); )转移到core0的任务 microros_task 中,如下图:
      3f0caa52-e147-4442-9db4-fdbeb1797637-图片.png
      烧录运行后,果然程序正常运行了!!! 并且/odom也能够正常发布了:
      42c78c2a-c3b1-47a6-a222-50302aa9ee73-图片.png

      ef039061-8759-4745-bfb1-8229c1b7e09c-图片.png

      为了进一步排查错误所在,我回到example12 ,教授编写发布节点的那个工程,将定时器的代码注释调, 在loop中手动发布, 如下图:
      4ca6b07c-4b3a-4b61-b75f-72c691c91bd3-图片.png

      烧录运行后,发现这时程序是能够正常运行的 :
      53ce395e-7945-4af0-a7ac-ded9a4a53f1f-图片.png

      但是!!, 当我在setup()中添加一个任务给 core0(这个任务什么都不做),其他代码保持不变时, 话题发布失败了! :
      9d5371c7-5b30-4c3b-bd1b-2d3d4e4bca93-图片.png
      (这是添加的代码)

      7ef120f4-82f7-429d-86e0-c3fd49ca60b2-图片.png
      (这里 echo 卡住了,无法输出数据)

      7b02505e-a2cf-4453-9d37-0d81e6edfd61-图片.png
      (这时打开串口可以看到一些乱码,但从core1 panic ,CPU_RESET等字样不难看出是和之前一样的问题,即core1恐慌导致重启)

      到这时我基本可以断定,当分配任务给core0时(xTaskCreatePinnedToCore 函数),在loop 中 rcl_publish 会导致 core1 panic, 从而发布失败;

      我也考虑过是不是我的板子核心坏了,但找了客服,说是我代码有问题,可是我并没有检查出什么问题, 更何况我是照着小鱼老师的教程一句句敲的,:
      60ab1017-042b-4c14-b305-d63b11e01acf-c4bcd3f16c4c21a92cde91a4133b39ac.jpg

      所以我按照他说的,到社区提问,希望能够得到解答 @小鱼

      G 小鱼小 2 条回复 最后回复 回复 引用 0
      • 小鱼小
        小鱼 技术大佬 @Gerry
        最后由 编辑

        @Gerry 1.该教程不再维护,请按照最新的教程《ROS2机器人开发从入门到实践》学习
        2. 代码有问题的地方是 microROS 还没初始化完成,loop函数就已经开始执行了

        xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);

        if(rcl_publish(&publisher, &pub_msg, NULL) != RCL_RET_OK)
        {
        Serial.printf("Failed to publish: %s\n", rcl_get_error_string().str);
        }

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

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

          从你描述的情况来看,问题出现在使用 rcl_publish 函数时与 FreeRTOS 的任务调度以及核心分配有关。在使用 MicroROS 和 FreeRTOS 的多核系统中,任务的分配和调度需要特别注意,以避免资源冲突或任务抢占导致的问题。

          分析问题

          1. Core1 Panic: 当在 loop 中调用 rcl_publish 时,如果该函数内部尝试访问或操作了被其他核心(如 core0)占用的资源,可能会导致资源冲突或访问违规,从而触发 panic。

          2. 任务分配的影响: 当你将 rcl_publish 移至 core0 的任务中,并且 core0 没有其他任务或资源竞争时,rcl_publish 可以正常工作。但是,一旦在 core0 上添加其他任务(即使这些任务看似空闲),可能会影响 rcl_publish 的执行环境,特别是如果这些任务与 ROS 2 的内部机制(如网络堆栈、定时器、内存管理等)存在资源竞争。

          3. 社区教程与硬件差异: 虽然你是按照教程操作,但硬件平台(特别是多核处理器)的具体实现和配置可能会影响 FreeRTOS 和 MicroROS 的行为。此外,教程可能未涵盖所有特定硬件平台上的最佳实践或潜在问题。

          解决建议

          1. 确保资源隔离:

            • 尽量避免在多个核心上运行可能访问相同资源的任务。
            • 如果需要在多个核心上运行 ROS 2 相关的任务,确保这些任务不会同时访问共享资源,或者通过适当的同步机制(如互斥锁)来保护这些资源。
          2. 优化任务分配:

            • 将所有与 ROS 2 通信相关的任务(包括发布和订阅)分配给一个核心,以减少资源竞争。
            • 使用 xTaskCreatePinnedToCore 函数明确指定任务的运行核心。
          3. 调试和监控:

            • 使用 FreeRTOS 的调试工具监控任务状态和核心使用情况。
            • 检查是否有内存泄漏或堆栈溢出的问题,这些问题可能导致未定义行为。
          4. 社区和文档:

            • 访问 MicroROS 社区和文档,查找是否有关于多核处理和任务分配的特定指导。
            • 提问时提供尽可能详细的信息,包括硬件平台、FreeRTOS 版本、MicroROS 版本以及完整的代码示例。
          5. 硬件考虑:

            • 虽然硬件损坏的可能性较低,但如果问题持续存在,考虑在另一块相同的硬件上测试代码以排除硬件故障。

          通过上述步骤,你应该能够更准确地定位问题原因,并找到适合你的硬件和应用的解决方案。


          以上为生成回答,仅供参考~

          我是小伊,已接入ChatGpt,所有回复,仅供参考~

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

            @Gerry
            最后附上代码:

            fishbot_motion_control的main.cpp:
            
            #include <Arduino.h>
            #include <micro_ros_platformio.h>    
            #include <WiFi.h>                    
            #include <rcl/rcl.h>                
            #include <rclc/rclc.h>              
            #include <rclc/executor.h>          
            #include <geometry_msgs/msg/twist.h> 
            #include <Esp32PcntEncoder.h>        // 包含用于计数电机编码器脉冲的 ESP32 PCNT 编码器库
            #include <Esp32McpwmMotor.h>         // 包含使用 ESP32 的 MCPWM 硬件模块控制 DC 电机的 ESP32 MCPWM 电机库
            #include <PidController.h>           // 包含 PID 控制器库,用于实现 PID 控制
            #include <Kinematics.h>              // 运动学相关实现
            #include <nav_msgs/msg/odometry.h>
            #include <micro_ros_utilities/string_utilities.h>
            
            rcl_publisher_t odom_publisher;   // 用于发布机器人的里程计信息(Odom)
            nav_msgs__msg__Odometry odom_msg; // 机器人的里程计信息
            rcl_timer_t timer;
            
            Esp32PcntEncoder encoders[2];      // 编码器数组
            
            rclc_executor_t executor;          
            rclc_support_t support;            
            rcl_allocator_t allocator;        
            rcl_node_t node;                  
            
            rcl_subscription_t subscriber;     
            geometry_msgs__msg__Twist sub_msg; 
            Esp32McpwmMotor motor;             
            
            float out_motor_speed[2];        // 用于保存输出电机速度
            
            PidController pid_controller[2]; // 创建PidController的两个对象
            Kinematics kinematics;           // 运动学相关对象
            
            void twist_callback(const void *msg_in)
            {
              const geometry_msgs__msg__Twist *twist_msg = (const geometry_msgs__msg__Twist *)msg_in;
            
              static float target_motor_speed1, target_motor_speed2;
            
              float linear_x = twist_msg->linear.x;   // 获取 Twist 消息的线性 x 分量
              float angular_z = twist_msg->angular.z; // 获取 Twist 消息的角度 z 分量
            
              Serial.printf("linear speed: %f   angular speed: %f\n",  linear_x, angular_z);
            
              kinematics.kinematic_inverse(linear_x * 1000, angular_z, target_motor_speed1, target_motor_speed2);
            
              pid_controller[0].update_target(target_motor_speed1);
              pid_controller[1].update_target(target_motor_speed2);
            }
            
            // 这个函数是一个后台任务,负责设置和处理与 micro-ROS 代理的通信。
            void microros_task(void *param)
            {
            
              IPAddress agent_ip;
              agent_ip.fromString("");
            
              set_microros_wifi_transports(" ", " ", agent_ip, 8888);
            
               // 使用 micro_ros_string_utilities_set 函数设置到 odom_msg.header.frame_id 中
               odom_msg.header.frame_id = micro_ros_string_utilities_set(odom_msg.header.frame_id, "odom");
               odom_msg.child_frame_id = micro_ros_string_utilities_set(odom_msg.child_frame_id, "base_link");
            
              delay(2000);
            
              allocator = rcl_get_default_allocator();
              rclc_support_init(&support, 0, NULL, &allocator);
              rclc_node_init_default(&node, "esp32_car", "", &support);
            
              rclc_subscription_init_default(
                  &subscriber,
                  &node,
                  ROSIDL_GET_MSG_TYPE_SUPPORT(geometry_msgs, msg, Twist),
                  "/cmd_vel");
            
              rcl_ret_t pub_init_ret = rclc_publisher_init_best_effort(
                &odom_publisher,
                &node,
                ROSIDL_GET_MSG_TYPE_SUPPORT(nav_msgs, msg, Odometry),
                "odom");
            
              if (pub_init_ret != RCL_RET_OK) {
                  Serial.printf("Failed to initialize odom_publisher! Error code: %d, Error message: %s\n", 
                                pub_init_ret, rcl_get_error_string().str);
                  rcl_reset_error(); // 清除错误,以便后续不受影响
              }
            
              rclc_executor_init(&executor, &support.context, 1, &allocator);
              rclc_executor_add_subscription(&executor, &subscriber, &sub_msg, &twist_callback, ON_NEW_DATA);
            
              // 循环运行 micro-ROS 执行器以处理传入的消息。
              while (true)
              {
                if (!rmw_uros_epoch_synchronized())
                {
                  rmw_uros_sync_session(1000);
                  // 如果时间同步成功,则将当前时间设置为MicroROS代理的时间,并输出调试信息。
                  delay(10);
                }
                delay(100);
                rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
                if(rcl_publish(&odom_publisher, &odom_msg, NULL) != RCL_RET_OK)
                {
                  Serial.printf("Failed to publish: %s\n", rcl_get_error_string().str);
                }
              }
            }
            
            
            void setup()
            {
              Serial.begin(115200);
            
              motor.attachMotor(0, 22, 23);
              motor.attachMotor(1, 12, 13);
            
              // 在引脚32、33和26、25上初始化两个编码器
              encoders[0].init(0, 32, 33);
              encoders[1].init(1, 26, 25);
            
              // 初始化PID控制器的kp、ki和kd
              pid_controller[0].update_pid(0.625, 0.125, 0.0);
              pid_controller[1].update_pid(0.625, 0.125, 0.0);
            
              // 初始化PID控制器的最大输入输出,MPCNT大小范围在正负100之间
              pid_controller[0].out_limit(-100, 100);
              pid_controller[1].out_limit(-100, 100);
            
              // 设置运动学参数
              kinematics.set_motor_param(0, 45, 44, 65);
              kinematics.set_motor_param(1, 45, 44, 65);
              kinematics.set_kinematic_param(150);
            
              // 在核心0上创建一个名为"microros_task"的任务,栈大小为10240
              xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);
            }
            
            unsigned long previousMillis = 0; 
            unsigned long interval = 50; 
            
            void loop()
            {
              static float out_motor_speed[2];
            
              kinematics.update_motor_ticks(micros(), encoders[0].getTicks(), encoders[1].getTicks());
            
              out_motor_speed[0] = pid_controller[0].update(kinematics.motor_speed(0));
              out_motor_speed[1] = pid_controller[1].update(kinematics.motor_speed(1));
            
              motor.updateMotorSpeed(0, out_motor_speed[0]);
              motor.updateMotorSpeed(1, out_motor_speed[1]);
            
              unsigned long currentMillis = millis(); // 获取当前时间
              if (currentMillis - previousMillis >= interval)
              {                                 // 判断是否到达间隔时间
                previousMillis = currentMillis; // 记录上一次打印的时间
                float linear_speed, angle_speed;
                kinematics.kinematic_forward(kinematics.motor_speed(0), kinematics.motor_speed(1), linear_speed, angle_speed);
            
                //  Serial.printf("[%ld] linear:%f angular:%f\n", currentMillis, linear_speed, angle_speed);                 
                // Serial.printf("[%ld] x:%f y:%f yaml:%f\n", currentMillis,
                //                                         kinematics.odom().x, kinematics.odom().y, kinematics.odom().yaw); 
            
                // 用于获取当前的时间戳,并将其存储在消息的头部中
                int64_t stamp = rmw_uros_epoch_millis();
                // 获取机器人的位置和速度信息,并将其存储在一个ROS消息(odom_msg)中
                odom_t odom = kinematics.odom();
                odom_msg.header.stamp.sec = static_cast<int32_t>(stamp / 1000); // 秒部分
                odom_msg.header.stamp.nanosec = static_cast<uint32_t>((stamp % 1000) * 1e6); // 纳秒部分
                odom_msg.pose.pose.position.x = odom.x;
                odom_msg.pose.pose.position.y = odom.y;
                odom_msg.pose.pose.orientation.w = odom.quaternion.w;
                odom_msg.pose.pose.orientation.x = odom.quaternion.x;
                odom_msg.pose.pose.orientation.y = odom.quaternion.y;
                odom_msg.pose.pose.orientation.z = odom.quaternion.z;
            
                odom_msg.twist.twist.angular.z = odom.angular_speed;
                odom_msg.twist.twist.linear.x = odom.linear_speed;
            
                //Serial.printf("X: %f Y: %f LINEAR: %f ANGULAR: %f\n", odom.x, odom.y, odom.linear_speed, odom.angular_speed);
            
                // if(rcl_publish(&odom_publisher, &odom_msg, NULL) != RCL_RET_OK)
                // {
                //   Serial.printf("Failed to publish: %s\n", rcl_get_error_string().str);
                // }
            
                //rcl_ret_t ret = rcl_publish(&odom_publisher, &odom_msg, NULL);
              }
            
              // 延迟10毫秒
              delay(10);
            }
            

            <============================================>

            example12的main.cpp:

            #include <Arduino.h>
            #include <micro_ros_platformio.h>
            
            #include <rcl/rcl.h>
            #include <rclc/rclc.h>
            #include <rclc/executor.h>
            #include <std_msgs/msg/float32.h>
            
            rclc_executor_t executor;
            rclc_support_t support;
            rcl_allocator_t allocator;
            rcl_node_t node;
            rcl_timer_t timer;
            
            rcl_publisher_t publisher;
            std_msgs__msg__Float32 pub_msg;
            
            void timer_callback(rcl_timer_t* timer, int64_t last_call_time)
            {
              RCLC_UNUSED(last_call_time);
              if(timer != NULL)
              {
                rcl_publish(&publisher, &pub_msg, NULL);
              }
            }
            
            void microros_task(void *param)
            {
              int i = 0;
            }
            
            void setup()
            {
              Serial.begin(115200);
              set_microros_serial_transports(Serial);
              delay(2000);
              allocator = rcl_get_default_allocator();
              rclc_support_init(&support, 0, NULL, &allocator);
              //创建节点
              rclc_node_init_default(&node, "topic_pub_test", "", &support);
              //发布者初始化
              rclc_publisher_init_default(
                &publisher,
                &node,
                ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, Float32),
                "battery_voltage"
              );
              const unsigned int timer_timeout = 200;
              //定时器实例化
              rclc_timer_init_default(
                &timer,
                &support,
                RCL_MS_TO_NS(timer_timeout),
                timer_callback
              );
              /*
              timeout_ns: 类型为 uint64_t 的无符号64位整数,表示定时器的超时时间,单位是纳秒(nanoseconds)。
              这是定时器在触发回调函数之前需要等待的时间。
            
              callback: 类型为 rcl_timer_callback_t 的函数指针,指向定时器每次触发时应调用的回调函数。
              这个回调函数的原型通常是 void callback(rcl_timer_t * timer, int64_t last_call_time),其中 timer 是触发回调的定时器,
              last_call_time 是最后一次调用回调函数的时间戳(以纳秒为单位)。
              */
             //执行器初始化
             rclc_executor_init(&executor, &support.context, 1, &allocator);
             //number_of_handles: 类型为 size_t 的无符号整数,表示执行器可以管理的总句柄数。
             //这里的句柄是指订阅(subscriptions)、定时器(timers)、服务(services)、客户端(clients)和守护条件(guard conditions)。
             //注意,这个数字不包括节点(nodes)和发布者(publishers)的数量。
             rclc_executor_add_timer(&executor, &timer);
             //初始化ADC
             pinMode(34, INPUT);
             analogSetAttenuation(ADC_11db);
            
             xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);
            }
            
            void loop()
            {
              delay(100);
              //rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
            
              int analogValue = analogRead(34);
              int analogVolts = analogReadMilliVolts(34); //获取模拟电压,单位为毫伏
              float realVolts = 5.02 * ((float)analogVolts * 1e-3);
              pub_msg.data = realVolts;
            
              if(rcl_publish(&publisher, &pub_msg, NULL) != RCL_RET_OK)
              {
                Serial.printf("Failed to publish: %s\n", rcl_get_error_string().str);
              }
            }
            
            1 条回复 最后回复 回复 引用 0
            • G Gerry 将这个主题转为问答主题,在
            • 小鱼小
              小鱼 技术大佬 @Gerry
              最后由 编辑

              @Gerry 1.该教程不再维护,请按照最新的教程《ROS2机器人开发从入门到实践》学习
              2. 代码有问题的地方是 microROS 还没初始化完成,loop函数就已经开始执行了

              xTaskCreatePinnedToCore(microros_task, "microros_task", 10240, NULL, 1, NULL, 0);

              if(rcl_publish(&publisher, &pub_msg, NULL) != RCL_RET_OK)
              {
              Serial.printf("Failed to publish: %s\n", rcl_get_error_string().str);
              }

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

              G 1 条回复 最后回复 回复 引用 0
              • G Gerry 将这个主题标记为已解决,在
              • G
                Gerry @小鱼
                最后由 编辑

                @小鱼
                明白了! 谢谢小鱼!果然在setup最后加上delay(3000)就好用了😊 😊 😊 👍 👍 👍

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