激光相机数据融合(5)--Gazebo仿真数据融合

这一节将用ROS+Gazebo 环境获取激光获取点云,并用PCL和OPENCV处理,源代码在:https://github.com/ZouCheng321/5_laser_camera_sim

 由于激光的视角远大于相机,所以我们使用了5个相机来获取图像,这类似于Ladybug相机:

相机获取的五张图像:

 

接下来我们用来构建彩色点云:

相机与激光的位置变换,由于是正五边形分别,这很容易求得:

  Eigen::Matrix4f rt0,rt1,rt2,rt3,rt4;
    rt0<< 0,0,-1,0,  0,1,0,0,  1,0,0,0, 0,0,0,1;
    rt1<< 0,0,-1,0,  -0.95105651629,0.30901699437,0,0,  0.30901699437,0.95105651629,0,0, 0,0,0,1;
    rt2 << 0,0,-1,0,  -0.58778525229,-0.80901699437,0,0,  -0.80901699437,0.58778525229,0,0, 0,0,0,1;
    rt3 << 0,0,-1,0,  0.58778525229,-0.80901699437,0,0,  -0.80901699437,-0.58778525229,0,0, 0,0,0,1;
    rt4 << 0,0,-1,0,  0.95105651629,0.30901699437,0,0,  0.30901699437,-0.95105651629,0,0, 0,0,0,1;
    Eigen::Matrix4f inv0,inv1,inv2,inv3,inv4;
    inv0=rt0.inverse();
    inv1=rt1.inverse();
    inv2=rt2.inverse();
    inv3=rt3.inverse();
    inv4=rt4.inverse();

    RT.push_back(rt0);
    RT.push_back(rt1);
    RT.push_back(rt2);
    RT.push_back(rt3);
    RT.push_back(rt4);

    INV.push_back(inv0);
    INV.push_back(inv1);
    INV.push_back(inv2);
    INV.push_back(inv3);
    INV.push_back(inv4);

相机的内参,已经在仿真软件中设定:

 std::vector<cv::Point2d> imagePoints;

    cv::Mat intrisicMat(3, 3, cv::DataType<double>::type); // Intrisic matrix
    intrisicMat.at<double>(0, 0) = 476.715669286;
    intrisicMat.at<double>(1, 0) = 0;
    intrisicMat.at<double>(2, 0) = 0;

    intrisicMat.at<double>(0, 1) = 0;
    intrisicMat.at<double>(1, 1) = 476.715669286;
    intrisicMat.at<double>(2, 1) = 0;

    intrisicMat.at<double>(0, 2) = 400;
    intrisicMat.at<double>(1, 2) = 400;
    intrisicMat.at<double>(2, 2) = 1;



    cv::Mat rVec(3, 1, cv::DataType<double>::type); // Rotation vector
    rVec.at<double>(0) = 0;
    rVec.at<double>(1) = 0;
    rVec.at<double>(2) = 0;

    cv::Mat tVec(3, 1, cv::DataType<double>::type); // Translation vector
    tVec.at<double>(0) = 0.4;
    tVec.at<double>(1) = 0;
    tVec.at<double>(2) = -0.1;

    cv::Mat distCoeffs(5, 1, cv::DataType<double>::type);   // Distortion vector
    distCoeffs.at<double>(0) = 0;
    distCoeffs.at<double>(1) = 0;
    distCoeffs.at<double>(2) = 0;
    distCoeffs.at<double>(3) = 0;
    distCoeffs.at<double>(4) = 0;

去除相机后方的点云:

std::vector<cv::Point3d> Generate3DPoints(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,int num)
{
    std::vector<cv::Point3d> points;
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_f (new pcl::PointCloud<pcl::PointXYZ>);

    Eigen::Matrix4f TR;
    TR << 0,0,-1,0,  0,1,0,0,  1,0,0,0, 0,0,0,1;
    pcl::transformPointCloud (*cloud, *cloud_f, RT[num]);

    pcl::PassThrough<pcl::PointXYZ> pass;
    pass.setInputCloud (cloud_f);
    pass.setFilterFieldName ("z");
    pass.setFilterLimits (0.0, 10);
    //pass.setFilterLimitsNegative (true);
    pass.filter (*cloud);
    cout<<"size:"<<cloud->size()<<endl;



    for(int i=0;i<=cloud->points.size();i++)
    {
        points.push_back(cv::Point3d(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z));
    }

    return points;
}

将前方的点云投影到相机平面,这里直接用opencv自带的projectPoints函数:

        cv::projectPoints(objectPoints, rVec, tVec, intrisicMat, distCoeffs, imagePoints);

保留图像内的点云:

 for(int i=0;i<imagePoints.size();i++)
        {
            if(imagePoints[i].x>=0&&imagePoints[i].x<800&&imagePoints[i].y>=0&&imagePoints[i].y<800)
            {

                pcl::PointXYZRGB point;
                point.x = cloud->points[i].x;
                point.y = cloud->points[i].y;
                point.z = cloud->points[i].z;
                point.r = _I(round(imagePoints[i].x),round(imagePoints[i].y))[2];
                point.g = _I(round(imagePoints[i].x),round(imagePoints[i].y))[1];
                point.b = _I(round(imagePoints[i].x),round(imagePoints[i].y))[0];

                colored_cloud->points.push_back (point);
            }
        }

最后显示所有点云:

  pcl::visualization::PCLVisualizer viewer("Cloud viewer");
    viewer.addPointCloud(colored_cloud_sum, "sample cloud");
    viewer.setBackgroundColor(0,0,0);

    while(!viewer.wasStopped())
        //while (!viewer->wasStopped ())
        viewer.spinOnce(100);

要构建这个项目:

cd 5_laser_camera_sim
mkdir build
cd build
cmake ..
make
./color

将看到如下显示:

 

转载于:https://www.cnblogs.com/zoucheng/p/7867986.html

px4是一款开放源代码的飞行控制软件,它广泛应用于无人机的飞行控制系统中。而gazebo是一款用于机器人模拟和仿真的强大工具。基于gazebo的视觉导航仿真是指利用gazebo仿真环境和px4飞行控制系统进行无人机的视觉导航仿真。 在学习px4的过程中,基于gazebo的视觉导航仿真是一个重要的学习内容。这种仿真方式可以提供一个虚拟的环境,使得我们可以在计算机上进行无人机的飞行控制和导航算法的开发与测试。 学习基于gazebo的视觉导航仿真,首先需要了解gazebo的基本原理和使用方法。gazebo可以模拟真实的物理环境,包括地形、天气等因素,同时还能够与px4飞行控制系统进行集成。学习者需要掌握gazebo的安装和配置,以及如何创建无人机模型和仿真场景。 其次,学习者还需要了解px4飞行控制系统在视觉导航方面的应用。px4可以利用无人机搭载的摄像头获取图像信息,并通过计算机视觉算法进行视觉导航。学习者需要学习如何配置无人机的视觉传感器,并利用px4的导航算法实现视觉导航功能。 在学习过程中,可以通过模拟不同的仿真场景,如室内、室外、复杂地形等,来测试和优化视觉导航算法。学习者可以通过观察仿真结果,调整算法参数和改进算法,提高无人机的导航精度和鲁棒性。 总体而言,基于gazebo的视觉导航仿真是学习px4的重要环节之一。通过这种仿真方式,可以帮助学习者深入了解px4飞行控制系统和视觉导航算法的原理和应用,提升无人机的导航能力。
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值