lidar_camera_calib学习笔记(激光雷达相机标定)

参考项目链接:https://gitee.com/manifold/lidar_camera_calib/tree/master

  • 项目提供的bag中的信息
    在这里插入图片描述
  • pointgrey.yaml 文件内容
%YAML:1.0
K: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [1061.37439737547, 0, 980.706836288949,0, 1061.02435228316, 601.685030610243,0, 0, 1]
d: !!opencv-matrix
   rows: 5
   cols: 1
   dt: d
   data: [-0.149007007770170, 0.0729485326193990, 0.000257753168848673, -0.000207183134328829, 0]

Camera.width: 1920
Camera.height: 1200

grid_length: 0.15
corner_in_x: 7
corner_in_y: 5
  • launch文件配置
<?xml version="1.0"?>
<launch>

  <node pkg="ilcc2" type="get_image_corners_bag" name="get_image_corners_bag" output="screen">

    <param name="bag_path_prefix"  value= "/home/stone/Desktop/rosws/src/bag/2018-12-03-" />
    <param name="bag_num"  value= "6" />
    <param name="camera_name"  value= "pointgrey" />
    <param name="image_topic"  value= "/camera/image_raw " />
    <param name="yaml_path"  value= "pointgrey.yaml" />
    <param name="save_image_flag"  value= "true" />

  </node>
</launch>

  • 运行指令
roslaunch ilcc2 image_corners.launch
  • 得到的结果(去畸变后的图片)
    在这里插入图片描述
  • 对应的代码
#include <ros/ros.h>
#include <ros/package.h>
#include <iostream>

/// read rosbag
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <boost/foreach.hpp>
#define foreach BOOST_FOREACH

#include <sensor_msgs/Image.h>        /// sensor_msgs::Image
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui.hpp>


#include "ilcc2/ImageCornersEst.h"
//cv_bridge用于ROS图像和OpenCV图像的转换
cv::Mat get_image_from_msg(const sensor_msgs::ImageConstPtr& msg_img)
{
  //Create cv_brigde instance
  cv_bridge::CvImagePtr cv_ptr;
  try
  {
    cv_ptr=cv_bridge::toCvCopy(msg_img, sensor_msgs::image_encodings::MONO8);
  }
  catch (cv_bridge::Exception& e)
  {
    ROS_ERROR("Not able to convert sensor_msgs::Image to OpenCV::Mat format %s", e.what());
    return cv::Mat();
  }
  // sensor_msgs::Image to OpenCV Mat structure
  cv::Mat Image = cv_ptr->image;
  return Image;
}


int main(int argc, char **argv)
{
    ros::init(argc, argv, "image_corners");
    ros::NodeHandle nh;
    //显示出来ilcc2 package的路径
    std::string package_path = ros::package::getPath("ilcc2");
    ROS_INFO("ilcc2 package at %s", package_path.c_str());
	
    int bag_num;
    bool save_image_flag;
    std::string bag_path_prefix, image_topic, yaml_path, camera_name;
    ros::NodeHandle nh_private("~");
    //nh_private:一般用来参数配置。在launch文件中param标签会把参数解释为/node/param_name,相当于(~param_name)
    nh_private.param<std::string>("bag_path_prefix", bag_path_prefix, "20181101_");  //bag的前缀
    nh_private.param<int>("bag_num", bag_num, 1);                                    //bag的个数
    nh_private.param<std::string>("yaml_path", yaml_path, "30w.yaml");               //参数文件
    nh_private.param<std::string>("image_topic", image_topic, "/front");             // 对应的topic
    nh_private.param<std::string>("camera_name", camera_name, "front");             //输出的文件前缀
    nh_private.param<bool>("save_image_flag", save_image_flag, "true");

    std::cout << "bag_num: " << bag_num << std::endl;
    std::cout << package_path << "/config/" << yaml_path << std::endl;

    ImageCornersEst::Ptr image_corners_est(new ImageCornersEst);
    image_corners_est = ImageCornersEst::Ptr(new ImageCornersEst(package_path+"/config/"+yaml_path, true) );


    for(int bag_idx = 1; bag_idx <= bag_num; bag_idx++)
    {
        std::cout << bag_idx << "============================================================\n";
        std::string bag_path = bag_path_prefix+std::to_string(bag_idx)+".bag";
        ROS_INFO("bag_path: %s", bag_path.c_str());

        rosbag::Bag bag_read;
        bag_read.open(bag_path, rosbag::bagmode::Read);
        std::vector<std::string> topics;
        topics.push_back(image_topic);

        rosbag::View view(bag_read, rosbag::TopicQuery(topics));
        std::cout << "view: " << view.size() << std::endl;

        sensor_msgs::ImageConstPtr msg_image_last = NULL;
        foreach(rosbag::MessageInstance const m, view)
        {
            sensor_msgs::ImageConstPtr msg_image = m.instantiate<sensor_msgs::Image>();
            if (msg_image != NULL){
              msg_image_last = msg_image;
            }

            if(msg_image_last != NULL)
              break;
        }
        bag_read.close();

        if(msg_image_last == NULL)
        {
          ROS_WARN("can't read image topic");
          continue;
        }


        ROS_INFO("findCorners");
        cv::Mat image = get_image_from_msg(msg_image_last);

        cv::Mat rectifyImage;
        image_corners_est->undistort_image(image, rectifyImage);

        //image_corners_est->findCorners(image);
        printf(package_path.c_str());
        if(save_image_flag)
          cv::imwrite(package_path+"/process_data/"+camera_name+std::to_string(bag_idx)+".jpg", rectifyImage);

    }


    return 0;
}

