Skip to content

Commit 28c6ac4

Browse files
committed
basic depth_image_proc unit test of a camera situated behind the depth camera, next try a camera at an angle to the depth points next
1 parent 4b8c45f commit 28c6ac4

File tree

6 files changed

+441
-3
lines changed

6 files changed

+441
-3
lines changed

depth_image_proc/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,3 +54,10 @@ install(TARGETS ${PROJECT_NAME}
5454
install(FILES nodelet_plugins.xml
5555
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
5656
)
57+
58+
if(CATKIN_ENABLE_TESTING)
59+
find_package(rostest REQUIRED)
60+
61+
add_rostest(test/test_register.test
62+
DEPENDENCIES ${${PROJECT_NAME}_EXPORTED_TARGETS})
63+
endif()

depth_image_proc/package.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,4 +45,7 @@
4545
<run_depend>tf2</run_depend>
4646
<run_depend>tf2_ros</run_depend>
4747
<run_depend>sensor_msgs</run_depend>
48+
49+
<test_depend>rostest</test_depend>
50+
<test_depend>tf</test_depend>
4851
</package>

depth_image_proc/src/nodelets/register.cpp

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -247,9 +247,6 @@ bool transform_depth(
247247
return true;
248248
}
249249

250-
// TODO(lucasw) need a unit test for this, simple low res image (e.g. 4x4 pixels) with
251-
// depth ranges of around 1.0
252-
// shift it to the right 1.0 units, view from 90 degrees
253250
template<typename T>
254251
void RegisterNodelet::convert(const sensor_msgs::ImageConstPtr& depth_msg,
255252
const sensor_msgs::ImagePtr& registered_msg,
Lines changed: 120 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
#!/usr/bin/env python
2+
3+
import copy
4+
import unittest
5+
6+
import numpy as np
7+
import rospy
8+
import rostest
9+
from cv_bridge import CvBridge
10+
from sensor_msgs.msg import CameraInfo
11+
from sensor_msgs.msg import Image
12+
13+
14+
class TestRegister(unittest.TestCase):
15+
def test_register(self):
16+
# publish a 2x2 float depth image with depths like
17+
# [1.0, 2.0], [2.0, 1.0]
18+
# publish a camera info with a aov of around 90 degrees
19+
# publish two static tfs in the .test file, one shifted
20+
# by 1.0 in x from the depth camera_info frame
21+
# another by 2.0 in x, and 1.5 in z, with a 90 degree rotation
22+
# looking back at those depth points
23+
# publish another camera info, in series, have it shift from one frame to the other
24+
# subscribe to the depth_image_proc node and verify output
25+
# (make numbers come out even with 90 degree aov)
26+
27+
self.output_depth = rospy.get_param("~output_depth", 1.0)
28+
self.expected_depth = rospy.get_param("~expected_depth", 7.0)
29+
rospy.loginfo(f"published depth: {self.output_depth}, expected input depth: {self.expected_depth}")
30+
31+
self.cv_bridge = CvBridge()
32+
self.depth_image_pub = rospy.Publisher("depth/image_rect", Image, queue_size=2)
33+
self.depth_ci_pub = rospy.Publisher("depth/camera_info", CameraInfo, queue_size=2)
34+
self.rgb_ci_pub = rospy.Publisher("rgb/camera_info", CameraInfo, queue_size=2)
35+
36+
self.received_msg = None
37+
38+
# TODO(lucasw) use time sync subscriber
39+
self.depth_sub = rospy.Subscriber("depth_registered/image_rect", Image, self.depth_callback, queue_size=2)
40+
self.ci_sub = rospy.Subscriber("depth_registered/camera_info", CameraInfo, self.ci_callback, queue_size=2)
41+
42+
ci_msg = CameraInfo()
43+
wd = 3
44+
ht = 3
45+
ci_msg.header.frame_id = "station1"
46+
ci_msg.height = ht
47+
ci_msg.width = wd
48+
ci_msg.distortion_model = "plumb_bob"
49+
50+
cx = 1.5
51+
cy = 1.5
52+
fx = 1.5
53+
fy = 1.5
54+
ci_msg.K = [fx, 0.0, cx,
55+
0.0, fy, cy,
56+
0.0, 0.0, 1.0]
57+
ci_msg.R = [1, 0, 0,
58+
0, 1, 0,
59+
0, 0, 1]
60+
ci_msg.P = [fx, 0.0, cx, 0.0,
61+
0.0, fy, cy, 0.0,
62+
0.0, 0.0, 1.0, 0.0]
63+
64+
depth = np.ones((ht, wd, 1), np.float32) * self.output_depth
65+
rospy.loginfo(depth)
66+
67+
depth_msg = self.cv_bridge.cv2_to_imgmsg(depth, "32FC1")
68+
ci_msg.header.stamp = rospy.Time.now()
69+
rgb_ci_msg = copy.deepcopy(ci_msg)
70+
rgb_ci_msg.header.frame_id = "station2"
71+
depth_msg.header = ci_msg.header
72+
73+
for i in range(6):
74+
rospy.loginfo(f"{i} waiting for register connections...")
75+
num_im_sub = self.depth_image_pub.get_num_connections()
76+
num_ci_sub = self.depth_ci_pub.get_num_connections()
77+
num_rgb_ci_sub = self.rgb_ci_pub.get_num_connections()
78+
rospy.sleep(1)
79+
if num_im_sub > 0 and num_ci_sub > 0 and num_rgb_ci_sub > 0:
80+
break
81+
82+
self.assertGreater(self.depth_image_pub.get_num_connections(), 0)
83+
self.assertGreater(self.depth_ci_pub.get_num_connections(), 0)
84+
self.assertGreater(self.rgb_ci_pub.get_num_connections(), 0)
85+
rospy.sleep(1.0)
86+
87+
self.count = 0
88+
rospy.loginfo("publishing depth and ci, wait for callbacks")
89+
for i in range(4):
90+
self.depth_image_pub.publish(depth_msg)
91+
self.depth_ci_pub.publish(ci_msg)
92+
self.rgb_ci_pub.publish(rgb_ci_msg)
93+
rospy.sleep(0.1)
94+
95+
while i in range(6):
96+
if self.count > 1:
97+
break
98+
rospy.sleep(1)
99+
rospy.loginfo("done waiting")
100+
101+
self.assertIsNotNone(self.received_msg, "no depth message received")
102+
registered_depth = self.cv_bridge.imgmsg_to_cv2(self.received_msg, "32FC1")
103+
# the edges of the expected 3x3 image may be nans, but the center should be valid
104+
valid_depth = registered_depth[1, 1]
105+
self.assertAlmostEqual(valid_depth, self.expected_depth, places=1)
106+
107+
def depth_callback(self, msg):
108+
rospy.loginfo("received depth")
109+
self.received_msg = msg
110+
self.count += 1
111+
112+
def ci_callback(self, msg):
113+
rospy.logdebug("received camera info")
114+
115+
116+
if __name__ == "__main__":
117+
node_name = 'test_register'
118+
rospy.init_node(node_name)
119+
# rostest.rosrun("depth_image_proc", node_name, sys.argv)
120+
rostest.rosrun("depth_image_proc", node_name, TestRegister)

0 commit comments

Comments
 (0)