in src/k4a_ros_device.cpp [538:569]
k4a_result_t K4AROSDevice::getRbgFrame(const k4a::capture& capture, sensor_msgs::ImagePtr& rgb_image,
bool rectified = false)
{
k4a::image k4a_bgra_frame = capture.get_color_image();
if (!k4a_bgra_frame)
{
ROS_ERROR("Cannot render BGRA frame: no frame");
return K4A_RESULT_FAILED;
}
size_t color_image_size =
static_cast<size_t>(k4a_bgra_frame.get_width_pixels() * k4a_bgra_frame.get_height_pixels()) * sizeof(BgraPixel);
if (k4a_bgra_frame.get_size() != color_image_size)
{
ROS_WARN("Invalid k4a_bgra_frame returned from K4A");
return K4A_RESULT_FAILED;
}
if (rectified)
{
k4a::image k4a_depth_frame = capture.get_depth_image();
calibration_data_.k4a_transformation_.color_image_to_depth_camera(k4a_depth_frame, k4a_bgra_frame,
&calibration_data_.transformed_rgb_image_);
return renderBGRA32ToROS(rgb_image, calibration_data_.transformed_rgb_image_);
}
return renderBGRA32ToROS(rgb_image, k4a_bgra_frame);
}