图像提取标定板角点libcbdetect

激光提取标定板角点ilcc2

  • 运行程序
roslaunch ilcc2 lidar_corners.launch
  • 程序会弹出两个pcl_viewer,分别是visual_corners与visual_chessboard

  • 打开rviz ,更改Fixed Frame 并添加PointCloud2 (把topic改为volodyne_points)
    在这里插入图片描述

  • 选中rviz的Publish Point功能,在标定板点云的中间点一个点.之后在visual_chessboard界面会显示提取结果,提取结果用粉色点云表示.
    在这里插入图片描述

  • 若提取正确,按o键后,visual_corners界面会显示角点提取结果

  • 一共有两张标定板的图,一张是在激光原点,一张是在原始位置.其中在原始位置的标定板有粉色点,也就是激光角点.

  • 最终正确的结果如下图所示.粉色角点提取正确.按k键确认.

  • 循环操作完成其他的bag

标定激光与相机外参

  • 运行程序
roslaunch ilcc2 calib_lidar_cam.launch

在这里插入图片描述

  • 若初始外参设置正确,在lidar_camera_corners窗口中可以看到绿色相机角点与红色激光角点.该主要是为了确保lidar角点与相机角点的对应关系一致,只要红色点和绿色的排序方式一样即可(一般不会出问题,按任意键跳过即可).
    在这里插入图片描述

  • 标定好之后,会显示重投影结果(如上图所示).最终标定的结果会在终端输出,也会保存为bin文件存在config文件夹下.

激光投影回相机效果

roslaunch ilcc2 pcd2image.launch
rosbag play xxx.bag -l

在这里插入图片描述

  • 对应代码
#include <fstream>
#include <iostream>
#include <math.h>
#include <ros/package.h>        /// ros::package::getPath

#include <Eigen/Core>

#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>

#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/Image.h>

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>


#include <pcl_conversions/pcl_conversions.h>
#include <pcl/common/transforms.h>          /// pcl::transformPointCloud

#include "ilcc2/ImageCornersEst.h"

using namespace std;
using namespace message_filters;

ImageCornersEst::Ptr image_corners_est(new ImageCornersEst);

double distance_valid;


// void cv::undistort	
// (	InputArray 	src,                        // 原始图像
//         OutputArray 	dst,                        // 矫正图像
//         InputArray 	cameraMatrix,               // 原相机内参矩阵
//         InputArray 	distCoeffs,                 // 相机畸变参数
//         InputArray 	newCameraMatrix = noArray() // 新相机内参矩阵
// )	

