Skip to content

Commit b3513b4

Browse files
Make RenderResult variables protected (#56)
2 parents c9755a8 + 9a27209 commit b3513b4

File tree

1 file changed

+13
-13
lines changed

1 file changed

+13
-13
lines changed

ed_sensor_integration/src/kinect/renderer.cpp

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -17,29 +17,28 @@ class SampleRenderResult : public geo::RenderResult
1717

1818
public:
1919

20-
SampleRenderResult(cv::Mat& z_buffer_, std::vector<unsigned int>& pixels_)
21-
: geo::RenderResult(z_buffer_.cols, z_buffer_.rows), z_buffer(z_buffer_), num_pixels(0), pixels(pixels_)
20+
SampleRenderResult(cv::Mat& z_buffer, std::vector<unsigned int>& pixels)
21+
: geo::RenderResult(z_buffer.cols, z_buffer.rows), z_buffer_(z_buffer), pixels_(pixels)
2222
{
2323
}
2424

2525
void renderPixel(int x, int y, float depth, int i_triangle)
2626
{
27-
float old_depth = z_buffer.at<float>(y, x);
27+
float old_depth = z_buffer_.at<float>(y, x);
2828
if (old_depth == 0)
2929
{
30-
z_buffer.at<float>(y, x) = depth;
31-
pixels[num_pixels] = y * z_buffer.cols + x;
32-
++num_pixels;
30+
z_buffer_.at<float>(y, x) = depth;
31+
pixels_.push_back(y * z_buffer_.cols + x);
3332
}
3433
else if (depth < old_depth)
3534
{
36-
z_buffer.at<float>(y, x) = depth;
35+
z_buffer_.at<float>(y, x) = depth;
3736
}
3837
}
3938

40-
cv::Mat& z_buffer;
41-
unsigned int num_pixels;
42-
std::vector<unsigned int>& pixels;
39+
protected:
40+
cv::Mat& z_buffer_; // Depth image
41+
std::vector<unsigned int>& pixels_; // Maps index of occupied pixels to actual pixel position
4342

4443
};
4544

@@ -57,7 +56,8 @@ void fitZRP(const geo::Shape& shape, const geo::Pose3D& shape_pose, const rgbd::
5756
unsigned int width = view.getWidth();
5857
unsigned int height = view.getHeight();
5958

60-
std::vector<unsigned int> pixels(width * height);
59+
std::vector<unsigned int> pixels;
60+
pixels.reserve(width * height);
6161

6262
// Create a resized version of the sensor depth image
6363
cv::Mat sensor_depth_img(height, width, CV_32FC1, 0.0);
@@ -94,9 +94,9 @@ void fitZRP(const geo::Shape& shape, const geo::Pose3D& shape_pose, const rgbd::
9494

9595
int n = 0;
9696
double total_error = 0;
97-
for(unsigned int i = 0; i < res.num_pixels; ++i)
97+
for(std::vector<unsigned int>::const_iterator it = pixels.cbegin(); it != pixels.cend(); ++it)
9898
{
99-
unsigned int p_idx = res.pixels[i];
99+
unsigned int p_idx = *it;
100100

101101
float ds = sensor_depth_img.at<float>(p_idx);
102102

0 commit comments

Comments
 (0)