rgbd
view.h
Go to the documentation of this file.
1 #ifndef RGBD_VIEW_H_
2 #define RGBD_VIEW_H_
3 
4 #include <rgbd/image.h>
5 
6 #include <geolib/datatypes.h>
8 
9 namespace rgbd {
10 
11 class View {
12 
13 public:
14 
15  View(const Image& image, int width);
16 
17  inline const int& getWidth() const
18  {
19  return width_;
20  }
21 
22  inline const int& getHeight() const
23  {
24  return height_;
25  }
26 
27  inline const cv::Vec3b& getColor(int x, int y) const
28  {
29  return image_.getRGBImage().at<cv::Vec3b>(y * rgb_factor_, x * rgb_factor_);
30  }
31 
32  inline const float& getDepth(int x, int y) const
33  {
34  return image_.getDepthImage().at<float>(y * depth_factor_, x * depth_factor_);
35  }
36 
37  inline bool getPoint3D(int x, int y, geo::Vector3& p) const
38  {
39  float d = getDepth(x, y);
40  p = rasterizer_.project2Dto3D(x, y) * d;
41  return (d == d && d > 0);
42  }
43 
44  inline bool getPoint3DSafe(int x, int y, geo::Vector3& p) const
45  {
46  if (x < 0 || y < 0 || x >= width_ || y >= height_)
47  return false;
48 
49  float d = getDepth(x, y);
50  p = rasterizer_.project2Dto3D(x, y) * d;
51  return (d == d && d > 0);
52  }
53 
54  inline const geo::DepthCamera& getRasterizer() const { return rasterizer_; }
55 
56 protected:
57  const Image& image_;
58  int width_;
59  int height_;
60 
61  float rgb_factor_;
63 
65 
66 };
67 
68 }
69 
70 #endif // RGBD_VIEW_H_
datatypes.h
rgbd::Image::getDepthImage
const cv::Mat & getDepthImage() const
Get the depth image.
Definition: image.h:72
DepthCamera.h
rgbd::View::getPoint3DSafe
bool getPoint3DSafe(int x, int y, geo::Vector3 &p) const
Definition: view.h:44
rgbd::View::getWidth
const int & getWidth() const
Definition: view.h:17
rgbd::View::height_
int height_
Definition: view.h:59
rgbd::View::rgb_factor_
float rgb_factor_
Definition: view.h:61
rgbd::View::getDepth
const float & getDepth(int x, int y) const
Definition: view.h:32
rgbd::Image
Definition: image.h:43
rgbd::View::getRasterizer
const geo::DepthCamera & getRasterizer() const
Definition: view.h:54
rgbd::View::getHeight
const int & getHeight() const
Definition: view.h:22
rgbd
Definition: client.h:24
rgbd::View::getPoint3D
bool getPoint3D(int x, int y, geo::Vector3 &p) const
Definition: view.h:37
image.h
rgbd::Image::getRGBImage
const cv::Mat & getRGBImage() const
Get the RGB color image.
Definition: image.h:78
geo::Vector3
geo::DepthCamera::project2Dto3D
geo::Vec3T< T > project2Dto3D(int x, int y) const
rgbd::View::depth_factor_
float depth_factor_
Definition: view.h:62
rgbd::View::width_
int width_
Definition: view.h:58
geo::DepthCamera
rgbd::View::rasterizer_
geo::DepthCamera rasterizer_
Definition: view.h:64
rgbd::View::image_
const Image & image_
Definition: view.h:57
rgbd::View::View
View(const Image &image, int width)
Definition: src/view.cpp:10
rgbd::View::getColor
const cv::Vec3b & getColor(int x, int y) const
Definition: view.h:27
rgbd::View
Definition: view.h:11