void processData(cv::Mat image, pcl::PointCloud<pcl::PointXYZI>::Ptr cloud)  
{

  cv::Mat rectifyImage;       //矫正的图像
  cv::undistort(image, rectifyImage, image_corners_est->camK, image_corners_est->distort_param, image_corners_est->camK);

  pcl::PointXYZI ptmp;

  /// 生成每个点的颜色
  double inten_low=255, inten_high=0;    
  std::vector<double> datas;            
  for(unsigned int index=0; index<cloud->size(); index++)  //找深度的最大值和最小值
  {
      ptmp = cloud->points[index];
      if(inten_low > ptmp.intensity)
          inten_low = ptmp.intensity;
      if(inten_high < ptmp.intensity)
          inten_high = ptmp.intensity;
      datas.push_back(ptmp.intensity);
  }

  inten_low = 0;
  inten_high = 60;


//  std::cout<<"start project "<< cloud->size() << " ,  ";
  int counter = 0;
  for(unsigned int index=0; index<cloud->size(); index++)
  {

    ptmp = cloud->points[index];
    Eigen::Vector3d Pw(ptmp.x, ptmp.y, ptmp.z);
    Eigen::Vector2d Pcam;
       //转换平面
    if ( image_corners_est->spaceToPlane(Pw, Pcam, distance_valid) ) {

      int x = Pcam[0];
      int y = Pcam[1];

      unsigned char r, g, b;

      double h = (ptmp.intensity-inten_low)/(inten_high-inten_low)*255;  //对深度进行归一化

      image_corners_est->HSVtoRGB(h, 100, 100, &r, &g, &b);

      cv::circle(rectifyImage, cv::Point2d(x,y), 0.6, cv::Scalar(r,g,b), 2);
//      cv::circle(rectifyImage, cv::Point2d(x,y), 0.8, cv::Scalar(r,g,b), 0.8);
//      image.ptr<uchar>(y)[x*3] = 255;
//      image.ptr<uchar>(y)[x*3+1] = 0;
//      image.ptr<uchar>(y)[x*3+2] = 0;

      counter++;
    }
  }
//  std::cout << counter << " points ok\n";
  cv::resize(rectifyImage, rectifyImage, cv::Size(rectifyImage.cols/1, rectifyImage.rows/1));
  cv::imshow("img_liar_point", rectifyImage);  //矫正后的图像
  cv::waitKey(5);
}


void callback_LidarCam(const sensor_msgs::PointCloud2ConstPtr& msg_pc,
          const sensor_msgs::ImageConstPtr& msg_img)
{
//  ROS_INFO_STREAM("Velodyne scan received at " << msg_pc->header.stamp.toSec());
//  ROS_INFO_STREAM("image received at " << msg_img->header.stamp.toSec());
  pcl::PointCloud<pcl::PointXYZI> input_cloud;
  pcl::fromROSMsg(*msg_pc, input_cloud);                       //转换为模板点云fromROSMsg
  cv::Mat img = cv_bridge::toCvCopy(msg_img,"bgr8")->image;    //image从ros转为opencv常用格式
  processData(img, input_cloud.makeShared());
}



