52                                    sensor_msgs::CameraInfoConstPtr camera_info_msg)
 
   54   if (!depth_msg || !camera_info_msg)
 
   59   std::size_t width = depth_msg->width;
 
   60   std::size_t height = depth_msg->height;
 
   71     float center_x = camera_info_msg->P[2] - camera_info_msg->roi.x_offset;
 
   72     float center_y = camera_info_msg->P[6] - camera_info_msg->roi.y_offset;
 
   75     double scale_x = camera_info_msg->binning_x > 1 ? (1.0 / camera_info_msg->binning_x) : 1.0;
 
   76     double scale_y = camera_info_msg->binning_y > 1 ? (1.0 / camera_info_msg->binning_y) : 1.0;
 
   78     double fx = camera_info_msg->P[0] * scale_x;
 
   79     double fy = camera_info_msg->P[5] * scale_y;
 
   81     float constant_x = 1.0f / fx;
 
   82     float constant_y = 1.0f / fy;
 
   90     for (
int v = 0; v < height; ++v, ++projY)
 
   91       *projY = (v - center_y) * constant_y;
 
   93     for (
int u = 0; u < width; ++u, ++projX)
 
   94       *projX = (u - center_x) * constant_x;