test_camera.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- python -*-
3 
4 #
5 # Copyright (C) 2018 ifm electronic, gmbh
6 #
7 # Licensed under the Apache License, Version 2.0 (the "License");
8 # you may not use this file except in compliance with the License.
9 # You may obtain a copy of the License at
10 #
11 # http://www.apache.org/licenses/LICENSE-2.0
12 #
13 # Unless required by applicable law or agreed to in writing, software
14 # distributed under the License is distribted on an "AS IS" BASIS,
15 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16 # See the License for the specific language governing permissions and
17 # limitations under the License.
18 #
19 
20 import sys
21 import time
22 import unittest
23 import rospy
24 import rostest
25 import numpy as np
26 import tf2_ros
27 import tf2_geometry_msgs
28 from sensor_msgs.msg import Image
29 from geometry_msgs.msg import PointStamped
30 from cv_bridge import CvBridge, CvBridgeError
31 from ifm3d.msg import Extrinsics
32 
33 # XXX: TP debugging
34 #np.set_printoptions(threshold=np.nan)
35 
36 class TestCamera(unittest.TestCase):
37  """
38  TP: 14 May 2018 - heavily adapted from my old o3d3xx-ros test of the same
39  name.
40 
41  This class tests the following:
42  - Getting data from the camera
43  - Computing the Cartesian data and comparing it to ground truth
44  - To do the comparison to ground truth, the computed cartesian data
45  must be transformed, to do that we use the tf2 API. It follows that
46  this indirectly is testing our tf2 static publisher which is publishing
47  the transform between the optical and camera frames
48 
49  NOTE: The camera h/w is needed to run this test.
50  """
51 
52  def __init__(self, *args):
53  super(TestCamera, self).__init__(*args)
54  self.success_ = False
55 
56  self.cloud_ = None # ground truth for cartesian computation
57  self.rdis_ = None
58  self.uvec_ = None
59  self.extrinsics_ = None
60  self.conf_ = None
61 
62  def test_camera(self):
63  time.sleep(5.0) # <-- wait for rosmaster and ifm3d nodelet
64  rospy.init_node('test_camera')
65 
66  self.bridge_ = CvBridge()
67  self.rdis_sub_ = \
68  rospy.Subscriber("/ifm3d/camera/distance", Image, self.image_cb,
69  queue_size=None, callback_args="rdis")
70  self.cloud_sub_ = \
71  rospy.Subscriber("/ifm3d/camera/xyz_image", Image, self.image_cb,
72  queue_size=None, callback_args="cloud")
73  self.uvec_sub_ = \
74  rospy.Subscriber("/ifm3d/camera/unit_vectors", Image, self.image_cb,
75  queue_size=None, callback_args="uvec")
76  self.extrinsics_sub_ = \
77  rospy.Subscriber("/ifm3d/camera/extrinsics", Extrinsics,
78  self.extrinsics_cb, queue_size=None)
79  self.conf_sub_ = \
80  rospy.Subscriber("/ifm3d/camera/confidence", Image, self.image_cb,
81  queue_size=None, callback_args="conf")
82 
83  # If it takes more than 10 secs to run our test, something is wrong.
84  timeout_t = time.time() + 10.0
85  rate = rospy.Rate(10.0)
86  while ((not rospy.is_shutdown()) and
87  (not self.success_) and
88  (time.time() < timeout_t)):
89  # Make sure we have all the data we need to compute
90  if ((self.rdis_ is not None) and
91  (self.cloud_ is not None) and
92  (self.uvec_ is not None) and
93  (self.extrinsics_ is not None) and
94  (self.conf_ is not None)):
95 
96  # Make sure the cloud, conf, and rdis are from the same image
97  # acquisition.
98  d = self.rdis_.header.stamp - self.cloud_.header.stamp
99  if d.to_sec() == 0:
100  d2 = self.rdis_.header.stamp - self.conf_.header.stamp
101  if d2.to_sec() == 0:
102  self.success_ = self.compute_cartesian()
103  break
104  else:
105  # get new data
106  self.rdis_ = None
107  self.cloud_ = None
108  self.conf_ = None
109  else:
110  # get new data
111  self.rdis_ = None
112  self.cloud_ = None
113  self.conf_ = None
114 
115  rate.sleep()
116 
117  self.assertTrue(self.success_)
118 
119  def extrinsics_cb(self, data, *args):
120  if self.extrinsics_ is None:
121  self.extrinsics_ = data
122 
123  def image_cb(self, data, *args):
124  im_type = args[0]
125  if im_type == "rdis":
126  if self.rdis_ is None:
127  self.rdis_ = data
128  elif im_type == "cloud":
129  if self.cloud_ is None:
130  self.cloud_ = data
131  elif im_type == "uvec":
132  if self.uvec_ is None:
133  self.uvec_ = data
134  elif im_type == "conf":
135  if self.conf_ is None:
136  self.conf_ = data
137 
138  def compute_cartesian(self):
139  """
140  Computes the Cartesian data from the radial distance image, unit
141  vectors, and extrinsics. Then transforms it to the camera frame using
142  the tf2 api. Once transformed, it will do a pixel-by-pixel comparision
143  to ground truth.
144 
145  Returns a bool indicating the the success of the computation.
146  """
147  rdis = np.array(self.bridge_.imgmsg_to_cv2(self.rdis_))
148  uvec = np.array(self.bridge_.imgmsg_to_cv2(self.uvec_))
149  cloud = np.array(self.bridge_.imgmsg_to_cv2(self.cloud_))
150  conf = np.array(self.bridge_.imgmsg_to_cv2(self.conf_))
151 
152  # split out the camera-computed image planes
153  x_cam = cloud[:,:,0]
154  y_cam = cloud[:,:,1]
155  z_cam = cloud[:,:,2]
156  if ((cloud.dtype == np.float32) or
157  (cloud.dtype == np.float64)):
158  # convert to mm
159  x_cam *= 1000.
160  y_cam *= 1000.
161  z_cam *= 1000.
162 
163  # cast to int16_t
164  x_cam = x_cam.astype(np.int16)
165  y_cam = y_cam.astype(np.int16)
166  z_cam = z_cam.astype(np.int16)
167  else:
168  # camera data are already in mm
169  pass
170 
171  # Get the unit vectors
172  ex = uvec[:,:,0]
173  ey = uvec[:,:,1]
174  ez = uvec[:,:,2]
175 
176  # translation vector from extrinsics
177  tx = self.extrinsics_.tx
178  ty = self.extrinsics_.ty
179  tz = self.extrinsics_.tz
180 
181  # Cast the radial distance image to float
182  rdis_f = rdis.astype(np.float32)
183  if (rdis.dtype == np.float32):
184  # assume rdis was in meters, convert to mm
185  rdis_f *= 1000.
186 
187  # Compute Cartesian
188  x_ = ex * rdis_f + tx
189  y_ = ey * rdis_f + ty
190  z_ = ez * rdis_f + tz
191 
192  # mask out bad pixels from our computed cartesian values
193  bad_mask = (np.bitwise_and(conf, 0x1) == 0x1)
194  x_[bad_mask] = 0.
195  y_[bad_mask] = 0.
196  z_[bad_mask] = 0.
197 
198  # Transform to target frame
199  #
200  # NOTE: This could obviously be vectorized if we exploit our apriori
201  # knowledge of the transform, but we want to test the transform we are
202  # broadcasting via tf and the tf2 api for doing the transformation.
203  #
204  # I agree, this loop is slow and ugly :-( -- mostly b/c using the tf2
205  # interface with our data structures here is kind of wonky
206  #
207  tf_buffer = tf2_ros.Buffer()
208  tf_listener = tf2_ros.TransformListener(tf_buffer)
209  n_rows = x_.shape[0]
210  n_cols = x_.shape[1]
211  x_f = np.zeros((n_rows, n_cols), dtype=np.float32)
212  y_f = np.zeros((n_rows, n_cols), dtype=np.float32)
213  z_f = np.zeros((n_rows, n_cols), dtype=np.float32)
214  for i in range(n_rows):
215  for j in range(n_cols):
216  p = PointStamped()
217  p.header = self.rdis_.header
218  p.point.x = x_[i,j]
219  p.point.y = y_[i,j]
220  p.point.z = z_[i,j]
221  pt = tf_buffer.transform(p, self.cloud_.header.frame_id,
222  rospy.Duration(2.0))
223  x_f[i,j] = pt.point.x
224  y_f[i,j] = pt.point.y
225  z_f[i,j] = pt.point.z
226 
227  # cast to the data type of the point cloud
228  x_i = x_f.astype(np.int16)
229  y_i = y_f.astype(np.int16)
230  z_i = z_f.astype(np.int16)
231 
232  tol = 10 # milli-meters
233  x_mask = np.fabs(x_i - x_cam) > tol
234  y_mask = np.fabs(y_i - y_cam) > tol
235  z_mask = np.fabs(z_i - z_cam) > tol
236 
237  # we are asserting that no pixels are out-of-tolerance
238  # per the computation of the x_,y_,z_mask variables above.
239  self.assertTrue(x_mask.sum() == 0)
240  self.assertTrue(y_mask.sum() == 0)
241  self.assertTrue(z_mask.sum() == 0)
242 
243  # if any of the above asserts fail, the test will error out,
244  # so, we return True here carte blanche
245  return True
246 
247 def main():
248  rostest.rosrun('ifm3d', 'test_camera', TestCamera, sys.argv)
249  return 0
250 
251 if __name__ == '__main__':
252  sys.exit(main())
def extrinsics_cb(self, data, args)
Definition: test_camera.py:119
def __init__(self, args)
Definition: test_camera.py:52
def image_cb(self, data, args)
Definition: test_camera.py:123
def compute_cartesian(self)
Definition: test_camera.py:138


ifm3d
Author(s): Tom Panzarella
autogenerated on Thu Feb 4 2021 03:23:54