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
38 TP: 14 May 2018 - heavily adapted from my old o3d3xx-ros test of the same 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 49 NOTE: The camera h/w is needed to run this test. 53 super(TestCamera, self).
__init__(*args)
64 rospy.init_node(
'test_camera')
68 rospy.Subscriber(
"/ifm3d/camera/distance", Image, self.
image_cb,
69 queue_size=
None, callback_args=
"rdis")
71 rospy.Subscriber(
"/ifm3d/camera/xyz_image", Image, self.
image_cb,
72 queue_size=
None, callback_args=
"cloud")
74 rospy.Subscriber(
"/ifm3d/camera/unit_vectors", Image, self.
image_cb,
75 queue_size=
None, callback_args=
"uvec")
77 rospy.Subscriber(
"/ifm3d/camera/extrinsics", Extrinsics,
80 rospy.Subscriber(
"/ifm3d/camera/confidence", Image, self.
image_cb,
81 queue_size=
None, callback_args=
"conf")
84 timeout_t = time.time() + 10.0
85 rate = rospy.Rate(10.0)
86 while ((
not rospy.is_shutdown())
and 88 (time.time() < timeout_t)):
90 if ((self.
rdis_ is not None)
and 91 (self.
cloud_ is not None)
and 92 (self.
uvec_ is not None)
and 94 (self.
conf_ is not None)):
98 d = self.rdis_.header.stamp - self.cloud_.header.stamp
100 d2 = self.rdis_.header.stamp - self.conf_.header.stamp
125 if im_type ==
"rdis":
126 if self.
rdis_ is None:
128 elif im_type ==
"cloud":
131 elif im_type ==
"uvec":
132 if self.
uvec_ is None:
134 elif im_type ==
"conf":
135 if self.
conf_ is None:
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 145 Returns a bool indicating the the success of the computation. 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_))
156 if ((cloud.dtype == np.float32)
or 157 (cloud.dtype == np.float64)):
164 x_cam = x_cam.astype(np.int16)
165 y_cam = y_cam.astype(np.int16)
166 z_cam = z_cam.astype(np.int16)
177 tx = self.extrinsics_.tx
178 ty = self.extrinsics_.ty
179 tz = self.extrinsics_.tz
182 rdis_f = rdis.astype(np.float32)
183 if (rdis.dtype == np.float32):
188 x_ = ex * rdis_f + tx
189 y_ = ey * rdis_f + ty
190 z_ = ez * rdis_f + tz
193 bad_mask = (np.bitwise_and(conf, 0x1) == 0x1)
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):
217 p.header = self.rdis_.header
221 pt = tf_buffer.transform(p, self.cloud_.header.frame_id,
223 x_f[i,j] = pt.point.x
224 y_f[i,j] = pt.point.y
225 z_f[i,j] = pt.point.z
228 x_i = x_f.astype(np.int16)
229 y_i = y_f.astype(np.int16)
230 z_i = z_f.astype(np.int16)
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
239 self.assertTrue(x_mask.sum() == 0)
240 self.assertTrue(y_mask.sum() == 0)
241 self.assertTrue(z_mask.sum() == 0)
248 rostest.rosrun(
'ifm3d',
'test_camera', TestCamera, sys.argv)
251 if __name__ ==
'__main__':
def extrinsics_cb(self, data, args)
def image_cb(self, data, args)
def compute_cartesian(self)