相机和雷达外参联合标定

这篇具有很好参考价值的文章主要介绍了相机和雷达外参联合标定。希望对大家有所帮助。如果存在错误或未考虑完全的地方,请大家不吝赐教,您也可以点击"举报违法"按钮提交疑问。

内容: 关于雷达和相机外参联合标定的踩坑纪录。

Date: 2023/03/19

硬件:

  • 上位机: Jetson ORIN (Ubuntu 20.04, ROS noetic)
  • 雷达: Ouster 32线
  • 相机: Intel D435

一、 标定方案

目前流行的 雷达+相机 标定方案有五种:Autoware, apollo, lidar_camera_calibration, but_velodyne。

Ubuntu20.04安装autoware我看bug比较多,因此我follow的是: https://github.com/ankitdhall/lidar_camera_calibration

相机和雷达外参联合标定

1.1 opencv

这一步花了我一天时间,坑比较多,需要安装opencv_contrib才能进行进一步的操作,仅仅安装opencv是不行的!

我安的版本是3.4.10。

参考:

  • https://blog.csdn.net/m0_73694897/article/details/129175515?spm=1001.2014.3001.5506
  • https://blog.csdn.net/weixin_34910922/article/details/125248118?spm=1001.2014.3001.5506

二、 时间强行同步

直接实时或者直接播包的话就会发生: 只有mono8这一个窗口,没有其他窗口弹出!

  • Only Mono8 window visible · Issue #94 · ankitdhall/lidar_camera_calibration
  • https://github.com/ankitdhall/lidar_camera_calibration/issues/65
  • https://github.com/ankitdhall/lidar_camera_calibration/issues/53

因为车是静止的,如果时间戳不完全一致,标定的程序是无法弹出点云窗口的,这个bug困扰了我很久,在issues中也没找到也没有人能给出解决方案,于是我把时间戳都强行设置到1970年,解决。

#!/usr/bin/env python3

import rospy
import rosbag
import sys

if sys.getdefaultencoding() != 'utf-8':
    reload(sys)
    sys.setdefaultencoding('utf-8')
bag_name = 'subset_2023-03-19-15-52-03.bag' #被修改的bag名
out_bag_name = 'change.bag' #修改后的bag名
dst_dir = '/aigo/' #使用路径

with rosbag.Bag(dst_dir+out_bag_name, 'w') as outbag:
    stamp = None
    #topic:就是发布的topic msg:该topic在当前时间点下的message t:消息记录时间(非header)
    ##read_messages内可以指定的某个topic
    for topic, msg, t in rosbag.Bag(dst_dir+bag_name).read_messages():
       
       
        if topic == '/ouster/points':
            stamp = msg.header.stamp
           # print("imu")
            #print(stamp)
            outbag.write(topic, msg, stamp)
        #针对没有header的文件,使用上面帧数最高的topic(即:/gps)的时间戳
        ##因为read_messages是逐时间读取,所以该方法可以使用
        elif topic == '/camera/color/image_raw' and stamp is not None: 
            #print("lidar")
            #print(msg.header.stamp)
            outbag.write(topic, msg, stamp)
        #    continue
        # #针对格式为Header的topic
        elif topic == '/camera/depth/image_rect_raw' and stamp is not None:
            #print("image")
            #print(msg.header.stamp)
            outbag.write(topic, msg, stamp)

        #     outbag.write(topic, msg, msg.stamp)
        #     continue
        # #针对一般topic
        #outbag.write(topic, msg, msg.header.stamp)

print("finished")
  • 前:

相机和雷达外参联合标定

  • 后:

相机和雷达外参联合标定

三、 标定

我用的雷达是32线的,我修改了/home/nvidia/wuke/a2b_ws/src/lidar_camera_calibration/include/lidar_camera_calibration/PreprocessUtils.h:

// line 200
// std::vector <std::vector<myPointXYZRID *>> rings(16);
std::vector <std::vector<myPointXYZRID *>> rings(32);
  • 播包:
roscore

cd /aigo/
rosbag play -l --clock change.bag 
  • 标定:
cd ~/wuke/a2b_ws
source devel/setup.bash

roslaunch lidar_camera_calibration find_transform.launch 

相机和雷达外参联合标定

四、 标定结果

--------------------------------------------------------------------
After 40 iterations
--------------------------------------------------------------------
Average translation is:
0.00659326
 -0.241034
 -0.113246
Average rotation is:
  0.901867 0.00575031   0.431975
-0.0142371   0.999764  0.0164154
 -0.431778 -0.0209546   0.901736
Average transformation is: 
  0.901867 0.00575031   0.431975 0.00659326
-0.0142371   0.999764  0.0164154  -0.241034
 -0.431778 -0.0209546   0.901736  -0.113246
         0          0          0          1
Final rotation is:
  0.0174841   -0.999826 -0.00654644
  0.0208512  0.00691063   -0.999759
    0.99963   0.0173434   0.0209684
Final ypr is:
0.873007
-1.54358
 0.69106
Average RMSE is: 0.0291125
RMSE on average transformation is: 0.0298826
4.1 将雷达点云投影到相机坐标系

上面的位姿变换是从雷达坐标系到相机坐标系的变换。

我打算把雷达点云变换到相机坐标系下然后和深度图对比,看重叠效果咋样:

  • 将D435的深度图变成点云:

    #include <ros/ros.h>
    #include <cv_bridge/cv_bridge.h>
    #include <sensor_msgs/Image.h>
    #include <sensor_msgs/CameraInfo.h>
    #include <sensor_msgs/PointCloud2.h>
    #include <pcl_conversions/pcl_conversions.h>
    #include <pcl/point_types.h>
    #include <pcl/PCLPointCloud2.h>
    #include <pcl/conversions.h>
    #include <iostream>
    using namespace std;
     
    ros::Publisher pub_point_cloud2;
     
    bool is_K_empty = 1;
    double K[9];
    //     [fx  0 cx]
    // K = [ 0 fy cy]
    //     [ 0  0  1]
     
    void img_callback(const sensor_msgs::ImageConstPtr &img_msg)
    {
        // Step1: 读取深度图
        //ROS_INFO("image format: %s %dx%d", img_msg->encoding.c_str(), img_msg->height, img_msg->width);
        int height = img_msg->height;
        int width = img_msg->width;
        // 通过指针强制转换,读取为16UC1数据,单位是mm
        unsigned short *depth_data = (unsigned short*)&img_msg->data[0];
        
        // Step2: 深度图转点云
        sensor_msgs::PointCloud2 point_cloud2;
        pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
        for(int uy=0; uy<height; uy++)
        {
            for(int ux=0; ux<width; ux++)
            {
                float x, y, z;
                z = *(depth_data + uy*width + ux) / 1000.0;
                if(z!=0)
                {
                    x = z * (ux - K[2]) / K[0];
                    y = z * (uy - K[5]) / K[4];
                    pcl::PointXYZ p(x, y, z);
                    cloud->push_back(p);
                    
                }
            }
        }
        // Step3: 发布点云
        pcl::toROSMsg(*cloud, point_cloud2);
        point_cloud2.header.frame_id = "world";
        pub_point_cloud2.publish(point_cloud2);
    }
     
     
    void camera_info_callback(const sensor_msgs::CameraInfoConstPtr &camera_info_msg)
    {
        // 读取相机参数
        if(is_K_empty)
        {
            for(int i=0; i<9; i++)
            {
                K[i] = camera_info_msg->K[i];
            }
            is_K_empty = 0;
        }
    }
     
    int main(int argc, char **argv)
    {
        ros::init(argc, argv, "ros_tutorial_node");
        ros::NodeHandle n;
        // 订阅D435i的深度图,在其回调函数中把深度图转化为点云,并发布出来
        ros::Subscriber sub_img = n.subscribe("/camera/depth/image_rect_raw", 100, img_callback);
        // 订阅D435i的深度相机参数
        ros::Subscriber sub_cmara_info = n.subscribe("/camera/depth/camera_info", 1, camera_info_callback);
        pub_point_cloud2 = n.advertise<sensor_msgs::PointCloud2>("/d435i_point_cloud", 1000);
        
        ROS_INFO("Runing ...");
        ros::spin();
        return 0;
    }
    
  • 发布tf变换消息:

    rosrun tf2_ros static_transform_publisher 0 0 0 1.57 -1.57 0 world os_sensor
    
  • result:

    • raw

      相机和雷达外参联合标定

    • after (红色是雷达点云,白色是深度相机的投影)
      相机和雷达外参联合标定

