test_zivid_camera.cpp
Go to the documentation of this file.
1 #ifdef __clang__
2 #pragma clang diagnostic push
3 // Errors to ignore for this entire file
4 #pragma clang diagnostic ignored "-Wglobal-constructors" // error triggered by gtest fixtures
5 #endif
6 
7 #include <zivid_camera/CameraInfoSerialNumber.h>
8 #include <zivid_camera/CameraInfoModelName.h>
9 #include <zivid_camera/Capture.h>
10 #include <zivid_camera/Capture2D.h>
11 #include <zivid_camera/CaptureAssistantSuggestSettings.h>
12 #include <zivid_camera/SettingsAcquisitionConfig.h>
13 #include <zivid_camera/Settings2DAcquisitionConfig.h>
14 #include <zivid_camera/SettingsConfig.h>
15 #include <zivid_camera/Settings2DConfig.h>
16 #include <zivid_camera/IsConnected.h>
17 
18 #include <Zivid/Application.h>
19 #include <Zivid/CaptureAssistant.h>
20 #include <Zivid/Experimental/SettingsInfo.h>
21 #include <Zivid/Frame.h>
22 #include <Zivid/Camera.h>
23 #include <Zivid/Version.h>
24 
25 #include <dynamic_reconfigure/client.h>
26 #include <sensor_msgs/CameraInfo.h>
27 #include <sensor_msgs/PointCloud2.h>
28 #include <sensor_msgs/Image.h>
29 
30 #include "gtest_include_wrapper.h"
31 
32 #include <ros/ros.h>
33 
34 using SecondsD = std::chrono::duration<double>;
35 
36 namespace
37 {
38 template <class Rep, class Period>
39 ros::Duration toRosDuration(const std::chrono::duration<Rep, Period>& d)
40 {
41  return ros::Duration{ std::chrono::duration_cast<SecondsD>(d).count() };
42 }
43 } // namespace
44 
45 class ZividNodeTestBase : public testing::Test
46 {
47 protected:
49  {
50  const auto test_name = testing::UnitTest::GetInstance()->current_test_info()->name();
51  std::cerr << "Starting test " << test_name << "\n";
52  }
53 };
54 
56 {
57 protected:
59 
60  const ros::Duration node_ready_wait_duration{ 15 };
61  const ros::Duration short_wait_duration{ 0.25 };
62  const ros::Duration dr_get_max_wait_duration{ 5 };
63  static constexpr auto capture_service_name = "/zivid_camera/capture";
64  static constexpr auto capture_2d_service_name = "/zivid_camera/capture_2d";
65  static constexpr auto capture_assistant_suggest_settings_service_name = "/zivid_camera/capture_assistant/"
66  "suggest_settings";
67  static constexpr auto color_camera_info_topic_name = "/zivid_camera/color/camera_info";
68  static constexpr auto color_image_color_topic_name = "/zivid_camera/color/image_color";
69  static constexpr auto depth_camera_info_topic_name = "/zivid_camera/depth/camera_info";
70  static constexpr auto depth_image_topic_name = "/zivid_camera/depth/image";
71  static constexpr auto snr_camera_info_topic_name = "/zivid_camera/depth/camera_info";
72  static constexpr auto snr_image_topic_name = "/zivid_camera/snr/image";
73  static constexpr auto points_xyz_topic_name = "/zivid_camera/points/xyz";
74  static constexpr auto points_xyzrgba_topic_name = "/zivid_camera/points/xyzrgba";
75  static constexpr size_t num_dr_capture_servers = 10;
76  static constexpr auto file_camera_path = "/usr/share/Zivid/data/FileCameraZividOne.zfc";
77 
78  template <typename Type>
80  {
81  public:
82  static SubscriptionWrapper<Type> make(ros::NodeHandle& nh, const std::string& name)
83  {
84  auto w = SubscriptionWrapper<Type>();
85  boost::function<void(const boost::shared_ptr<const Type>&)> cb = [impl = w.impl_.get()](const auto& v) mutable {
86  impl->num_messages_++;
87  impl->last_message_ = *v;
88  };
89  w.impl_->subscriber_ = nh.subscribe<Type>(name, 1, cb);
90  return w;
91  }
92 
93  const std::optional<Type>& lastMessage() const
94  {
95  return impl_->last_message_;
96  }
97 
98  std::size_t numMessages() const
99  {
100  return impl_->num_messages_;
101  }
102 
103  private:
104  SubscriptionWrapper() : impl_(std::make_unique<Impl>())
105  {
106  }
107  struct Impl
108  {
109  Impl() : num_messages_(0)
110  {
111  }
113  std::optional<Type> last_message_;
114  std::size_t num_messages_;
115  };
116  std::unique_ptr<Impl> impl_;
117  };
118 
120  {
121  ASSERT_TRUE(ros::service::waitForService(capture_service_name, node_ready_wait_duration));
122  }
123 
125  {
126  dynamic_reconfigure::Client<zivid_camera::SettingsAcquisitionConfig> acquisition_0_client("/zivid_camera/settings/"
127  "acquisition_0/");
128  zivid_camera::SettingsAcquisitionConfig acquisition_0_cfg;
129  ASSERT_TRUE(acquisition_0_client.getDefaultConfiguration(acquisition_0_cfg, dr_get_max_wait_duration));
130  acquisition_0_cfg.enabled = true;
131  ASSERT_TRUE(acquisition_0_client.setConfiguration(acquisition_0_cfg));
132  }
133 
135  {
136  dynamic_reconfigure::Client<zivid_camera::Settings2DAcquisitionConfig> acquisition_0_client("/zivid_camera/"
137  "settings_2d/"
138  "acquisition_0/");
139  zivid_camera::Settings2DAcquisitionConfig cfg;
140  ASSERT_TRUE(acquisition_0_client.getDefaultConfiguration(cfg, dr_get_max_wait_duration));
141  cfg.enabled = true;
142  ASSERT_TRUE(acquisition_0_client.setConfiguration(cfg));
143  }
144 
146  {
147  enableFirst3DAcquisition();
148  zivid_camera::Capture capture;
149  ASSERT_TRUE(ros::service::call(capture_service_name, capture));
150  short_wait_duration.sleep();
151  }
152 
153  template <class Type>
154  SubscriptionWrapper<Type> subscribe(const std::string& name)
155  {
156  return SubscriptionWrapper<Type>::make(nh_, name);
157  }
158 
159  template <class A, class B>
160  void assertArrayFloatEq(const A& actual, const B& expected) const
161  {
162  ASSERT_EQ(actual.size(), expected.size());
163  for (std::size_t i = 0; i < actual.size(); i++)
164  {
165  ASSERT_FLOAT_EQ(actual[i], expected[i]);
166  }
167  }
168 
169  void assertSensorMsgsPointCloud2Meta(const sensor_msgs::PointCloud2& point_cloud, std::size_t width,
170  std::size_t height, std::size_t point_step)
171  {
172  ASSERT_EQ(point_cloud.width, width);
173  ASSERT_EQ(point_cloud.height, height);
174  ASSERT_EQ(point_cloud.point_step, point_step);
175  ASSERT_EQ(point_cloud.row_step, point_cloud.width * point_cloud.point_step);
176  ASSERT_EQ(point_cloud.is_dense, false);
177  ASSERT_EQ(point_cloud.data.size(), point_cloud.width * point_cloud.height * point_cloud.point_step);
178  }
179 
180  void assertSensorMsgsImageMeta(const sensor_msgs::Image& image, std::size_t width, std::size_t height,
181  std::size_t bytes_per_pixel, const std::string& encoding)
182  {
183  ASSERT_EQ(image.width, width);
184  ASSERT_EQ(image.height, height);
185  ASSERT_EQ(image.step, bytes_per_pixel * image.width);
186  ASSERT_EQ(image.data.size(), image.step * image.height);
187  ASSERT_EQ(image.encoding, encoding);
188  ASSERT_EQ(image.is_bigendian, false);
189  }
190 
191  void assertSensorMsgsImageContents(const sensor_msgs::Image& image,
192  const Zivid::Array2D<Zivid::ColorRGBA>& expected_rgba)
193  {
194  ASSERT_EQ(image.width, expected_rgba.width());
195  ASSERT_EQ(image.height, expected_rgba.height());
196  for (std::size_t i = 0; i < expected_rgba.size(); i++)
197  {
198  const auto expectedPixel = expected_rgba(i);
199  const auto index = i * 4U;
200  ASSERT_EQ(image.data[index], expectedPixel.r);
201  ASSERT_EQ(image.data[index + 1], expectedPixel.g);
202  ASSERT_EQ(image.data[index + 2], expectedPixel.b);
203  ASSERT_EQ(image.data[index + 3], expectedPixel.a);
204  ASSERT_EQ(expectedPixel.a, 255);
205  }
206  }
207 
208  void assertCameraInfoForFileCamera(const sensor_msgs::CameraInfo& ci) const
209  {
210  ASSERT_EQ(ci.width, 1920U);
211  ASSERT_EQ(ci.height, 1200U);
212  ASSERT_EQ(ci.distortion_model, "plumb_bob");
213 
214  // [fx 0 cx]
215  // K = [ 0 fy cy]
216  // [ 0 0 1]
217  assertArrayFloatEq(
218  ci.K, std::array<double, 9>{ 2759.12329102, 0, 958.78460693, 0, 2758.73681641, 634.94018555, 0, 0, 1 });
219 
220  // R = I
221  assertArrayFloatEq(ci.R, std::array<double, 9>{ 1, 0, 0, 0, 1, 0, 0, 0, 1 });
222 
223  // [fx' 0 cx' Tx]
224  // P = [ 0 fy' cy' Ty]
225  // [ 0 0 1 0]
226  assertArrayFloatEq(ci.P, std::array<double, 12>{ 2759.12329102, 0, 958.78460693, 0, 0, 2758.73681641, 634.94018555,
227  0, 0, 0, 1, 0 });
228  }
229 };
230 
232 {
233 protected:
234  TestWithFileCamera() : camera_(zivid_.createFileCamera(file_camera_path))
235  {
236  waitForReady();
237  }
238  Zivid::Application zivid_;
239  Zivid::Camera camera_;
240 };
241 
242 TEST_F(ZividNodeTest, testServiceCameraInfoModelName)
243 {
244  waitForReady();
245  zivid_camera::CameraInfoModelName model_name;
246  ASSERT_TRUE(ros::service::call("/zivid_camera/camera_info/model_name", model_name));
247  ASSERT_EQ(model_name.response.model_name, std::string("FileCamera-") + ZIVID_CORE_VERSION);
248 }
249 
250 TEST_F(ZividNodeTest, testServiceCameraInfoSerialNumber)
251 {
252  waitForReady();
253  zivid_camera::CameraInfoSerialNumber serial_number;
254  ASSERT_TRUE(ros::service::call("/zivid_camera/camera_info/serial_number", serial_number));
255  ASSERT_EQ(serial_number.response.serial_number, "F1");
256 }
257 
258 TEST_F(ZividNodeTest, testServiceIsConnected)
259 {
260  waitForReady();
261  zivid_camera::IsConnected is_connected;
262  ASSERT_TRUE(ros::service::call("/zivid_camera/is_connected", is_connected));
263  ASSERT_EQ(is_connected.response.is_connected, true);
264 }
265 
266 TEST_F(ZividNodeTest, testCapturePublishesTopics)
267 {
268  waitForReady();
269 
270  auto color_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(color_camera_info_topic_name);
271  auto color_image_color_sub = subscribe<sensor_msgs::Image>(color_image_color_topic_name);
272  auto depth_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(depth_camera_info_topic_name);
273  auto depth_image_sub = subscribe<sensor_msgs::Image>(depth_image_topic_name);
274  auto snr_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(snr_camera_info_topic_name);
275  auto snr_image_sub = subscribe<sensor_msgs::Image>(snr_image_topic_name);
276  auto points_xyz_sub = subscribe<sensor_msgs::PointCloud2>(points_xyz_topic_name);
277  auto points_xyzrgba_sub = subscribe<sensor_msgs::PointCloud2>(points_xyzrgba_topic_name);
278 
279  auto assert_num_topics_received = [&](std::size_t numTopics) {
280  ASSERT_EQ(color_camera_info_sub.numMessages(), numTopics);
281  ASSERT_EQ(color_image_color_sub.numMessages(), numTopics);
282  ASSERT_EQ(depth_camera_info_sub.numMessages(), numTopics);
283  ASSERT_EQ(depth_image_sub.numMessages(), numTopics);
284  ASSERT_EQ(snr_camera_info_sub.numMessages(), numTopics);
285  ASSERT_EQ(snr_image_sub.numMessages(), numTopics);
286  ASSERT_EQ(points_xyz_sub.numMessages(), numTopics);
287  ASSERT_EQ(points_xyzrgba_sub.numMessages(), numTopics);
288  };
289 
290  short_wait_duration.sleep();
291  assert_num_topics_received(0);
292 
293  zivid_camera::Capture capture;
294  // Capture fails when no acquisitions are enabled
295  ASSERT_FALSE(ros::service::call(capture_service_name, capture));
296  short_wait_duration.sleep();
297  assert_num_topics_received(0);
298 
299  enableFirst3DAcquisition();
300 
301  ASSERT_TRUE(ros::service::call(capture_service_name, capture));
302  short_wait_duration.sleep();
303  assert_num_topics_received(1);
304 
305  ASSERT_TRUE(ros::service::call(capture_service_name, capture));
306  short_wait_duration.sleep();
307  assert_num_topics_received(2);
308 
309  ASSERT_TRUE(ros::service::call(capture_service_name, capture));
310  short_wait_duration.sleep();
311  assert_num_topics_received(3);
312 
313  short_wait_duration.sleep();
314  assert_num_topics_received(3);
315 }
316 
318 {
319 protected:
320  Zivid::PointCloud captureViaSDKDefaultSettings()
321  {
322  return camera_.capture(Zivid::Settings{ Zivid::Settings::Acquisitions{ Zivid::Settings::Acquisition{} } })
323  .pointCloud();
324  }
325 
327  {
328  return camera_.capture(Zivid::Settings2D{ Zivid::Settings2D::Acquisitions{ Zivid::Settings2D::Acquisition{} } });
329  }
330 
331  void comparePointCoordinate(float ros_coordinate, float sdk_coordinate) const
332  {
333  if (std::isnan(ros_coordinate))
334  {
335  ASSERT_TRUE(std::isnan(sdk_coordinate));
336  }
337  else
338  {
339  // Output from the SDK is millimeters. In the ROS driver a transform is applied to convert
340  // the ROS points to meters.
341  const float delta = 0.000001f;
342  ASSERT_NEAR(ros_coordinate, sdk_coordinate / 1000, delta);
343  }
344  }
345 };
346 
347 TEST_F(CaptureOutputTest, testCapturePointsXYZGBA)
348 {
349  auto points_sub = subscribe<sensor_msgs::PointCloud2>(points_xyzrgba_topic_name);
350 
351  enableFirst3DAcquisitionAndCapture();
352 
353  const auto& last_pc2 = points_sub.lastMessage();
354  ASSERT_TRUE(last_pc2.has_value());
355  assertSensorMsgsPointCloud2Meta(*last_pc2, 1920U, 1200U, 16U);
356 
357  const auto point_cloud = captureViaSDKDefaultSettings();
358  const auto expected_xyzrgba = point_cloud.copyData<Zivid::PointXYZColorRGBA>();
359  ASSERT_EQ(last_pc2->width, expected_xyzrgba.width());
360  ASSERT_EQ(last_pc2->height, expected_xyzrgba.height());
361  for (std::size_t i = 0; i < expected_xyzrgba.size(); i++)
362  {
363  const uint8_t* point_ptr = &last_pc2->data[i * last_pc2->point_step];
364  const float x = *reinterpret_cast<const float*>(&point_ptr[0]);
365  const float y = *reinterpret_cast<const float*>(&point_ptr[4]);
366  const float z = *reinterpret_cast<const float*>(&point_ptr[8]);
367  const uint32_t argb = *reinterpret_cast<const uint32_t*>(&point_ptr[12]);
368  const auto& expected = expected_xyzrgba(i);
369 
370  comparePointCoordinate(x, expected.point.x);
371  comparePointCoordinate(y, expected.point.y);
372  comparePointCoordinate(z, expected.point.z);
373  const auto expected_argb = static_cast<uint32_t>(expected.color.a << 24) |
374  static_cast<uint32_t>(expected.color.r << 16) |
375  static_cast<uint32_t>(expected.color.g << 8) | static_cast<uint32_t>(expected.color.b);
376  ASSERT_EQ(argb, expected_argb);
377  }
378 }
379 
380 TEST_F(CaptureOutputTest, testCapturePointsXYZ)
381 {
382  auto points_sub = subscribe<sensor_msgs::PointCloud2>(points_xyz_topic_name);
383 
384  enableFirst3DAcquisitionAndCapture();
385 
386  const auto& point_cloud = points_sub.lastMessage();
387  ASSERT_TRUE(point_cloud.has_value());
388  assertSensorMsgsPointCloud2Meta(*point_cloud, 1920U, 1200U,
389  16U); // 3x4 bytes for xyz + 4 bytes padding (w) = 16 bytes total
390 
391  auto point_cloud_sdk = captureViaSDKDefaultSettings();
392  auto expected_xyz = point_cloud_sdk.copyData<Zivid::PointXYZ>();
393  ASSERT_EQ(point_cloud->width, expected_xyz.width());
394  ASSERT_EQ(point_cloud->height, expected_xyz.height());
395  for (std::size_t i = 0; i < expected_xyz.size(); i++)
396  {
397  const uint8_t* point_ptr = &point_cloud->data[i * point_cloud->point_step];
398  const float x = *reinterpret_cast<const float*>(&point_ptr[0]);
399  const float y = *reinterpret_cast<const float*>(&point_ptr[4]);
400  const float z = *reinterpret_cast<const float*>(&point_ptr[8]);
401 
402  const auto expected = expected_xyz(i);
403  comparePointCoordinate(x, expected.x);
404  comparePointCoordinate(y, expected.y);
405  comparePointCoordinate(z, expected.z);
406  }
407 }
408 
409 TEST_F(CaptureOutputTest, testCapture3DColorImage)
410 {
411  auto color_image_sub = subscribe<sensor_msgs::Image>(color_image_color_topic_name);
412 
413  enableFirst3DAcquisitionAndCapture();
414  const auto image = color_image_sub.lastMessage();
415  ASSERT_TRUE(image.has_value());
416  const std::size_t bytes_per_pixel = 4U;
417  assertSensorMsgsImageMeta(*image, 1920U, 1200U, bytes_per_pixel, "rgba8");
418 
419  const auto point_cloud = captureViaSDKDefaultSettings();
420  const auto expected_rgba = point_cloud.copyData<Zivid::ColorRGBA>();
421  assertSensorMsgsImageContents(*image, expected_rgba);
422 }
423 
424 TEST_F(CaptureOutputTest, testCaptureDepthImage)
425 {
426  auto depth_image_sub = subscribe<sensor_msgs::Image>(depth_image_topic_name);
427 
428  enableFirst3DAcquisitionAndCapture();
429 
430  const auto image = depth_image_sub.lastMessage();
431  ASSERT_TRUE(image.has_value());
432  const std::size_t bytes_per_pixel = 4U;
433  assertSensorMsgsImageMeta(*image, 1920U, 1200U, bytes_per_pixel, "32FC1");
434 
435  const auto point_cloud = captureViaSDKDefaultSettings();
436  const auto expected_z = point_cloud.copyData<Zivid::PointZ>();
437  ASSERT_EQ(image->width, expected_z.width());
438  ASSERT_EQ(image->height, expected_z.height());
439  for (std::size_t i = 0; i < expected_z.size(); i++)
440  {
441  const auto expected = expected_z(i);
442  const float z = *reinterpret_cast<const float*>(image->data.data() + i * bytes_per_pixel);
443  comparePointCoordinate(z, expected.z);
444  }
445 }
446 
447 TEST_F(CaptureOutputTest, testCaptureSNRImage)
448 {
449  auto snr_image_sub = subscribe<sensor_msgs::Image>(snr_image_topic_name);
450 
451  enableFirst3DAcquisitionAndCapture();
452 
453  const auto image = snr_image_sub.lastMessage();
454  ASSERT_TRUE(image.has_value());
455  const std::size_t bytes_per_pixel = 4U;
456  assertSensorMsgsImageMeta(*image, 1920U, 1200U, bytes_per_pixel, "32FC1");
457 
458  const auto point_cloud = captureViaSDKDefaultSettings();
459  const auto expected_snr = point_cloud.copyData<Zivid::SNR>();
460  ASSERT_EQ(image->width, expected_snr.width());
461  ASSERT_EQ(image->height, expected_snr.height());
462  for (std::size_t i = 0; i < expected_snr.size(); i++)
463  {
464  const auto expected = expected_snr(i);
465  const float snr = *reinterpret_cast<const float*>(image->data.data() + i * bytes_per_pixel);
466  ASSERT_EQ(snr, expected.value);
467  }
468 }
469 
470 #if ZIVID_CORE_VERSION_MAJOR > 2 || (ZIVID_CORE_VERSION_MAJOR == 2 && ZIVID_CORE_VERSION_MINOR >= 2)
471 // The stripe engine setting was added in SDK 2.2
472 TEST_F(TestWithFileCamera, testSettingsEngine)
473 {
474  waitForReady();
475  enableFirst3DAcquisition();
476  auto points_sub = subscribe<sensor_msgs::PointCloud2>(points_xyz_topic_name);
477 
478  dynamic_reconfigure::Client<zivid_camera::SettingsConfig> settings_client("/zivid_camera/settings/");
479  zivid_camera::SettingsConfig settings_cfg;
480  ASSERT_TRUE(settings_client.getDefaultConfiguration(settings_cfg, dr_get_max_wait_duration));
481  ASSERT_EQ(settings_cfg.experimental_engine, zivid_camera::Settings_ExperimentalEnginePhase);
482  settings_cfg.experimental_engine = zivid_camera::Settings_ExperimentalEngineStripe;
483  settings_cfg.processing_filters_reflection_removal_enabled = true;
484  settings_cfg.processing_filters_experimental_contrast_distortion_correction_enabled = true;
485  ASSERT_TRUE(settings_client.setConfiguration(settings_cfg));
486 
487  zivid_camera::Capture capture;
488  // Capture fails here because file camera does not support Stripe engine
489  ASSERT_FALSE(ros::service::call(capture_service_name, capture));
490  ASSERT_EQ(points_sub.numMessages(), 0U);
491 
492  settings_cfg.experimental_engine = zivid_camera::Settings_ExperimentalEnginePhase;
493  ASSERT_TRUE(settings_client.setConfiguration(settings_cfg));
494  ASSERT_TRUE(ros::service::call(capture_service_name, capture));
495  short_wait_duration.sleep();
496  ASSERT_EQ(points_sub.numMessages(), 1U);
497 }
498 #endif
499 
500 TEST_F(ZividNodeTest, testCaptureCameraInfo)
501 {
502  waitForReady();
503 
504  auto color_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(color_camera_info_topic_name);
505  auto depth_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(depth_camera_info_topic_name);
506  auto snr_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(snr_camera_info_topic_name);
507 
508  enableFirst3DAcquisitionAndCapture();
509 
510  ASSERT_EQ(color_camera_info_sub.numMessages(), 1U);
511  ASSERT_EQ(depth_camera_info_sub.numMessages(), 1U);
512  ASSERT_EQ(snr_camera_info_sub.numMessages(), 1U);
513 
514  assertCameraInfoForFileCamera(*color_camera_info_sub.lastMessage());
515  assertCameraInfoForFileCamera(*depth_camera_info_sub.lastMessage());
516  assertCameraInfoForFileCamera(*snr_camera_info_sub.lastMessage());
517 }
518 
519 TEST_F(CaptureOutputTest, testCapture2D)
520 {
521  auto color_camera_info_sub = subscribe<sensor_msgs::CameraInfo>(color_camera_info_topic_name);
522  auto color_image_color_sub = subscribe<sensor_msgs::Image>(color_image_color_topic_name);
523 
524  auto assert_num_topics_received = [&](std::size_t num_topics) {
525  ASSERT_EQ(color_camera_info_sub.numMessages(), num_topics);
526  ASSERT_EQ(color_image_color_sub.numMessages(), num_topics);
527  };
528 
529  short_wait_duration.sleep();
530  assert_num_topics_received(0);
531 
532  // Capture fails when no acquisitions are enabled
533  zivid_camera::Capture2D capture;
534  ASSERT_FALSE(ros::service::call(capture_2d_service_name, capture));
535  short_wait_duration.sleep();
536  assert_num_topics_received(0);
537 
538  enableFirst2DAcquisition();
539  ASSERT_TRUE(ros::service::call(capture_2d_service_name, capture));
540  short_wait_duration.sleep();
541  assert_num_topics_received(1);
542 
543  auto verify_image_and_camera_info = [this](const auto& img, const auto& info) {
544  assertCameraInfoForFileCamera(info);
545  assertSensorMsgsImageMeta(img, 1920U, 1200U, 4U, "rgba8");
546  assertSensorMsgsImageContents(img, capture2DViaSDKDefaultSettings().imageRGBA());
547  };
548 
549  verify_image_and_camera_info(*color_image_color_sub.lastMessage(), *color_camera_info_sub.lastMessage());
550 
551  short_wait_duration.sleep();
552  assert_num_topics_received(1);
553 
554  ASSERT_TRUE(ros::service::call(capture_2d_service_name, capture));
555  short_wait_duration.sleep();
556  assert_num_topics_received(2);
557  verify_image_and_camera_info(*color_image_color_sub.lastMessage(), *color_camera_info_sub.lastMessage());
558 }
559 
561 {
562 protected:
563  template <typename Setting>
564  typename Setting::ValueType sdkDefaultValue()
565  {
566  return Zivid::Experimental::SettingsInfo::defaultValue<Setting>(camera_.info()).value();
567  }
568 
569  template <typename Setting>
571  {
572  return Zivid::Experimental::SettingsInfo::validRange<Setting>(camera_.info());
573  }
574 
575  template <typename ZividSettingsType, typename ConfigType>
576  void testGeneralMinMaxDefault(const std::string& service_name)
577  {
578  ASSERT_TRUE(ros::service::waitForService(service_name + "/set_parameters", short_wait_duration));
579 
580  dynamic_reconfigure::Client<ConfigType> client(service_name);
581 
582  ConfigType default_cfg;
583  ASSERT_TRUE(client.getDefaultConfiguration(default_cfg, dr_get_max_wait_duration));
584  ConfigType min_cfg;
585  ASSERT_TRUE(client.getMinConfiguration(min_cfg, dr_get_max_wait_duration));
586  ConfigType max_cfg;
587  ASSERT_TRUE(client.getMaxConfiguration(max_cfg, dr_get_max_wait_duration));
588 
589  using BlueBalance = typename ZividSettingsType::Processing::Color::Balance::Blue;
590  ASSERT_EQ(default_cfg.processing_color_balance_blue, sdkDefaultValue<BlueBalance>());
591  ASSERT_EQ(min_cfg.processing_color_balance_blue, sdkValidRange<BlueBalance>().min());
592  ASSERT_EQ(max_cfg.processing_color_balance_blue, sdkValidRange<BlueBalance>().max());
593 
594  using GreenBalance = typename ZividSettingsType::Processing::Color::Balance::Green;
595  ASSERT_EQ(default_cfg.processing_color_balance_green, sdkDefaultValue<GreenBalance>());
596  ASSERT_EQ(min_cfg.processing_color_balance_green, sdkValidRange<GreenBalance>().min());
597  ASSERT_EQ(max_cfg.processing_color_balance_green, sdkValidRange<GreenBalance>().max());
598 
599  using RedBalance = typename ZividSettingsType::Processing::Color::Balance::Red;
600  ASSERT_EQ(default_cfg.processing_color_balance_red, sdkDefaultValue<RedBalance>());
601  ASSERT_EQ(min_cfg.processing_color_balance_red, sdkValidRange<RedBalance>().min());
602  ASSERT_EQ(max_cfg.processing_color_balance_red, sdkValidRange<RedBalance>().max());
603 
604  if constexpr (std::is_same_v<ZividSettingsType, Zivid::Settings>)
605  {
606  using OutlierRemovalThreshold = typename ZividSettingsType::Processing::Filters::Outlier::Removal::Threshold;
607  ASSERT_EQ(default_cfg.processing_filters_outlier_removal_threshold, sdkDefaultValue<OutlierRemovalThreshold>());
608  ASSERT_EQ(min_cfg.processing_filters_outlier_removal_threshold, sdkValidRange<OutlierRemovalThreshold>().min());
609  ASSERT_EQ(max_cfg.processing_filters_outlier_removal_threshold, sdkValidRange<OutlierRemovalThreshold>().max());
610  }
611  }
612 
613  template <typename ZividSettingsType, typename ConfigType>
614  void testAcquisitionMinMaxDefault(const std::string& prefix, std::size_t num_acquisition_servers)
615  {
616  for (std::size_t i = 0; i < num_acquisition_servers; i++)
617  {
618  ASSERT_TRUE(ros::service::waitForService(prefix + "acquisition_" + std::to_string(i) + "/set_parameters",
619  short_wait_duration));
620 
621  dynamic_reconfigure::Client<ConfigType> client(prefix + "acquisition_" + std::to_string(i) + "/");
622  ConfigType default_cfg;
623  ASSERT_TRUE(client.getDefaultConfiguration(default_cfg, dr_get_max_wait_duration));
624  ConfigType min_cfg;
625  ASSERT_TRUE(client.getMinConfiguration(min_cfg, dr_get_max_wait_duration));
626  ConfigType max_cfg;
627  ASSERT_TRUE(client.getMaxConfiguration(max_cfg, dr_get_max_wait_duration));
628 
629  ASSERT_EQ(default_cfg.enabled, false);
630 
631  using Aperture = typename ZividSettingsType::Acquisition::Aperture;
632  ASSERT_EQ(default_cfg.aperture, sdkDefaultValue<Aperture>());
633  ASSERT_EQ(min_cfg.aperture, sdkValidRange<Aperture>().min());
634  ASSERT_EQ(max_cfg.aperture, sdkValidRange<Aperture>().max());
635 
636  using Brightness = typename ZividSettingsType::Acquisition::Brightness;
637  ASSERT_EQ(default_cfg.brightness, sdkDefaultValue<Brightness>());
638  ASSERT_EQ(min_cfg.brightness, sdkValidRange<Brightness>().min());
639  ASSERT_EQ(max_cfg.brightness, sdkValidRange<Brightness>().max());
640 
641  using ExposureTime = typename ZividSettingsType::Acquisition::ExposureTime;
642  ASSERT_EQ(default_cfg.exposure_time, sdkDefaultValue<ExposureTime>().count());
643  ASSERT_EQ(min_cfg.exposure_time, sdkValidRange<ExposureTime>().min().count());
644  ASSERT_EQ(max_cfg.exposure_time, sdkValidRange<ExposureTime>().max().count());
645 
646  using Gain = typename ZividSettingsType::Acquisition::Gain;
647  ASSERT_EQ(default_cfg.gain, sdkDefaultValue<Gain>());
648  ASSERT_EQ(min_cfg.gain, sdkValidRange<Gain>().min());
649  ASSERT_EQ(max_cfg.gain, sdkValidRange<Gain>().max());
650  }
651  ASSERT_FALSE(ros::service::waitForService(
652  prefix + "acquisition_" + std::to_string(num_acquisition_servers) + "/set_parameters", short_wait_duration));
653  }
654 };
655 
656 TEST_F(DynamicReconfigureMinMaxDefaultTest, testDynamicReconfigureSettingsMinMaxDefaultValue)
657 {
658  // Test the default, min and max configuration of the file camera used in the test suite. This
659  // file camera is of model "Zivid One".
660  waitForReady();
661 
662  testGeneralMinMaxDefault<Zivid::Settings, zivid_camera::SettingsConfig>("/zivid_camera/settings/");
663  testAcquisitionMinMaxDefault<Zivid::Settings, zivid_camera::SettingsAcquisitionConfig>("/zivid_camera/settings/", 10);
664 
665  testGeneralMinMaxDefault<Zivid::Settings2D, zivid_camera::Settings2DConfig>("/zivid_camera/settings_2d/");
666  testAcquisitionMinMaxDefault<Zivid::Settings2D, zivid_camera::Settings2DAcquisitionConfig>("/zivid_camera/"
667  "settings_2d/",
668  1);
669 }
670 
672 {
673 protected:
674  ZividCATest() : camera_settings_client_("/zivid_camera/settings")
675  {
676  settings_acquisition_clients_.reserve(num_dr_capture_servers);
677  for (std::size_t i = 0; i < num_dr_capture_servers; i++)
678  {
679  using Client = dynamic_reconfigure::Client<zivid_camera::SettingsAcquisitionConfig>;
680  settings_acquisition_clients_.emplace_back(
681  std::make_unique<Client>("/zivid_camera/settings/acquisition_" + std::to_string(i)));
682  }
683  }
684 
685  zivid_camera::SettingsConfig settingsConfig()
686  {
687  zivid_camera::SettingsConfig cfg;
688  EXPECT_TRUE(camera_settings_client_.getCurrentConfiguration(cfg, dr_get_max_wait_duration));
689  return cfg;
690  }
691 
692  zivid_camera::SettingsAcquisitionConfig settingsAcquisitionConfig(std::size_t i) const
693  {
694  zivid_camera::SettingsAcquisitionConfig cfg;
695  EXPECT_TRUE(settings_acquisition_clients_[i]->getCurrentConfiguration(cfg, dr_get_max_wait_duration));
696  return cfg;
697  }
698 
699  std::size_t numEnabled3DAcquisitions() const
700  {
701  std::size_t enabled_acquisitions = 0;
702  for (std::size_t i = 0; i < num_dr_capture_servers; i++)
703  {
704  if (settingsAcquisitionConfig(i).enabled)
705  {
706  enabled_acquisitions++;
707  }
708  }
709  return enabled_acquisitions;
710  }
711 
712  void compareSettingsAcquisitionConfigWithSettings(const Zivid::Settings::Acquisition& a,
713  const zivid_camera::SettingsAcquisitionConfig& cfg) const
714  {
715  ASSERT_EQ(true, cfg.enabled);
716  ASSERT_EQ(a.aperture().value(), cfg.aperture);
717  ASSERT_EQ(a.brightness().value(), cfg.brightness);
718  ASSERT_EQ(a.exposureTime().value().count(), cfg.exposure_time);
719  ASSERT_EQ(a.gain().value(), cfg.gain);
720  }
721 
722  void compareSettingsConfigWithSettings(const Zivid::Settings& s, const zivid_camera::SettingsConfig& cfg) const
723  {
724  const auto& color = s.processing().color();
725  ASSERT_EQ(color.balance().blue().value(), cfg.processing_color_balance_blue);
726  ASSERT_EQ(color.balance().green().value(), cfg.processing_color_balance_green);
727  ASSERT_EQ(color.balance().red().value(), cfg.processing_color_balance_red);
728 
729  const auto& filters = s.processing().filters();
730  ASSERT_EQ(filters.noise().removal().isEnabled().value(), cfg.processing_filters_noise_removal_enabled);
731  ASSERT_EQ(filters.noise().removal().threshold().value(), cfg.processing_filters_noise_removal_threshold);
732  ASSERT_EQ(filters.smoothing().gaussian().isEnabled().value(), cfg.processing_filters_smoothing_gaussian_enabled);
733  ASSERT_EQ(filters.smoothing().gaussian().sigma().value(), cfg.processing_filters_smoothing_gaussian_sigma);
734  ASSERT_EQ(filters.outlier().removal().isEnabled().value(), cfg.processing_filters_outlier_removal_enabled);
735  ASSERT_EQ(filters.outlier().removal().threshold().value(), cfg.processing_filters_outlier_removal_threshold);
736  ASSERT_EQ(filters.reflection().removal().isEnabled().value(), cfg.processing_filters_reflection_removal_enabled);
737  }
738 
739  Zivid::CaptureAssistant::SuggestSettingsParameters::AmbientLightFrequency toAPIAmbientLightFrequency(
740  zivid_camera::CaptureAssistantSuggestSettings::Request::_ambient_light_frequency_type ambient_light_frequency)
741  {
742  using AmbientLightFrequency = Zivid::CaptureAssistant::SuggestSettingsParameters::AmbientLightFrequency;
743  using Request = zivid_camera::CaptureAssistantSuggestSettings::Request;
744  switch (ambient_light_frequency)
745  {
746  case Request::AMBIENT_LIGHT_FREQUENCY_NONE:
747  return AmbientLightFrequency::none;
748  case Request::AMBIENT_LIGHT_FREQUENCY_50HZ:
749  return AmbientLightFrequency::hz50;
750  case Request::AMBIENT_LIGHT_FREQUENCY_60HZ:
751  return AmbientLightFrequency::hz60;
752  }
753  throw std::runtime_error("Could not convert value " + std::to_string(ambient_light_frequency) + " to API enum.");
754  }
755 
757  ros::Duration max_capture_time,
758  zivid_camera::CaptureAssistantSuggestSettings::Request::_ambient_light_frequency_type ambient_light_frequency)
759  {
760  zivid_camera::CaptureAssistantSuggestSettings srv;
761  srv.request.max_capture_time = max_capture_time;
762  srv.request.ambient_light_frequency = ambient_light_frequency;
763  ASSERT_TRUE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
764  short_wait_duration.sleep();
765 
766  Zivid::CaptureAssistant::SuggestSettingsParameters suggest_settings_parameters{
767  Zivid::CaptureAssistant::SuggestSettingsParameters::MaxCaptureTime{
768  std::chrono::round<std::chrono::milliseconds>(SecondsD{ max_capture_time.toSec() }) },
769  toAPIAmbientLightFrequency(ambient_light_frequency)
770  };
771  const auto api_settings = Zivid::CaptureAssistant::suggestSettings(camera_, suggest_settings_parameters);
772  const auto& acquisitions = api_settings.acquisitions();
773 
774  ASSERT_EQ(acquisitions.size(), numEnabled3DAcquisitions());
775 
776  compareSettingsConfigWithSettings(api_settings, settingsConfig());
777  for (std::size_t i = 0; i < acquisitions.size(); i++)
778  {
779  compareSettingsAcquisitionConfigWithSettings(acquisitions[i], settingsAcquisitionConfig(i));
780  }
781  for (std::size_t i = acquisitions.size(); i < num_dr_capture_servers; i++)
782  {
783  ASSERT_EQ(false, settingsAcquisitionConfig(i).enabled);
784  }
785  }
786 
787 private:
788  dynamic_reconfigure::Client<zivid_camera::SettingsConfig> camera_settings_client_;
789  std::vector<std::unique_ptr<dynamic_reconfigure::Client<zivid_camera::SettingsAcquisitionConfig>>>
791 };
792 
793 TEST_F(ZividCATest, testCaptureAssistantServiceAvailable)
794 {
795  ASSERT_TRUE(ros::service::waitForService(capture_assistant_suggest_settings_service_name, short_wait_duration));
796 }
797 
798 TEST_F(ZividCATest, testDifferentMaxCaptureTimeAndAmbientLightFrequency)
799 {
800  using Request = zivid_camera::CaptureAssistantSuggestSettings::Request;
801  for (double max_capture_time : { 0.2, 1.2, 10.0 })
802  {
803  for (auto ambient_light_frequency : { Request::AMBIENT_LIGHT_FREQUENCY_NONE, Request::AMBIENT_LIGHT_FREQUENCY_50HZ,
804  Request::AMBIENT_LIGHT_FREQUENCY_60HZ })
805  {
806  performSuggestSettingsAndCompareWithCppAPI(ros::Duration{ max_capture_time }, ambient_light_frequency);
807  }
808  }
809 }
810 
811 TEST_F(ZividCATest, testGoingFromMultipleAcquisitionsTo1Acquisition)
812 {
813  using Request = zivid_camera::CaptureAssistantSuggestSettings::Request;
814  performSuggestSettingsAndCompareWithCppAPI(ros::Duration{ 10.0 }, Request::AMBIENT_LIGHT_FREQUENCY_NONE);
815  ASSERT_GT(numEnabled3DAcquisitions(), 1U);
816 
817  performSuggestSettingsAndCompareWithCppAPI(ros::Duration{ 0.2 }, Request::AMBIENT_LIGHT_FREQUENCY_NONE);
818  ASSERT_EQ(numEnabled3DAcquisitions(), 1U);
819 }
820 
821 TEST_F(ZividCATest, testCaptureAssistantWithInvalidMaxCaptureTimeFails)
822 {
823  zivid_camera::CaptureAssistantSuggestSettings srv;
824  srv.request.max_capture_time = ros::Duration{ 0.0 };
825  ASSERT_FALSE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
826 
827  const auto valid_range = Zivid::CaptureAssistant::SuggestSettingsParameters::MaxCaptureTime::validRange();
828  const auto small_delta = std::chrono::milliseconds{ 1 };
829  srv.request.max_capture_time = toRosDuration(valid_range.min() - small_delta);
830  ASSERT_FALSE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
831  srv.request.max_capture_time = toRosDuration(valid_range.max() + small_delta);
832  ASSERT_FALSE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
833 
834  srv.request.max_capture_time = toRosDuration(valid_range.max());
835  ASSERT_TRUE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
836 }
837 
838 TEST_F(ZividCATest, testCaptureAssistantDefaultAmbientLightFrequencyWorks)
839 {
840  zivid_camera::CaptureAssistantSuggestSettings srv;
841  srv.request.max_capture_time = ros::Duration{ 1.0 };
842  ASSERT_TRUE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
843 }
844 
845 TEST_F(ZividCATest, testCaptureAssistantInvalidAmbientLightFrequencyFails)
846 {
847  zivid_camera::CaptureAssistantSuggestSettings srv;
848  srv.request.max_capture_time = ros::Duration{ 1.0 };
849  srv.request.ambient_light_frequency = 255;
850  ASSERT_FALSE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
851 
852  srv.request.ambient_light_frequency =
853  zivid_camera::CaptureAssistantSuggestSettings::Request::AMBIENT_LIGHT_FREQUENCY_NONE;
854  ASSERT_TRUE(ros::service::call(capture_assistant_suggest_settings_service_name, srv));
855 }
856 
857 int main(int argc, char** argv)
858 {
859  testing::InitGoogleTest(&argc, argv);
860  ros::init(argc, argv, "test_zivid_camera");
861  ros::AsyncSpinner spinner(1);
862  spinner.start();
863 
864  ros::NodeHandle nh;
865  return RUN_ALL_TESTS();
866 }
d
zivid_camera::SettingsAcquisitionConfig settingsAcquisitionConfig(std::size_t i) const
const std::optional< Type > & lastMessage() const
void testAcquisitionMinMaxDefault(const std::string &prefix, std::size_t num_acquisition_servers)
TEST_F(ZividNodeTest, testServiceCameraInfoModelName)
void assertCameraInfoForFileCamera(const sensor_msgs::CameraInfo &ci) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
dynamic_reconfigure::Client< zivid_camera::SettingsConfig > camera_settings_client_
void compareSettingsConfigWithSettings(const Zivid::Settings &s, const zivid_camera::SettingsConfig &cfg) const
bool call(const std::string &service_name, MReq &req, MRes &res)
zivid_camera::SettingsConfig settingsConfig()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static SubscriptionWrapper< Type > make(ros::NodeHandle &nh, const std::string &name)
void testGeneralMinMaxDefault(const std::string &service_name)
void enableFirst2DAcquisition()
void assertSensorMsgsImageContents(const sensor_msgs::Image &image, const Zivid::Array2D< Zivid::ColorRGBA > &expected_rgba)
void assertArrayFloatEq(const A &actual, const B &expected) const
Zivid::Application zivid_
void assertSensorMsgsPointCloud2Meta(const sensor_msgs::PointCloud2 &point_cloud, std::size_t width, std::size_t height, std::size_t point_step)
void enableFirst3DAcquisition()
SubscriptionWrapper< Type > subscribe(const std::string &name)
std::chrono::duration< double > SecondsD
Zivid::Frame2D capture2DViaSDKDefaultSettings()
std::size_t numEnabled3DAcquisitions() const
ros::NodeHandle nh_
void enableFirst3DAcquisitionAndCapture()
Zivid::CaptureAssistant::SuggestSettingsParameters::AmbientLightFrequency toAPIAmbientLightFrequency(zivid_camera::CaptureAssistantSuggestSettings::Request::_ambient_light_frequency_type ambient_light_frequency)
int main(int argc, char **argv)
void compareSettingsAcquisitionConfigWithSettings(const Zivid::Settings::Acquisition &a, const zivid_camera::SettingsAcquisitionConfig &cfg) const
void performSuggestSettingsAndCompareWithCppAPI(ros::Duration max_capture_time, zivid_camera::CaptureAssistantSuggestSettings::Request::_ambient_light_frequency_type ambient_light_frequency)
Zivid::PointCloud captureViaSDKDefaultSettings()
void assertSensorMsgsImageMeta(const sensor_msgs::Image &image, std::size_t width, std::size_t height, std::size_t bytes_per_pixel, const std::string &encoding)
void comparePointCoordinate(float ros_coordinate, float sdk_coordinate) const
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
std::vector< std::unique_ptr< dynamic_reconfigure::Client< zivid_camera::SettingsAcquisitionConfig > > > settings_acquisition_clients_


zivid_camera
Author(s): Zivid
autogenerated on Sat Apr 17 2021 02:51:05