void K4ACalibrationTransformData::initialize()

in src/k4a_calibration_transform_data.cpp [37:77]


void K4ACalibrationTransformData::initialize(const K4AROSDeviceParams params)
{
  k4a_transformation_ = k4a::transformation(k4a_calibration_);
  tf_prefix_ = params.tf_prefix;

  print();

  bool depthEnabled = (getDepthWidth() * getDepthHeight() > 0);
  bool colorEnabled = (getColorWidth() * getColorHeight() > 0);

  // Create a buffer to store the point cloud
  if (params.point_cloud && (!params.rgb_point_cloud || params.point_cloud_in_depth_frame))
  {
    point_cloud_image_ = k4a::image::create(K4A_IMAGE_FORMAT_DEPTH16, getDepthWidth(), getDepthHeight(),
                                            getDepthWidth() * 3 * (int) sizeof(DepthPixel));
  }
  else if (params.point_cloud && params.rgb_point_cloud)
  {
    point_cloud_image_ = k4a::image::create(K4A_IMAGE_FORMAT_DEPTH16, getColorWidth(), getColorHeight(),
                                            getColorWidth() * 3 * (int) sizeof(DepthPixel));
  }

  if (depthEnabled && colorEnabled)
  {
    // Create a buffer to store RGB images that are transformed into the depth camera geometry
    transformed_rgb_image_ = k4a::image::create(K4A_IMAGE_FORMAT_COLOR_BGRA32, getDepthWidth(), getDepthHeight(),
                                                getDepthWidth() * (int) sizeof(BgraPixel));

    // Create a buffer to store depth images that are transformed into the RGB camera geometry
    transformed_depth_image_ = k4a::image::create(K4A_IMAGE_FORMAT_DEPTH16, getColorWidth(), getColorHeight(),
                                                  getColorWidth() * (int) sizeof(DepthPixel));
  }

  // Publish various transforms needed by ROS.
  // We publish all TFs all the time, even if the respective sensor data
  // output is off. This allows us to just use the SDK calibrations, and one
  // cosmetic TF output between the depth and the base.
  publishDepthToBaseTf();
  publishImuToDepthTf();
  publishRgbToDepthTf();
}