rgbd
image_gtest.cpp
Go to the documentation of this file.
1 #include "test_utils.h"
2 
3 #include <gtest/gtest.h>
4 
5 #include <opencv2/core/mat.hpp>
6 
7 #include <rgbd/image.h>
8 
9 #include <sensor_msgs/CameraInfo.h>
10 
11 
12 TEST(Image, EmptyClone)
13 {
14  rgbd::Image image1;
15  rgbd::Image image2 = image1.clone();
16 
17  EXPECT_EQ(image1, image2);
18  EXPECT_FALSE(image1 != image2);
19 }
20 
21 TEST(Image, RandomClone)
22 {
24  rgbd::Image image2 = image1.clone();
25 
26  EXPECT_EQ(image1, image2);
27  EXPECT_FALSE(image1 != image2);
28 }
29 
30 TEST(Image, NotEqual)
31 {
34 
35  // Two random images
36  EXPECT_FALSE(image1 == image2);
37  EXPECT_NE(image1, image2);
38 
39  // Different frame_id
40  image2 = image1.clone();
41  image2.setFrameId("bla");
42  EXPECT_FALSE(image1 == image2);
43  EXPECT_NE(image1, image2);
44 
45  // Different timestamp
46  image2 = image1.clone();
47  image2.setTimestamp(image1.getTimestamp()+10.);
48  EXPECT_FALSE(image1 == image2);
49  EXPECT_NE(image1, image2);
50 
51  // Different camera model
52  image2 = image1.clone();
53  sensor_msgs::CameraInfo cam_info = image2.getCameraModel().cameraInfo();
54  cam_info.width += 10;
55  image2.setCameraInfo(cam_info);
56  EXPECT_FALSE(image1 == image2);
57  EXPECT_NE(image1, image2);
58 
59  // Different depth image
60  image2 = image1.clone();
61  cv::Mat depth = image2.getDepthImage();
62  depth.at<float>(0, 0) += 0.1;
63  image2.setDepthImage(depth);
64  EXPECT_FALSE(image1 == image2);
65  EXPECT_NE(image1, image2);
66 
67  // Different RGB color image
68  image2 = image1.clone();
69  cv::Mat color = image2.getRGBImage();
70  color.at<cv::Vec3b>(0, 0) *= 2;
71  image2.setRGBImage(color);
72  EXPECT_FALSE(image1 == image2);
73  EXPECT_NE(image1, image2);
74 }
75 
76 // Run all the tests that were declared with TEST()
77 int main(int argc, char **argv)
78 {
79  testing::InitGoogleTest(&argc, argv);
80  return RUN_ALL_TESTS();
81 }
TEST
TEST(Image, EmptyClone)
Definition: image_gtest.cpp:12
rgbd::Image::getDepthImage
const cv::Mat & getDepthImage() const
Get the depth image.
Definition: image.h:72
test_utils.h
rgbd::Image::getTimestamp
double getTimestamp() const
Get the timestamp.
Definition: image.h:90
rgbd::Image::setDepthImage
void setDepthImage(const cv::Mat &depth_image)
Set the depth image.
Definition: image.h:105
rgbd::Image::setFrameId
void setFrameId(const std::string &frame_id)
Set the frame_id.
Definition: image.h:117
rgbd::Image::setRGBImage
void setRGBImage(const cv::Mat &rgb_image)
Set the BGR color image.
Definition: image.h:111
rgbd::Image
Definition: image.h:43
rgbd::Image::setTimestamp
void setTimestamp(double timestamp)
Set the timestamp.
Definition: image.h:123
image.h
rgbd::Image::getRGBImage
const cv::Mat & getRGBImage() const
Get the RGB color image.
Definition: image.h:78
main
int main(int argc, char **argv)
Definition: image_gtest.cpp:77
rgbd::Image::clone
Image clone() const
Create a clone of this image. The depth and RGB images will be cloned, so the new image will not shar...
Definition: image.cpp:56
rgbd::Image::getCameraModel
const image_geometry::PinholeCameraModel & getCameraModel() const
Get the camera model.
Definition: image.h:96
rgbd::Image::setCameraInfo
void setCameraInfo(sensor_msgs::CameraInfo cam_info)
Set the camera model by using a camera info message. The frame_id and timestamp of the message will b...
Definition: image.cpp:34
rgbd::generateRandomImage
rgbd::Image generateRandomImage()
Definition: test_utils.h:36