int main(int argc, char** argv){

  ros::init(argc,argv,"pcd2image");
  ros::NodeHandle nh;
  std::string package_path = ros::package::getPath("ilcc2");
  ROS_INFO("ilcc2 package at %s", package_path.c_str());


  std::string yaml_path, image_topic, lidar_topic;
  std::string extrinsic_file;
  ros::NodeHandle nh_private("~");

  nh_private.param<double>("distance_valid", distance_valid, 5);
  nh_private.param<std::string>("extrinsic_file", extrinsic_file, "/process_data/pose.bin");
  nh_private.param<std::string>("yaml_path", yaml_path, "30w.yaml");
  nh_private.param<std::string>("image_topic", image_topic, "/front");
  nh_private.param<std::string>("lidar_topic", lidar_topic, "/velodyne_points");


  std::string extrinsic_path = package_path + extrinsic_file;             //外参路径
  ROS_INFO("load T_lidar2cam from %s", extrinsic_path.c_str());             

  image_corners_est = ImageCornersEst::Ptr(new ImageCornersEst(package_path+"/config/"+yaml_path, true) ); //内参路径
  image_corners_est->txt2extrinsic( extrinsic_path );

  message_filters::Subscriber<sensor_msgs::PointCloud2> cloud_sub(nh, lidar_topic, 2);      //点云接收
  message_filters::Subscriber<sensor_msgs::Image> image_sub(nh, image_topic, 2);            // 图像接收

  typedef sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> MySyncPolicy;   //时间戳同步
  Synchronizer<MySyncPolicy> sync(MySyncPolicy(2), cloud_sub, image_sub);
  sync.registerCallback(boost::bind(&callback_LidarCam, _1, _2));                                  //回调函数
  ROS_INFO("waiting for lidar image topic %s %s", lidar_topic.c_str(), image_topic.c_str());       


  while (ros::ok())
  {
    ros::spin();
  }
}




  • 0
    点赞
  • 18
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
### 回答1: 这个问题翻译成中文是:b'lidar_imu_calib标定过程'。 回答:lidar_imu_calib是指激光雷达和惯性测量单元(IMU)之间的标定过程,通过该过程可以解决激光雷达和IMU在安装中的相对姿态和时间同步问题。该过程需要收集一些基准数据,例如IMU的加速度计和陀螺仪数据,以及激光雷达的点云数据。然后将这些数据引入标定算法中,得到激光雷达和IMU之间的相对位姿和时间偏差,最后将它们纠正并同步,从而使系统达到更高的精度。 ### 回答2: Lidar_imu_calib是一种激光雷达和惯性测量单元的联合标定方法。它旨在从激光雷达的数据和惯性传感器的数据中获取相机、激光雷达和车辆的位姿(即位置和姿态)信息。 lidar_imu_calib标定过程可以分为以下几步: 1.采集数据:首先需要采集车辆在各种不同的姿态和运动条件下的数据,包括车速变化、车辆俯仰和横滚角变化等。同时,需要记录激光雷达和惯性传感器的输出数据。 2.匹配点云和IMU数据:利用系统时间戳进行点云数据和IMU数据的对齐,通过坐标系变换将两者的数据进行匹配。 3.计算位姿:根据匹配后的数据,计算车辆的位姿,包括车辆位置和姿态(即旋转角度),这是通过解决非线性优化问题来完成的。 4.评估误差:标定结果需要进行评估,通过比较计算出的车辆真实姿态和标定结果之间的差异来确定标定的准确性。 5.优化标定结果:根据评估结果进行标定结果的优化,即根据误差来调整标定结果,以提高标定准确性。 总之,lidar_imu_calib标定是激光雷达与惯性测量单元联合标定的方法,通过匹配点云和IMU数据,计算位姿,评估误差和优化标定结果等步骤,得到车辆的位姿信息,从而提高自动驾驶车辆的安全性和性能。 ### 回答3: Lidar_imu_calib是一种遥感设备,由激光雷达和惯性测量单元(IMU)组成,它的目的是3D空间中的可视化地图构建。Lidar可以测量环境中物体的位置和形状,而IMU可以测量设备的位置和运动状态。因此,Lidar_imu_calib的精度和准确性对于它的应用非常重要。为此,在使用Lidar_imu_calib之前,必须进行标定。 Lidar_imu_calib标定过程试图确定几何和姿态转换矩阵,这个矩阵用于将Lidar和IMU测量结果在同一个坐标系下进行配置。其中,几何变换矩阵被用来纠正从Lidar和IMU获得的点云数据中发生的误差,姿态变换矩阵则用于纠正导致视角变化的角度问题。 标定过程的首要步骤是采集数据,包括Lidar和IMU的原始数据以及因为设备不同而引起的差异。通过在一定时间内在多个场景下对数据进行采集,可以获得更加丰富的数据,并确保标定能够在多种条件下表示准确。 数据采集之后,接下来需要进行数据处理。主要是通过使用非线性最小二乘法以最小化两个矩阵的几何和姿态误差。 这个过程需要大量的计算能力和优秀的算法以最大化标定的准确度。最终的标定参数是由几何和姿态矩阵的组合产生的,并被应用到Lidar_imu_calib设备以及期望的应用程序中。 总之,Lidar_imu_calib标定是一项复杂的过程,它需要充分的数据采集、数据处理和优秀的算法来确保标定结果的准确性和精度。
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值