unit_test.cpp
Go to the documentation of this file.
1 /* $Id$ */
2 
3 /*********************************************************************
4 * Software License Agreement (BSD License)
5 *
6 * Copyright (c) 2010 Jack O'Quin
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the author nor other contributors may be
20 * used to endorse or promote products derived from this software
21 * without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *********************************************************************/
36 
37 #include <unistd.h>
38 #include <stdlib.h>
39 #include <ros/ros.h>
40 #include <ros/package.h>
43 #include <string>
44 #include <gtest/gtest.h>
45 
47 // global test data
49 
50 namespace
51 {
52  const std::string g_package_name("camera_info_manager");
53  const std::string g_test_name("test_calibration");
54  const std::string g_package_filename("/tests/" + g_test_name +".yaml");
55  const std::string g_package_url("package://" + g_package_name
56  + g_package_filename);
57  const std::string g_package_name_url("package://" + g_package_name
58  + "/tests/${NAME}.yaml");
59  const std::string g_default_url("file://${ROS_HOME}/camera_info/${NAME}.yaml");
60  const std::string g_camera_name("08144361026320a0");
61 }
62 
64 // utility functions
66 
67 // compare CameraInfo fields that are saved and loaded for calibration
68 void compare_calibration(const sensor_msgs::CameraInfo &exp,
69  const sensor_msgs::CameraInfo &ci)
70 {
71  // check image size
72  EXPECT_EQ(exp.width, ci.width);
73  EXPECT_EQ(exp.height, ci.height);
74 
75  // check distortion coefficients
76  EXPECT_EQ(exp.distortion_model, ci.distortion_model);
77  EXPECT_EQ(exp.D.size(), ci.D.size());
78  for (unsigned i = 0; i < ci.D.size(); ++i)
79  {
80  EXPECT_EQ(exp.D[i], ci.D[i]);
81  }
82 
83  // check camera matrix
84  for (unsigned i = 0; i < ci.K.size(); ++i)
85  {
86  EXPECT_EQ(exp.K[i], ci.K[i]);
87  }
88 
89  // check rectification matrix
90  for (unsigned i = 0; i < ci.R.size(); ++i)
91  {
92  EXPECT_EQ(exp.R[i], ci.R[i]);
93  }
94 
95  // check projection matrix
96  for (unsigned i = 0; i < ci.P.size(); ++i)
97  {
98  EXPECT_EQ(exp.P[i], ci.P[i]);
99  }
100 
101  // check binning
102  EXPECT_EQ(exp.binning_x, ci.binning_x);
103  EXPECT_EQ(exp.binning_y, ci.binning_y);
104 
105  // check region of interest
106  EXPECT_EQ(exp.roi.x_offset, ci.roi.x_offset);
107  EXPECT_EQ(exp.roi.y_offset, ci.roi.y_offset);
108  EXPECT_EQ(exp.roi.height, ci.roi.height);
109  EXPECT_EQ(exp.roi.width, ci.roi.width);
110  EXPECT_EQ(exp.roi.do_rectify, ci.roi.do_rectify);
111 }
112 
113 // make sure this file does not exist
114 void delete_file(std::string filename)
115 {
116  int rc = unlink(filename.c_str());
117  if (rc != 0)
118  {
119  if (errno != ENOENT)
120  ROS_INFO_STREAM("unexpected unlink() error: " << errno);
121  }
122 }
123 
125 {
126  std::string ros_home("/tmp");
127  setenv("ROS_HOME", ros_home.c_str(), true);
128  std::string tmpFile(ros_home + "/camera_info/camera.yaml");
129  delete_file(tmpFile);
130 }
131 
132 void do_system(const std::string &command)
133 {
134  int rc = system(command.c_str());
135  if (rc)
136  std::cout << command << " returns " << rc;
137 }
138 
140 {
141  do_system(std::string("rm -rf /tmp/camera_info"));
142 }
143 
145 {
146  do_system(std::string("mkdir -p /tmp/camera_info"));
147 }
148 
149 // These data must match the contents of test_calibration.yaml.
150 sensor_msgs::CameraInfo expected_calibration(void)
151 {
152  sensor_msgs::CameraInfo ci;
153 
154  ci.width = 640u;
155  ci.height = 480u;
156 
157  // set distortion coefficients
158  ci.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
159  ci.D.resize(5);
160  ci.D[0] = -1.04482;
161  ci.D[1] = 1.59252;
162  ci.D[2] = -0.0196308;
163  ci.D[3] = 0.0287906;
164  ci.D[4] = 0.0;
165 
166  // set camera matrix
167  ci.K[0] = 1168.68;
168  ci.K[1] = 0.0;
169  ci.K[2] = 295.015;
170  ci.K[3] = 0.0;
171  ci.K[4] = 1169.01;
172  ci.K[5] = 252.247;
173  ci.K[6] = 0.0;
174  ci.K[7] = 0.0;
175  ci.K[8] = 1.0;
176 
177  // set rectification matrix
178  ci.R[0] = 1.0;
179  ci.R[1] = 0.0;
180  ci.R[2] = 0.0;
181  ci.R[3] = 0.0;
182  ci.R[4] = 1.0;
183  ci.R[5] = 0.0;
184  ci.R[6] = 0.0;
185  ci.R[7] = 0.0;
186  ci.R[8] = 1.0;
187 
188  // set projection matrix
189  ci.P[0] = ci.K[0];
190  ci.P[1] = ci.K[1];
191  ci.P[2] = ci.K[2];
192  ci.P[3] = 0.0;
193  ci.P[4] = ci.K[3];
194  ci.P[5] = ci.K[4];
195  ci.P[6] = ci.K[5];
196  ci.P[7] = 0.0;
197  ci.P[8] = ci.K[6];
198  ci.P[9] = ci.K[7];
199  ci.P[10] = ci.K[8];
200  ci.P[11] = 0.0;
201 
202  ci.binning_x = 1;
203  ci.binning_y = 2;
204 
205  ci.roi.x_offset = 20;
206  ci.roi.y_offset = 40;
207  ci.roi.height = 400;
208  ci.roi.width = 600;
209 
210  return ci;
211 }
212 
213 // issue SetCameraInfo service request
215  const sensor_msgs::CameraInfo &calib)
216 {
217  ros::ServiceClient client =
218  node.serviceClient<sensor_msgs::SetCameraInfo>("set_camera_info");
219  sensor_msgs::SetCameraInfo set_camera_info;
220  set_camera_info.request.camera_info = calib;
221  bool success;
222  EXPECT_TRUE((success = client.call(set_camera_info)));
223  return success;
224 }
225 
226 // resolve URL string, result should be as expected
228  const std::string &url,
229  const std::string &exp_url,
230  const std::string &camera_name)
231 {
232  camera_info_manager::CameraInfoManager cinfo(node, camera_name, url);
233  std::string sub_url = cinfo.resolveURL(url, camera_name);
234  EXPECT_EQ(sub_url, exp_url);
235 }
236 
238 // Test cases
240 
241 // Test that valid camera names are accepted
242 TEST(CameraName, validNames)
243 {
244  ros::NodeHandle node;
246 
247  EXPECT_TRUE(cinfo.setCameraName(std::string("a")));
248  EXPECT_TRUE(cinfo.setCameraName(std::string("1")));
249  EXPECT_TRUE(cinfo.setCameraName(std::string("_")));
250  EXPECT_TRUE(cinfo.setCameraName(std::string("abcdefghijklmnopqrstuvwxyz")));
251  EXPECT_TRUE(cinfo.setCameraName(std::string("ABCDEFGHIJKLMNOPQRSTUVWXYZ")));
252  EXPECT_TRUE(cinfo.setCameraName(std::string("0123456789")));
253  EXPECT_TRUE(cinfo.setCameraName(std::string("0123456789abcdef")));
254  EXPECT_TRUE(cinfo.setCameraName(std::string("A1")));
255  EXPECT_TRUE(cinfo.setCameraName(std::string("9z")));
256  EXPECT_TRUE(cinfo.setCameraName(std::string("08144361026320a0_640x480_mono8")));
257 
258 }
259 
260 // Test that invalid camera names are rejected
261 TEST(CameraName, invalidNames)
262 {
263  ros::NodeHandle node;
265 
266  EXPECT_FALSE(cinfo.setCameraName(std::string("")));
267  EXPECT_FALSE(cinfo.setCameraName(std::string("-21")));
268  EXPECT_FALSE(cinfo.setCameraName(std::string("C++")));
269  EXPECT_FALSE(cinfo.setCameraName(std::string("file:///tmp/url.yaml")));
270  EXPECT_FALSE(cinfo.setCameraName(std::string("file://${INVALID}/xxx.yaml")));
271 }
272 
273 // Test that valid URLs are accepted
274 TEST(UrlValidation, validURLs)
275 {
276  ros::NodeHandle node;
278 
279  EXPECT_TRUE(cinfo.validateURL(std::string("")));
280  EXPECT_TRUE(cinfo.validateURL(std::string("file:///")));
281  EXPECT_TRUE(cinfo.validateURL(std::string("file:///tmp/url.yaml")));
282  EXPECT_TRUE(cinfo.validateURL(std::string("File:///tmp/url.ini")));
283  EXPECT_TRUE(cinfo.validateURL(std::string("FILE:///tmp/url.yaml")));
284  EXPECT_TRUE(cinfo.validateURL(g_default_url));
285  EXPECT_TRUE(cinfo.validateURL(g_package_url));
286  EXPECT_TRUE(cinfo.validateURL(std::string("package://no_such_package/calibration.yaml")));
287  EXPECT_TRUE(cinfo.validateURL(std::string("packAge://camera_info_manager/x")));
288 }
289 
290 // Test that invalid URLs are rejected
291 TEST(UrlValidation, invalidURLs)
292 {
293  ros::NodeHandle node;
295 
296  EXPECT_FALSE(cinfo.validateURL(std::string("file://")));
297  EXPECT_FALSE(cinfo.validateURL(std::string("flash:///")));
298  EXPECT_FALSE(cinfo.validateURL(std::string("html://ros.org/wiki/camera_info_manager")));
299  EXPECT_FALSE(cinfo.validateURL(std::string("package://")));
300  EXPECT_FALSE(cinfo.validateURL(std::string("package:///")));
301  EXPECT_FALSE(cinfo.validateURL(std::string("package://calibration.yaml")));
302  EXPECT_FALSE(cinfo.validateURL(std::string("package://camera_info_manager/")));
303 }
304 
305 // Test ability to provide uncalibrated CameraInfo
306 TEST(GetInfo, uncalibrated)
307 {
308  ros::NodeHandle node;
309 
311 
313  EXPECT_FALSE(cinfo.isCalibrated());
314 
315  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
316  sensor_msgs::CameraInfo exp;
317  compare_calibration(exp, ci);
318 }
319 
320 // Test ability to load calibrated CameraInfo
321 TEST(GetInfo, calibrated)
322 {
323  ros::NodeHandle node;
324 
326 
328  EXPECT_FALSE(cinfo.isCalibrated());
329 
330  std::string pkgPath(ros::package::getPath(g_package_name));
331  std::string url("file://" + pkgPath + "/tests/test_calibration.yaml");
332  EXPECT_TRUE(cinfo.loadCameraInfo(url));
333  EXPECT_TRUE(cinfo.isCalibrated());
334 
335  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
336  sensor_msgs::CameraInfo exp(expected_calibration());
337  compare_calibration(exp, ci);
338 }
339 
340 // Test ability to load calibrated CameraInfo from package
341 TEST(GetInfo, fromPackage)
342 {
343  ros::NodeHandle node;
345 
346  EXPECT_TRUE(cinfo.loadCameraInfo(g_package_url));
347  EXPECT_TRUE(cinfo.isCalibrated());
348 
349  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
350  sensor_msgs::CameraInfo exp(expected_calibration());
351  compare_calibration(exp, ci);
352 }
353 
354 // Test ability to access named calibrated CameraInfo from package
355 TEST(GetInfo, fromPackageWithName)
356 {
357  ros::NodeHandle node;
358  camera_info_manager::CameraInfoManager cinfo(node, g_test_name,
359  g_package_name_url);
360  EXPECT_TRUE(cinfo.isCalibrated());
361 
362  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
363  sensor_msgs::CameraInfo exp(expected_calibration());
364  compare_calibration(exp, ci);
365 }
366 
367 // Test load of unresolved "package:" URL files
368 TEST(GetInfo, unresolvedLoads)
369 {
370  ros::NodeHandle node;
372 
373  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://")));
374  EXPECT_FALSE(cinfo.isCalibrated());
375 
376  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package:///calibration.yaml")));
377  EXPECT_FALSE(cinfo.isCalibrated());
378 
379  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://no_such_package/calibration.yaml")));
380  EXPECT_FALSE(cinfo.isCalibrated());
381 
382  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://camera_info_manager/no_such_file.yaml")));
383  EXPECT_FALSE(cinfo.isCalibrated());
384 }
385 
386 // Test load of "package:" URL after changing name
387 TEST(GetInfo, nameChange)
388 {
389  ros::NodeHandle node;
390  const std::string missing_file("no_such_file");
391 
392  // first declare using non-existent camera name
393  camera_info_manager::CameraInfoManager cinfo(node, missing_file,
394  g_package_name_url);
395  EXPECT_FALSE(cinfo.isCalibrated());
396 
397  // set name so it resolves to a test file that does exist
398  EXPECT_TRUE(cinfo.setCameraName(g_test_name));
399  EXPECT_TRUE(cinfo.isCalibrated());
400  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
401  sensor_msgs::CameraInfo exp(expected_calibration());
402  compare_calibration(exp, ci);
403 }
404 
405 // Test load of invalid CameraInfo URLs
406 TEST(GetInfo, invalidLoads)
407 {
408  ros::NodeHandle node;
410 
411  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("flash:///")));
412  EXPECT_FALSE(cinfo.isCalibrated());
413 
414  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("html://ros.org/wiki/camera_info_manager")));
415  EXPECT_FALSE(cinfo.isCalibrated());
416 
417  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
418  sensor_msgs::CameraInfo exp;
419  compare_calibration(exp, ci);
420 }
421 
422 // Test ability to set CameraInfo directly
423 TEST(SetInfo, setCameraInfo)
424 {
425  ros::NodeHandle node;
427 
428  // issue calibration service request
429  sensor_msgs::CameraInfo exp(expected_calibration());
430  bool success = cinfo.setCameraInfo(exp);
431  EXPECT_TRUE(success);
432 
433  // only check results if the service succeeded, avoiding confusing
434  // and redundant failure messages
435  if (success)
436  {
437  // check that it worked
438  EXPECT_TRUE(cinfo.isCalibrated());
439  sensor_msgs::CameraInfo ci = cinfo.getCameraInfo();
440  compare_calibration(exp, ci);
441  }
442 }
443 
444 // Test ability to set calibrated CameraInfo
445 TEST(SetInfo, setCalibration)
446 {
447  ros::NodeHandle node;
449 
450  // issue calibration service request
451  sensor_msgs::CameraInfo exp(expected_calibration());
452  bool success = set_calibration(node, exp);
453 
454  // only check results if the service succeeded, avoiding confusing
455  // and redundant failure messages
456  if (success)
457  {
458  // check that it worked
459  EXPECT_TRUE(cinfo.isCalibrated());
460  sensor_msgs::CameraInfo ci = cinfo.getCameraInfo();
461  compare_calibration(exp, ci);
462  }
463 }
464 
465 // Test ability to save calibrated CameraInfo in default URL
466 TEST(SetInfo, saveCalibrationDefault)
467 {
468  ros::NodeHandle node;
469  sensor_msgs::CameraInfo exp(expected_calibration());
470  bool success;
471 
472  // Set ${ROS_HOME} to /tmp, then delete the /tmp/camera_info
473  // directory and everything in it.
474  setenv("ROS_HOME", "/tmp", true);
476 
477  {
478  // create instance to save calibrated data
480  EXPECT_FALSE(cinfo.isCalibrated());
481 
482  // issue calibration service request
483  success = set_calibration(node, exp);
484  EXPECT_TRUE(cinfo.isCalibrated());
485  }
486 
487  // only check results if the service succeeded, avoiding confusing
488  // and redundant failure messages
489  if (success)
490  {
491  // create a new instance to load saved calibration
493  EXPECT_TRUE(cinfo2.isCalibrated());
494  if (cinfo2.isCalibrated())
495  {
496  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
497  compare_calibration(exp, ci);
498  }
499  }
500 }
501 
502 // Test ability to save calibrated CameraInfo to default location with
503 // explicit camera name
504 TEST(SetInfo, saveCalibrationCameraName)
505 {
506  ros::NodeHandle node;
507  sensor_msgs::CameraInfo exp(expected_calibration());
508  bool success;
509 
510  // set ${ROS_HOME} to /tmp, delete the calibration file
511  std::string ros_home("/tmp");
512  setenv("ROS_HOME", ros_home.c_str(), true);
513  std::string tmpFile(ros_home + "/camera_info/" + g_camera_name + ".yaml");
514  delete_file(tmpFile);
515 
516  {
517  // create instance to save calibrated data
518  camera_info_manager::CameraInfoManager cinfo(node, g_camera_name);
519  success = set_calibration(node, exp);
520  EXPECT_TRUE(cinfo.isCalibrated());
521  }
522 
523  // only check results if the service succeeded, avoiding confusing
524  // and redundant failure messages
525  if (success)
526  {
527  // create a new instance to load saved calibration
529  std::string url = "file://" + tmpFile;
530  cinfo2.loadCameraInfo(std::string(url));
531  EXPECT_TRUE(cinfo2.isCalibrated());
532  if (cinfo2.isCalibrated())
533  {
534  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
535  compare_calibration(exp, ci);
536  }
537  }
538 }
539 
540 // Test ability to save calibrated CameraInfo in a file
541 TEST(SetInfo, saveCalibrationFile)
542 {
543  return;
544 
545  ros::NodeHandle node;
546  sensor_msgs::CameraInfo exp(expected_calibration());
547  std::string cname("camera");
548  std::string tmpFile("/tmp/camera_info_manager_calibration_test.yaml");
549  std::string url = "file://" + tmpFile;
550  bool success;
551 
552  // first, delete the file
553  delete_file(tmpFile);
554 
555  {
556  // create instance to save calibrated data
557  camera_info_manager::CameraInfoManager cinfo(node, cname, url);
558  success = set_calibration(node, exp);
559  EXPECT_TRUE(cinfo.isCalibrated());
560  }
561 
562  // only check results if the service succeeded, avoiding confusing
563  // and redundant failure messages
564  if (success)
565  {
566  // create a new instance to load saved calibration
567  camera_info_manager::CameraInfoManager cinfo2(node, cname, url);
568  EXPECT_TRUE(cinfo2.isCalibrated());
569  if (cinfo2.isCalibrated())
570  {
571  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
572  compare_calibration(exp, ci);
573  }
574  }
575 }
576 
577 // Test ability to save calibrated CameraInfo in a package
578 // (needs write access).
579 TEST(SetInfo, saveCalibrationPackage)
580 {
581  ros::NodeHandle node;
582  sensor_msgs::CameraInfo exp(expected_calibration());
583  std::string pkgPath(ros::package::getPath(g_package_name));
584  std::string filename(pkgPath + g_package_filename);
585  bool success;
586 
587  // first, delete the file
588  delete_file(filename);
589 
590  {
591  // create instance to save calibrated data
592  camera_info_manager::CameraInfoManager cinfo(node, g_camera_name,
593  g_package_url);
594  success = set_calibration(node, exp);
595  EXPECT_TRUE(cinfo.isCalibrated());
596  }
597 
598  // only check results if the service succeeded, avoiding confusing
599  // and redundant failure messages
600  if (success)
601  {
602  // create a new instance to load saved calibration
603  camera_info_manager::CameraInfoManager cinfo2(node, g_camera_name,
604  g_package_url);
605  EXPECT_TRUE(cinfo2.isCalibrated());
606  if (cinfo2.isCalibrated())
607  {
608  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
609  compare_calibration(exp, ci);
610  }
611  }
612 }
613 
614 TEST(UrlSubstitution, cameraName)
615 {
616  ros::NodeHandle node;
617  std::string name_url;
618  std::string exp_url;
619 
620  // resolve a GUID camera name
621  name_url = "package://" + g_package_name + "/tests/${NAME}.yaml";
622  exp_url = "package://" + g_package_name + "/tests/" + g_camera_name + ".yaml";
623  check_url_substitution(node, name_url, exp_url, g_camera_name);
624 
625  // substitute camera name "test"
626  name_url = "package://" + g_package_name + "/tests/${NAME}_calibration.yaml";
627  std::string test_name("test");
628  exp_url = "package://" + g_package_name + "/tests/" + test_name
629  + "_calibration.yaml";
630  check_url_substitution(node, name_url, exp_url, test_name);
631 
632  // with an '_' in the name
633  test_name = "camera_1024x768";
634  exp_url = "package://" + g_package_name + "/tests/" + test_name
635  + "_calibration.yaml";
636  check_url_substitution(node, name_url, exp_url, test_name);
637 
638  // substitute empty camera name
639  name_url = "package://" + g_package_name + "/tests/${NAME}_calibration.yaml";
640  std::string empty_name("");
641  exp_url = "package://" + g_package_name + "/tests/" + empty_name
642  + "_calibration.yaml";
643  check_url_substitution(node, name_url, exp_url, empty_name);
644 
645  // substitute test camera calibration from this package
646  check_url_substitution(node, g_package_name_url, g_package_url, g_test_name);
647 }
648 
649 TEST(UrlSubstitution, rosHome)
650 {
651  ros::NodeHandle node;
652  std::string name_url;
653  std::string exp_url;
654  char *home_env = getenv("HOME");
655  std::string home(home_env);
656 
657  // resolve ${ROS_HOME} with environment variable undefined
658  unsetenv("ROS_HOME");
659  name_url = "file://${ROS_HOME}/camera_info/test_camera.yaml";
660  exp_url = "file://" + home + "/.ros/camera_info/test_camera.yaml";
661  check_url_substitution(node, name_url, exp_url, g_camera_name);
662 
663  // resolve ${ROS_HOME} with environment variable defined
664  setenv("ROS_HOME", "/my/ros/home", true);
665  name_url = "file://${ROS_HOME}/camera_info/test_camera.yaml";
666  exp_url = "file:///my/ros/home/camera_info/test_camera.yaml";
667  check_url_substitution(node, name_url, exp_url, g_camera_name);
668 }
669 
670 TEST(UrlSubstitution, unmatchedDollarSigns)
671 {
672  ros::NodeHandle node;
673 
674  // test for "$$" in the URL (NAME should be resolved)
675  std::string name_url("file:///tmp/$${NAME}.yaml");
676  std::string exp_url("file:///tmp/$" + g_camera_name + ".yaml");
677  check_url_substitution(node, name_url, exp_url, g_camera_name);
678 
679  // test for "$" in middle of string
680  name_url = "file:///$whatever.yaml";
681  check_url_substitution(node, name_url, name_url, g_camera_name);
682 
683  // test for "$$" in middle of string
684  name_url = "file:///something$$whatever.yaml";
685  check_url_substitution(node, name_url, name_url, g_camera_name);
686 
687  // test for "$$" at end of string
688  name_url = "file:///$$";
689  check_url_substitution(node, name_url, name_url, g_camera_name);
690 }
691 
692 TEST(UrlSubstitution, emptyURL)
693 {
694  // test that empty URL is handled correctly
695  ros::NodeHandle node;
696  std::string empty_url("");
697  check_url_substitution(node, empty_url, empty_url, g_camera_name);
698 }
699 
700 TEST(UrlSubstitution, invalidVariables)
701 {
702  ros::NodeHandle node;
703  std::string name_url;
704 
705  // missing "{...}"
706  name_url = "file:///tmp/$NAME.yaml";
707  check_url_substitution(node, name_url, name_url, g_camera_name);
708 
709  // invalid substitution variable name
710  name_url = "file:///tmp/${INVALID}/calibration.yaml";
711  check_url_substitution(node, name_url, name_url, g_camera_name);
712 
713  // truncated substitution variable
714  name_url = "file:///tmp/${NAME";
715  check_url_substitution(node, name_url, name_url, g_camera_name);
716 
717  // missing substitution variable
718  name_url = "file:///tmp/${}";
719  check_url_substitution(node, name_url, name_url, g_camera_name);
720 
721  // no exception thrown for single "$" at end of string
722  name_url = "file:///$";
723  check_url_substitution(node, name_url, name_url, g_camera_name);
724 }
725 
726 // Run all the tests that were declared with TEST()
727 int main(int argc, char **argv)
728 {
729  ros::init(argc, argv, "camera_info_manager_unit_test");
730  testing::InitGoogleTest(&argc, argv);
731 
732  // create asynchronous thread for handling service requests
733  ros::AsyncSpinner spinner(1);
734  spinner.start();
735 
736  // run the tests in this thread
737  return RUN_ALL_TESTS();
738 }
check_url_substitution
void check_url_substitution(ros::NodeHandle node, const std::string &url, const std::string &exp_url, const std::string &camera_name)
Definition: unit_test.cpp:227
camera_info_manager::CameraInfoManager::getCameraInfo
virtual sensor_msgs::CameraInfo getCameraInfo(void)
Definition: camera_info_manager.cpp:115
do_system
void do_system(const std::string &command)
Definition: unit_test.cpp:132
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
delete_tmp_camera_info_directory
void delete_tmp_camera_info_directory(void)
Definition: unit_test.cpp:139
distortion_models.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
make_tmp_camera_info_directory
void make_tmp_camera_info_directory(void)
Definition: unit_test.cpp:144
ros::AsyncSpinner::start
void start()
ros.h
command
ROSLIB_DECL std::string command(const std::string &cmd)
set_calibration
bool set_calibration(ros::NodeHandle node, const sensor_msgs::CameraInfo &calib)
Definition: unit_test.cpp:214
ros::AsyncSpinner
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
camera_info_manager::CameraInfoManager::loadCameraInfo
virtual bool loadCameraInfo(const std::string &url)
Definition: camera_info_manager.cpp:325
TEST
TEST(CameraName, validNames)
Definition: unit_test.cpp:242
delete_file
void delete_file(std::string filename)
Definition: unit_test.cpp:114
main
int main(int argc, char **argv)
Definition: unit_test.cpp:727
expected_calibration
sensor_msgs::CameraInfo expected_calibration(void)
Definition: unit_test.cpp:150
camera_info_manager::CameraInfoManager::isCalibrated
virtual bool isCalibrated(void)
Definition: camera_info_manager.cpp:182
ros::ServiceClient
camera_info_manager::CameraInfoManager
CameraInfo Manager class.
Definition: camera_info_manager.h:188
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
package.h
camera_info_manager::CameraInfoManager::setCameraInfo
virtual bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
Definition: camera_info_manager.cpp:657
camera_info_manager::CameraInfoManager::validateURL
virtual bool validateURL(const std::string &url)
Definition: camera_info_manager.cpp:674
delete_default_file
void delete_default_file(void)
Definition: unit_test.cpp:124
camera_info_manager.h
CameraInfo Manager interface.
camera_info_manager::CameraInfoManager::setCameraName
virtual bool setCameraName(const std::string &cname)
Definition: camera_info_manager.cpp:624
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
compare_calibration
void compare_calibration(const sensor_msgs::CameraInfo &exp, const sensor_msgs::CameraInfo &ci)
Definition: unit_test.cpp:68
sensor_msgs::distortion_models::PLUMB_BOB
const std::string PLUMB_BOB
camera_info_manager::CameraInfoManager::resolveURL
virtual std::string resolveURL(const std::string &url, const std::string &cname)
Definition: camera_info_manager.cpp:348
ros::NodeHandle


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Sat Jan 20 2024 03:14:54