rgbd
src/view.cpp
Go to the documentation of this file.
1 #include "rgbd/view.h"
2 
3 #include <image_geometry/pinhole_camera_model.h>
4 #include <opencv2/core/mat.hpp>
5 
6 namespace rgbd {
7 
8 // ----------------------------------------------------------------------------------------
9 
10 View::View(const Image& image, int width) :
11  image_(image), width_(width)
12 {
13  const cv::Mat& rgb_image = image.getRGBImage();
14  const cv::Mat& depth_image = image.getDepthImage();
15  // Determine scaling between rgb and depth
16  float aspect_ratio = static_cast<float>(depth_image.cols) / static_cast<float>(depth_image.rows); // 640 / 480
17  height_ = static_cast<int>(width_ / aspect_ratio);
18 
19  // Factors
20  rgb_factor_ = static_cast<float>(rgb_image.cols) / static_cast<float>(width_);
21  depth_factor_ = static_cast<float>(depth_image.cols) / static_cast<float>(width_);
22 
24 }
25 
26 }
rgbd::Image::getDepthImage
const cv::Mat & getDepthImage() const
Get the depth image.
Definition: image.h:72
rgb_image
cv::Mat rgb_image
Definition: record_to_video.cpp:24
rgbd::View::height_
int height_
Definition: view.h:59
rgbd::View::rgb_factor_
float rgb_factor_
Definition: view.h:61
geo::DepthCamera::initFromCamModel
void initFromCamModel(const image_geometry::PinholeCameraModel &cam_model)
rgbd::Image
Definition: image.h:43
rgbd
Definition: client.h:24
rgbd::Image::getRGBImage
const cv::Mat & getRGBImage() const
Get the RGB color image.
Definition: image.h:78
rgbd::View::depth_factor_
float depth_factor_
Definition: view.h:62
rgbd::View::width_
int width_
Definition: view.h:58
rgbd::Image::getCameraModel
const image_geometry::PinholeCameraModel & getCameraModel() const
Get the camera model.
Definition: image.h:96
view.h
rgbd::View::rasterizer_
geo::DepthCamera rasterizer_
Definition: view.h:64
rgbd::View::View
View(const Image &image, int width)
Definition: src/view.cpp:10