Reference

[1] https://github.com/ankitdhall/lidar_camera_calibration/wiki/Welcome-to-%60lidar_camera_calibration%60-Wiki!

[2] 3D雷达与相机的标定方法详细教程_lidar_camera_calibration_敢敢のwings的博客-CSDN博客

[3] https://blog.csdn.net/m0_73694897/article/details/129175515?spm=1001.2014.3001.5506

[4] https://blog.csdn.net/weixin_34910922/article/details/125248118?spm=1001.2014.3001.5506

[5] https://blog.csdn.net/weixin_42840360/article/details/119844648?spm=1001.2014.3001.5506

[6] https://blog.csdn.net/Jeff_zjf/article/details/124255916?ops_request_misc=%257B%2522request%255Fid%2522%253A%2522167922032616800213053412%2522%252C%2522scm%2522%253A%252220140713.130102334.pc%255Fall.%2522%257D&request_id=167922032616800213053412&biz_id=0&utm_medium=distribute.pc_search_result.none-task-blog-2allfirst_rank_ecpm_v1~pc_rank_34-1-124255916-null-null.142文章来源地址https://www.toymoban.com/news/detail-500123.html

到了这里,关于相机和雷达外参联合标定的文章就介绍完了。如果您还想了解更多内容,请在右上角搜索TOY模板网以前的文章或继续浏览下面的相关文章,希望大家以后多多支持TOY模板网!

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处: 如若内容造成侵权/违法违规/事实不符,请点击违法举报进行投诉反馈,一经查实,立即删除!

领支付宝红包 赞助服务器费用

