ROS2 / 无人机 / 深度相机 / 遥感 · 2025年 12月 15日 0

便宜深度相机启用带光学色彩的深度点云(enable_colored_point_cloud)

淘宝一千的orbbec深度相机,实则是并非orbbec的别家做的,只能适配奥比中光比较老的sdk或ros2仓库,ROS2适配的代码:https://github.com/orbbec/ros2_astra_camera

launch文件里面:

带色彩的点云默认没有开启,就算改true再编译,启动后虽然有对应话题了但到rviz2里一看还是空的,控制台会报告深度与光学尺寸不匹配的错,确实一个640*480一个640*400。然而pyorbbecsdk里都有深度图和色彩图一起输出的示例而且匹配得没啥问题无非不是整幅都有深度,肯定是能校正的。找到用来输出这种点云的源代码,point_cloud_xyzrgb.cpp中的一段:

  // Check if the input image has to be resized
  Image::ConstSharedPtr rgb_msg = rgb_msg_in;
  if (depth_msg->width != rgb_msg->width || depth_msg->height != rgb_msg->height) {
    CameraInfo info_msg_tmp = *info_msg;
    info_msg_tmp.width = depth_msg->width;
    info_msg_tmp.height = depth_msg->height;
    float ratio = static_cast<float>(depth_msg->width) / static_cast<float>(rgb_msg->width);
    info_msg_tmp.k[0] *= ratio;
    info_msg_tmp.k[2] *= ratio;
    info_msg_tmp.k[4] *= ratio;
    info_msg_tmp.k[5] *= ratio;
    info_msg_tmp.p[0] *= ratio;
    info_msg_tmp.p[2] *= ratio;
    info_msg_tmp.p[5] *= ratio;
    info_msg_tmp.p[6] *= ratio;
    model_.fromCameraInfo(info_msg_tmp);

    cv_bridge::CvImageConstPtr cv_ptr;
    try {
      cv_ptr = cv_bridge::toCvShare(rgb_msg, rgb_msg->encoding);
    } catch (cv_bridge::Exception& e) {
      RCLCPP_ERROR(logger_, "cv_bridge exception: %s", e.what());
      return;
    }
    cv_bridge::CvImage cv_rsz;
    cv_rsz.header = cv_ptr->header;
    cv_rsz.encoding = cv_ptr->encoding;
    // FIXME:
    int end_raw = std::min<int>(depth_msg->height / ratio, rgb_msg->height);
    cv::resize(cv_ptr->image.rowRange(0, end_raw), cv_rsz.image,
               cv::Size(depth_msg->width, depth_msg->height));
    if ((rgb_msg->encoding == enc::RGB8) || (rgb_msg->encoding == enc::BGR8) ||
        (rgb_msg->encoding == enc::MONO8)) {
      rgb_msg = cv_rsz.toImageMsg();
    } else {
      rgb_msg = cv_bridge::toCvCopy(cv_rsz.toImageMsg(), enc::RGB8)->toImageMsg();
    }

    RCLCPP_ERROR_THROTTLE(logger_, *(node_->get_clock()), 50000,
                          "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)",
                          depth_msg->width, depth_msg->height, rgb_msg->width, rgb_msg->height);
    return;
  } else {
    rgb_msg = rgb_msg_in;
  }

破案了是两年前老仓库可能被弃用,赫然表着个FIXME。所以这段代码实际前面已经做了针对点云和色彩尺寸不匹配的resize等,但最后又直接加了个给ROS2报的ERROR,然后return。

抱着试一试的心态把报错改警告,return注视掉:

    RCLCPP_WARN_THROTTLE(logger_, *(node_->get_clock()), 50000,
                          "Depth resolution (%ux%u) does not match RGB resolution (%ux%u)",
                          depth_msg->width, depth_msg->height, rgb_msg->width, rgb_msg->height);
    //return;

编译完再启动,结果出来点云质量感觉挺好的嘛……

所以卖家为什么做个深度相机就拿来适配这种已经中途被放弃,改都没改完的仓库……好在确实能用,还是说真正的坑还在后头?