• 【AirSim】 得到完整的 LiDAR数据


    Airsim得到完整的 LiDAR 数据

    问题

    airsim中,激光雷达会根据激光雷达的旋转速度在一帧中返回它能够扫描的内容,然后在下一帧中继续扫描。不会在每一帧都获得完整的激光雷达扫描。

    解决

    我认为存在一个错误,publishPointCloud 查看的是非实时时间,而不是查看实时时间(它用于检查何时应该进行扫描),因此而不是发送非常接近完整扫描的扫描(± 5%),它将发送 70% 的扫描。

    通过进入项目文件夹中的 UnrealLidarSensor.cpp,并到getPointCloud() 函数中,修改两个delta_time 的值为 0.1f,使其仅发送完整扫描。这迫使函数相信它必须每次都进行全面扫描。

    // returns a point-cloud for the tick
    void UnrealLidarSensor::getPointCloud(const msr::airlib::Pose& lidar_pose, const msr::airlib::Pose& vehicle_pose,
                                          const msr::airlib::TTimeDelta delta_time, msr::airlib::vector<msr::airlib::real_T>& point_cloud, msr::airlib::vector<int>& segmentation_cloud)
    {
        point_cloud.clear();
        segmentation_cloud.clear();
    
        msr::airlib::LidarSimpleParams params = getParams();
        const auto number_of_lasers = params.number_of_channels;
    
        // cap the points to scan via ray-tracing; this is currently needed for car/Unreal tick scenarios
        // since SensorBase mechanism uses the elapsed clock time instead of the tick delta-time.
        constexpr float MAX_POINTS_IN_SCAN = 1e+5f;
        //delta_time = 0.1f;
        uint32 total_points_to_scan = FMath::RoundHalfFromZero(params.points_per_second * 0.1f);
        if (total_points_to_scan > MAX_POINTS_IN_SCAN) {
            total_points_to_scan = MAX_POINTS_IN_SCAN;
            UAirBlueprintLib::LogMessageString("Lidar: ", "Capping number of points to scan", LogDebugLevel::Failure);
        }
    
        // calculate number of points needed for each laser/channel
        const uint32 points_to_scan_with_one_laser = FMath::RoundHalfFromZero(total_points_to_scan / float(number_of_lasers));
        if (points_to_scan_with_one_laser <= 0) {
            //UAirBlueprintLib::LogMessageString("Lidar: ", "No points requested this frame", LogDebugLevel::Failure);
            return;
        }
    
        // calculate needed angle/distance between each point
        const float angle_distance_of_tick = params.horizontal_rotation_frequency * 360.0f * 0.1f;
        const float angle_distance_of_laser_measure = angle_distance_of_tick / points_to_scan_with_one_laser;
    
        // normalize FOV start/end
        const float laser_start = std::fmod(360.0f + params.horizontal_FOV_start, 360.0f);
        const float laser_end = std::fmod(360.0f + params.horizontal_FOV_end, 360.0f);
    
        // shoot lasers
        for (auto laser = 0u; laser < number_of_lasers; ++laser) {
            const float vertical_angle = laser_angles_[laser];
    
            for (auto i = 0u; i < points_to_scan_with_one_laser; ++i) {
                const float horizontal_angle = std::fmod(current_horizontal_angle_ + angle_distance_of_laser_measure * i, 360.0f);
    
                // check if the laser is outside the requested horizontal FOV
                if (!VectorMath::isAngleBetweenAngles(horizontal_angle, laser_start, laser_end))
                    continue;
    
                Vector3r point;
                int segmentationID = -1;
                // shoot laser and get the impact point, if any
                if (shootLaser(lidar_pose, vehicle_pose, laser, horizontal_angle, vertical_angle, params, point, segmentationID)) {
                    point_cloud.emplace_back(point.x());
                    point_cloud.emplace_back(point.y());
                    point_cloud.emplace_back(point.z());
                    segmentation_cloud.emplace_back(segmentationID);
                }
            }
        }
    
        current_horizontal_angle_ = std::fmod(current_horizontal_angle_ + angle_distance_of_tick, 360.0f);
    
        return;
    }
    
    • 1
    • 2
    • 3
    • 4
    • 5
    • 6
    • 7
    • 8
    • 9
    • 10
    • 11
    • 12
    • 13
    • 14
    • 15
    • 16
    • 17
    • 18
    • 19
    • 20
    • 21
    • 22
    • 23
    • 24
    • 25
    • 26
    • 27
    • 28
    • 29
    • 30
    • 31
    • 32
    • 33
    • 34
    • 35
    • 36
    • 37
    • 38
    • 39
    • 40
    • 41
    • 42
    • 43
    • 44
    • 45
    • 46
    • 47
    • 48
    • 49
    • 50
    • 51
    • 52
    • 53
    • 54
    • 55
    • 56
    • 57
    • 58
    • 59
    • 60
    • 61
    • 62

    注:0.1f 由 1/update_frequency 计算得出,可以在 LidarSimpleParams.hpp 中找到并编辑 update_frequency。

  • 相关阅读:
    Kotlin 开发Android app(十五):使用Broadcast收发广播
    【Python】数据类型 + 运算符 + 输入输出
    生动实践现代农业-国稻种芯-泸州江阳:谋定产村深度融合
    Java 设计模式 — 抽象工厂模式(2)
    详解自定义数据类型
    大数据技术基础实验九:Hive实验——部署Hive
    1156 Sexy Primes – PAT甲级真题
    学习ros1很好的免费教材:wiki.ros.org/cn
    (184)Verilog HDL:设计一个移位功能Shift18
    Python自动化办公【PDF文件自动化】
  • 原文地址:https://blog.csdn.net/hhz_999/article/details/126440762