相关文章

  • 激光雷达与相机外参标定(附open3d python代码)

    现在的激光雷达与相机的标定程序基本都是Ubuntu框架下面的,并且都是C++代码,需要安装的依赖也比较复杂,于是自己写了一个python版本的标定程序,依赖非常简单,Windows系统也可以运行。并且代码简单一个文件搞定,符合python简单易行的风格。 先上最后标定后的效果图​

    2024年02月11日
    浏览(28)
  • 激光雷达和相机联合标定

    所有内容仅供个人学习记录 相机内参是相机坐标系转换到图像像素坐标系 相机内参是世界坐标系转换到相机坐标系 相机的成像过程涉及到四个坐标系:世界坐标系、相机坐标系、图像坐标系、像素坐标系。 四个坐标系: 1) 世界坐标系(world coordinate system) 现实世界的三维坐

    2024年01月18日
    浏览(36)
  • 激光雷达-相机联合标定

    https://f.daixianiu.cn/csdn/9499401684344864.html imu与lidar标定 https://github.com/PJLab-ADG/SensorsCalibration/blob/master/lidar2imu/README.md 多雷达标定 https://f.daixianiu.cn/csdn/3885826454722603.html ros usb相机内参标定 ROS系统-摄像头标定camera calibration_berry丶的博客-CSDN博客

    2024年02月15日
    浏览(30)
  • 镭神激光雷达和相机联合标定

    镭神激光雷达坐标系和相机坐标系都为右手坐标系 镭神激光雷达坐标系:原点为激光雷达光学中心,右为X,前为Y,上为Z 相机坐标系:原点为相机光心,右为X,下为Y,前为Z 同时规定欧拉角:绕X轴为俯仰角(pitch),绕Y轴为翻滚角(roll),绕Z轴为偏航(航向)角(heading、yaw)。 此时

    2024年02月09日
    浏览(54)
  • Autoware实现相机和激光雷达联合标定

    1-编译 2-修改代码 打开CMakeLIsts.txt 将三处该行 if (\\\"${ROS_VERSION}\\\" MATCHES \\\"(indigo|jade|kinetic)\\\") 改为 if (\\\"${ROS_VERSION}\\\" MATCHES \\\"(indigo|jade|kinetic|melodic)\\\") 重新编译: 3-测试启动 输入命令,显示如下,则证明正常: 启动激光雷达: /velodyne_points /rslidar_points 启动相机: /camera/color/image_raw 设

    2024年01月19日
    浏览(33)
  • 【Ubuntu18.04】激光雷达与相机联合标定(Livox+HIKROBOT)(一)相机内参标定

    Livox Lidar + HIKROBOT Camera 联合标定 参考链接:相机雷达标定文档 安装ROS环境,参考笔者的博客:【ROS】Ubuntu18.04安装Ros 参考链接:海康Camera MVS Linux SDK二次开发封装ROS packge过程记录(c++) 海康的相机没有ros驱动,且对linux开发不太友好(但支持windows),因此需要重写了sdk接口

    2024年02月04日
    浏览(35)
  • 相机雷达联合标定cam_lidar_calibration

    ubuntu18.04.6 melodic opencv 3.4.16 python 2.7.17 (ros自带) usb-cam 速腾robosense 16 官方Github: https://github.com/acfr/cam_lidar_calibration rs_to_velodyne :https://github.com/HViktorTsoi/rs_to_velodyne 1)工作空间创建和编译 2)官方数据集测试环境 ①开始标定 标定好的文件保存在 cam_lidar_calibration/data/vlp/路径下 ②

    2024年02月11日
    浏览(32)
  • 虚拟机(Ubuntu1804)相机与激光雷达联合标定实现过程记录

    在智能小车录制的点云数据在rviz打开一定要修改Fixed Frame为laser_link,这样才能看到点云,注意此时用的是雷神激光雷达,话题名是lslidar_,可采用rostopic list查看具体名称 1、新建一个终端打开roscore 2、在文件夹libratia中新建一个终端 【注意】这里的--pause可以暂停,当后面需要

    2024年02月16日
    浏览(39)
  • autoware标定工具进行固态激光雷达与相机的联合标定并运用标定结果进行投影(C++)

    本文主要介绍速腾聚创的RS-LIDAR-M1固态雷达激光与小觅相机左眼的联合标定过程,并介绍标定过程中的一些技巧与避雷,加快标定效率。最后给出运用标定结果进行投影的关键代码。 一、安装autoware(为了标定完成后的可视化,可选,本文并未用到) 参考https://blog.csdn.net/qq

    2024年02月08日
    浏览(34)
  • MATLAB - 激光雷达 - 相机联合标定(Lidar-Camera Calibration)

          激光雷达 - 相机标定建立了三维激光雷达点和二维相机数据之间的对应关系,从而将激光雷达和相机输出融合在一起。 激光雷达传感器和相机被广泛用于自动驾驶、机器人和导航等应用中的三维场景重建。激光雷达传感器捕捉环境的三维结构信息,而相机则捕捉色彩、

    2024年02月20日
    浏览(34)

觉得文章有用就打赏一下文章作者

支付宝扫一扫打赏

博客赞助

微信扫一扫打赏

请作者喝杯咖啡吧~博客赞助

支付宝扫一扫领取红包,优惠每天领

二维码1

领取红包

二维码2

领红包