rgbd_topics.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  Copyright (c) 2016, Intel Corporation
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without
6  modification, are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software without
17  specific prior written permission.
18 
19  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *******************************************************************************/
30 
31 #include "rgbd_topics.h" // NOLINT(build/include)
32 
33 void topic0Callback(const sensor_msgs::ImageConstPtr msg)
34 {
35  if ((msg->height != 0) && (msg->width != 0))
36  {
37  topic_0_recv = true;
38  }
39 }
40 
41 void topic1Callback(const sensor_msgs::ImageConstPtr msg)
42 {
43  if ((msg->height != 0) && (msg->width != 0))
44  {
45  topic_1_recv = true;
46  }
47 }
48 
49 void topic2Callback(const sensor_msgs::ImageConstPtr msg)
50 {
51  if ((msg->height != 0) && (msg->width != 0))
52  {
53  topic_2_recv = true;
54  }
55 }
56 
57 void topic3Callback(const sensor_msgs::ImageConstPtr msg)
58 {
59  if ((msg->height != 0) && (msg->width != 0))
60  {
61  topic_3_recv = true;
62  }
63 }
64 
65 void topic4Callback(const sensor_msgs::ImageConstPtr msg)
66 {
67  if ((msg->height != 0) && (msg->width != 0))
68  {
69  topic_4_recv = true;
70  }
71 }
72 
73 void topic5Callback(const sensor_msgs::ImageConstPtr msg)
74 {
75  if ((msg->height != 0) && (msg->width != 0))
76  {
77  topic_5_recv = true;
78  }
79 }
80 
81 void topic6Callback(const sensor_msgs::ImageConstPtr msg)
82 {
83  if ((msg->height != 0) && (msg->width != 0))
84  {
85  topic_6_recv = true;
86  }
87 }
88 
89 void topic7Callback(const sensor_msgs::PointCloud2ConstPtr msg)
90 {
91  if ((msg->height != 0) && (msg->width != 0))
92  {
93  topic_7_recv = true;
94  }
95 }
96 
97 void topic8Callback(const sensor_msgs::ImageConstPtr msg)
98 {
99  if ((msg->height != 0) && (msg->width != 0))
100  {
101  topic_8_recv = true;
102  }
103 }
104 
105 void topic9Callback(const sensor_msgs::ImageConstPtr msg)
106 {
107  if ((msg->height != 0) && (msg->width != 0))
108  {
109  topic_9_recv = true;
110  }
111 }
112 
113 void topic10Callback(const sensor_msgs::CameraInfoConstPtr msg)
114 {
115  if ((msg->height != 0) && (msg->width != 0))
116  {
117  topic_10_recv = true;
118  }
119 }
120 
121 void topic11Callback(const sensor_msgs::PointCloud2ConstPtr msg)
122 {
123  if ((msg->height != 0) && (msg->width != 0))
124  {
125  topic_11_recv = true;
126  }
127 }
128 
129 void topic12Callback(const sensor_msgs::ImageConstPtr msg)
130 {
131  if ((msg->height != 0) && (msg->width != 0))
132  {
133  topic_12_recv = true;
134  }
135 }
136 
137 TEST(RealsenseTests, rgb_image_mono)
138 {
139  EXPECT_TRUE(topic_0_recv);
140 }
141 
142 TEST(RealsenseTests, rgb_image_color)
143 {
144  EXPECT_TRUE(topic_1_recv);
145 }
146 
147 TEST(RealsenseTests, rgb_image_rect_mono)
148 {
149  EXPECT_TRUE(topic_2_recv);
150 }
151 
152 TEST(RealsenseTests, rgb_image_rect_color)
153 {
154  EXPECT_TRUE(topic_3_recv);
155 }
156 
157 TEST(RealsenseTests, depth_image_rect_raw)
158 {
159  EXPECT_TRUE(topic_4_recv);
160 }
161 
162 TEST(RealsenseTests, depth_image_rect)
163 {
164  EXPECT_TRUE(topic_5_recv);
165 }
166 
167 TEST(RealsenseTests, depth_image)
168 {
169  EXPECT_TRUE(topic_6_recv);
170 }
171 
172 TEST(RealsenseTests, depth_points)
173 {
174  EXPECT_TRUE(topic_7_recv);
175 }
176 
177 TEST(RealsenseTests, ir_image_rect_ir)
178 {
179  EXPECT_TRUE(topic_8_recv);
180 }
181 
183 {
184  EXPECT_TRUE(topic_9_recv);
185 }
186 
188 {
189  EXPECT_TRUE(topic_10_recv);
190 }
191 
192 TEST(RealsenseTests, depth_reg_points)
193 {
194  EXPECT_TRUE(topic_11_recv);
195 }
196 
198 {
199  EXPECT_TRUE(topic_12_recv);
200 }
201 
202 void getParams()
203 {
204  ros::NodeHandle pnh;
205  pnh.param("camera", camera, CAMERA);
206  pnh.param("rgb", rgb, RGB);
207  pnh.param("depth", depth, DEPTH);
208  pnh.param("ir", ir, IR);
209  pnh.param("depth_registered", depth_registered, DEPTH_REGISTERED);
210 }
211 
212 void setTopics()
213 {
214  rgb_image_mono = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_MONO;
215  rgb_image_color = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_COLOR;
216  rgb_image_rect_mono = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_RECT_MONO;
217  rgb_image_rect_color = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_RECT_COLOR;
218  depth_image_rect_raw = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE_RECT_RAW;
219  depth_image_rect = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE_RECT;
220  depth_image = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE;
221  depth_points = "/" + camera + "/" + depth + "/" + DEPTH_POINTS;
222  ir_image_rect_ir = "/" + camera + "/" + ir + "/" + IR_IMAGE_RECT_IR;
227 }
228 
229 int main(int argc, char **argv) try
230 {
231  testing::InitGoogleTest(&argc, argv);
232  ros::init(argc, argv, "utest");
233 
234  ROS_INFO_STREAM("RealSense Camera - Starting rgbd_launch Tests...");
235 
236  ros::NodeHandle nh;
237  getParams();
238  setTopics();
239 
240  subscriber[0] = nh.subscribe<sensor_msgs::Image>(rgb_image_mono, 1, topic0Callback, 0);
241  subscriber[1] = nh.subscribe<sensor_msgs::Image>(rgb_image_color, 1, topic1Callback, 0);
242  subscriber[2] = nh.subscribe<sensor_msgs::Image>(rgb_image_rect_mono, 1, topic2Callback, 0);
243  subscriber[3] = nh.subscribe<sensor_msgs::Image>(rgb_image_rect_color, 1, topic3Callback, 0);
244  subscriber[4] = nh.subscribe<sensor_msgs::Image>(depth_image_rect_raw, 1, topic4Callback, 0);
245  subscriber[5] = nh.subscribe<sensor_msgs::Image>(depth_image_rect, 1, topic5Callback, 0);
246  subscriber[6] = nh.subscribe<sensor_msgs::Image>(depth_image, 1, topic6Callback, 0);
247  subscriber[7] = nh.subscribe<sensor_msgs::PointCloud2>(depth_points, 1, topic7Callback);
248  subscriber[8] = nh.subscribe<sensor_msgs::Image>(ir_image_rect_ir, 1, topic8Callback, 0);
249  subscriber[9] = nh.subscribe<sensor_msgs::Image>(depth_reg_sw_reg_image_rect_raw, 1, topic9Callback, 0);
250  subscriber[10] = nh.subscribe<sensor_msgs::CameraInfo>(depth_reg_sw_reg_camera_info, 1, topic10Callback);
251  subscriber[11] = nh.subscribe<sensor_msgs::PointCloud2>(depth_reg_points, 1, topic11Callback, 0);
252  subscriber[12] = nh.subscribe<sensor_msgs::Image>(depth_reg_sw_reg_image_rect, 1, topic12Callback, 0);
253 
254  ros::Duration duration;
255  duration.sec = 10;
256  duration.sleep();
257  ros::spinOnce();
258 
259  return RUN_ALL_TESTS();
260 }
261 catch(...) {} // catch the "testing::internal::<unnamed>::ClassUniqueToAlwaysTrue" from gtest
void topic12Callback(const sensor_msgs::ImageConstPtr msg)
void setTopics()
void topic5Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:73
std::string ir
Definition: rgbd_topics.h:69
void topic7Callback(const sensor_msgs::PointCloud2ConstPtr msg)
Definition: rgbd_topics.cpp:89
void topic6Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:81
std::string depth_reg_sw_reg_image_rect_raw
Definition: rgbd_topics.h:81
std::string DEPTH_REG_SW_REG_IMAGE_RECT
Definition: rgbd_topics.h:58
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string DEPTH_POINTS
Definition: rgbd_topics.h:53
void topic1Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:41
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
GLint GLint GLsizei GLsizei GLsizei depth
std::string depth_points
Definition: rgbd_topics.h:79
bool topic_6_recv
Definition: rgbd_topics.h:92
std::string depth_registered
Definition: rgbd_topics.h:70
std::string ir_image_rect_ir
Definition: rgbd_topics.h:80
std::string CAMERA
Definition: rgbd_topics.h:60
ros::Subscriber subscriber[TOPIC_COUNT]
Definition: rgbd_topics.h:100
bool topic_1_recv
Definition: rgbd_topics.h:87
void topic3Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:57
std::string DEPTH_REGISTERED
Definition: rgbd_topics.h:64
bool topic_2_recv
Definition: rgbd_topics.h:88
std::string depth_reg_sw_reg_image_rect
Definition: rgbd_topics.h:84
std::string IR
Definition: rgbd_topics.h:63
std::string DEPTH_REG_SW_REG_CAMERA_INFO
Definition: rgbd_topics.h:56
bool topic_11_recv
Definition: rgbd_topics.h:97
bool topic_5_recv
Definition: rgbd_topics.h:91
std::string depth_reg_points
Definition: rgbd_topics.h:83
std::string RGB_IMAGE_MONO
Definition: rgbd_topics.h:46
void topic10Callback(const sensor_msgs::CameraInfoConstPtr msg)
std::string DEPTH_IMAGE_RECT_RAW
Definition: rgbd_topics.h:50
std::string rgb_image_rect_mono
Definition: rgbd_topics.h:74
void topic11Callback(const sensor_msgs::PointCloud2ConstPtr msg)
std::string RGB_IMAGE_RECT_COLOR
Definition: rgbd_topics.h:49
std::string rgb
Definition: rgbd_topics.h:67
std::string depth_image_rect_raw
Definition: rgbd_topics.h:76
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void topic8Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:97
void topic9Callback(const sensor_msgs::ImageConstPtr msg)
bool topic_8_recv
Definition: rgbd_topics.h:94
std::string IR_IMAGE_RECT_IR
Definition: rgbd_topics.h:54
std::string RGB
Definition: rgbd_topics.h:61
std::string camera
Definition: rgbd_topics.h:66
void topic4Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:65
std::string DEPTH_IMAGE_RECT
Definition: rgbd_topics.h:51
bool topic_9_recv
Definition: rgbd_topics.h:95
void topic2Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:49
std::string depth_image
Definition: rgbd_topics.h:78
std::string DEPTH_REG_POINTS
Definition: rgbd_topics.h:57
bool topic_0_recv
Definition: rgbd_topics.h:86
bool topic_3_recv
Definition: rgbd_topics.h:89
#define ROS_INFO_STREAM(args)
std::string rgb_image_color
Definition: rgbd_topics.h:73
std::string RGB_IMAGE_RECT_MONO
Definition: rgbd_topics.h:48
bool topic_12_recv
Definition: rgbd_topics.h:98
bool topic_7_recv
Definition: rgbd_topics.h:93
void getParams()
std::string DEPTH
Definition: rgbd_topics.h:62
std::string DEPTH_IMAGE
Definition: rgbd_topics.h:52
std::string depth_reg_sw_reg_camera_info
Definition: rgbd_topics.h:82
std::string depth_image_rect
Definition: rgbd_topics.h:77
bool topic_4_recv
Definition: rgbd_topics.h:90
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)
std::string RGB_IMAGE_COLOR
Definition: rgbd_topics.h:47
std::string rgb_image_rect_color
Definition: rgbd_topics.h:75
void topic0Callback(const sensor_msgs::ImageConstPtr msg)
Definition: rgbd_topics.cpp:33
std::string rgb_image_mono
Definition: rgbd_topics.h:72
std::string DEPTH_REG_SW_REG_IMAGE_RECT_RAW
Definition: rgbd_topics.h:55
TEST(RealsenseTests, rgb_image_mono)
bool topic_10_recv
Definition: rgbd_topics.h:96


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37