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 
102 // make sure this file does not exist
103 void delete_file(std::string filename)
104 {
105  int rc = unlink(filename.c_str());
106  if (rc != 0)
107  {
108  if (errno != ENOENT)
109  ROS_INFO_STREAM("unexpected unlink() error: " << errno);
110  }
111 }
112 
114 {
115  std::string ros_home("/tmp");
116  setenv("ROS_HOME", ros_home.c_str(), true);
117  std::string tmpFile(ros_home + "/camera_info/camera.yaml");
118  delete_file(tmpFile);
119 }
120 
121 void do_system(const std::string &command)
122 {
123  int rc = system(command.c_str());
124  if (rc)
125  std::cout << command << " returns " << rc;
126 }
127 
129 {
130  do_system(std::string("rm -rf /tmp/camera_info"));
131 }
132 
134 {
135  do_system(std::string("mkdir -p /tmp/camera_info"));
136 }
137 
138 // These data must match the contents of test_calibration.yaml.
139 sensor_msgs::CameraInfo expected_calibration(void)
140 {
141  sensor_msgs::CameraInfo ci;
142 
143  ci.width = 640u;
144  ci.height = 480u;
145 
146  // set distortion coefficients
147  ci.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
148  ci.D.resize(5);
149  ci.D[0] = -1.04482;
150  ci.D[1] = 1.59252;
151  ci.D[2] = -0.0196308;
152  ci.D[3] = 0.0287906;
153  ci.D[4] = 0.0;
154 
155  // set camera matrix
156  ci.K[0] = 1168.68;
157  ci.K[1] = 0.0;
158  ci.K[2] = 295.015;
159  ci.K[3] = 0.0;
160  ci.K[4] = 1169.01;
161  ci.K[5] = 252.247;
162  ci.K[6] = 0.0;
163  ci.K[7] = 0.0;
164  ci.K[8] = 1.0;
165 
166  // set rectification matrix
167  ci.R[0] = 1.0;
168  ci.R[1] = 0.0;
169  ci.R[2] = 0.0;
170  ci.R[3] = 0.0;
171  ci.R[4] = 1.0;
172  ci.R[5] = 0.0;
173  ci.R[6] = 0.0;
174  ci.R[7] = 0.0;
175  ci.R[8] = 1.0;
176 
177  // set projection matrix
178  ci.P[0] = ci.K[0];
179  ci.P[1] = ci.K[1];
180  ci.P[2] = ci.K[2];
181  ci.P[3] = 0.0;
182  ci.P[4] = ci.K[3];
183  ci.P[5] = ci.K[4];
184  ci.P[6] = ci.K[5];
185  ci.P[7] = 0.0;
186  ci.P[8] = ci.K[6];
187  ci.P[9] = ci.K[7];
188  ci.P[10] = ci.K[8];
189  ci.P[11] = 0.0;
190 
191  return ci;
192 }
193 
194 // issue SetCameraInfo service request
196  const sensor_msgs::CameraInfo &calib)
197 {
198  ros::ServiceClient client =
199  node.serviceClient<sensor_msgs::SetCameraInfo>("set_camera_info");
200  sensor_msgs::SetCameraInfo set_camera_info;
201  set_camera_info.request.camera_info = calib;
202  bool success;
203  EXPECT_TRUE((success = client.call(set_camera_info)));
204  return success;
205 }
206 
207 // resolve URL string, result should be as expected
209  const std::string &url,
210  const std::string &exp_url,
211  const std::string &camera_name)
212 {
213  camera_info_manager::CameraInfoManager cinfo(node, camera_name, url);
214  std::string sub_url = cinfo.resolveURL(url, camera_name);
215  EXPECT_EQ(sub_url, exp_url);
216 }
217 
219 // Test cases
221 
222 // Test that valid camera names are accepted
223 TEST(CameraName, validNames)
224 {
225  ros::NodeHandle node;
227 
228  EXPECT_TRUE(cinfo.setCameraName(std::string("a")));
229  EXPECT_TRUE(cinfo.setCameraName(std::string("1")));
230  EXPECT_TRUE(cinfo.setCameraName(std::string("_")));
231  EXPECT_TRUE(cinfo.setCameraName(std::string("abcdefghijklmnopqrstuvwxyz")));
232  EXPECT_TRUE(cinfo.setCameraName(std::string("ABCDEFGHIJKLMNOPQRSTUVWXYZ")));
233  EXPECT_TRUE(cinfo.setCameraName(std::string("0123456789")));
234  EXPECT_TRUE(cinfo.setCameraName(std::string("0123456789abcdef")));
235  EXPECT_TRUE(cinfo.setCameraName(std::string("A1")));
236  EXPECT_TRUE(cinfo.setCameraName(std::string("9z")));
237  EXPECT_TRUE(cinfo.setCameraName(std::string("08144361026320a0_640x480_mono8")));
238 
239 }
240 
241 // Test that invalid camera names are rejected
242 TEST(CameraName, invalidNames)
243 {
244  ros::NodeHandle node;
246 
247  EXPECT_FALSE(cinfo.setCameraName(std::string("")));
248  EXPECT_FALSE(cinfo.setCameraName(std::string("-21")));
249  EXPECT_FALSE(cinfo.setCameraName(std::string("C++")));
250  EXPECT_FALSE(cinfo.setCameraName(std::string("file:///tmp/url.yaml")));
251  EXPECT_FALSE(cinfo.setCameraName(std::string("file://${INVALID}/xxx.yaml")));
252 }
253 
254 // Test that valid URLs are accepted
255 TEST(UrlValidation, validURLs)
256 {
257  ros::NodeHandle node;
259 
260  EXPECT_TRUE(cinfo.validateURL(std::string("")));
261  EXPECT_TRUE(cinfo.validateURL(std::string("file:///")));
262  EXPECT_TRUE(cinfo.validateURL(std::string("file:///tmp/url.yaml")));
263  EXPECT_TRUE(cinfo.validateURL(std::string("File:///tmp/url.ini")));
264  EXPECT_TRUE(cinfo.validateURL(std::string("FILE:///tmp/url.yaml")));
265  EXPECT_TRUE(cinfo.validateURL(g_default_url));
266  EXPECT_TRUE(cinfo.validateURL(g_package_url));
267  EXPECT_TRUE(cinfo.validateURL(std::string("package://no_such_package/calibration.yaml")));
268  EXPECT_TRUE(cinfo.validateURL(std::string("packAge://camera_info_manager/x")));
269 }
270 
271 // Test that invalid URLs are rejected
272 TEST(UrlValidation, invalidURLs)
273 {
274  ros::NodeHandle node;
276 
277  EXPECT_FALSE(cinfo.validateURL(std::string("file://")));
278  EXPECT_FALSE(cinfo.validateURL(std::string("flash:///")));
279  EXPECT_FALSE(cinfo.validateURL(std::string("html://ros.org/wiki/camera_info_manager")));
280  EXPECT_FALSE(cinfo.validateURL(std::string("package://")));
281  EXPECT_FALSE(cinfo.validateURL(std::string("package:///")));
282  EXPECT_FALSE(cinfo.validateURL(std::string("package://calibration.yaml")));
283  EXPECT_FALSE(cinfo.validateURL(std::string("package://camera_info_manager/")));
284 }
285 
286 // Test ability to provide uncalibrated CameraInfo
287 TEST(GetInfo, uncalibrated)
288 {
289  ros::NodeHandle node;
290 
292 
294  EXPECT_FALSE(cinfo.isCalibrated());
295 
296  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
297  sensor_msgs::CameraInfo exp;
298  compare_calibration(exp, ci);
299 }
300 
301 // Test ability to load calibrated CameraInfo
302 TEST(GetInfo, calibrated)
303 {
304  ros::NodeHandle node;
305 
307 
309  EXPECT_FALSE(cinfo.isCalibrated());
310 
311  std::string pkgPath(ros::package::getPath(g_package_name));
312  std::string url("file://" + pkgPath + "/tests/test_calibration.yaml");
313  EXPECT_TRUE(cinfo.loadCameraInfo(url));
314  EXPECT_TRUE(cinfo.isCalibrated());
315 
316  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
317  sensor_msgs::CameraInfo exp(expected_calibration());
318  compare_calibration(exp, ci);
319 }
320 
321 // Test ability to load calibrated CameraInfo from package
322 TEST(GetInfo, fromPackage)
323 {
324  ros::NodeHandle node;
326 
327  EXPECT_TRUE(cinfo.loadCameraInfo(g_package_url));
328  EXPECT_TRUE(cinfo.isCalibrated());
329 
330  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
331  sensor_msgs::CameraInfo exp(expected_calibration());
332  compare_calibration(exp, ci);
333 }
334 
335 // Test ability to access named calibrated CameraInfo from package
336 TEST(GetInfo, fromPackageWithName)
337 {
338  ros::NodeHandle node;
339  camera_info_manager::CameraInfoManager cinfo(node, g_test_name,
340  g_package_name_url);
341  EXPECT_TRUE(cinfo.isCalibrated());
342 
343  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
344  sensor_msgs::CameraInfo exp(expected_calibration());
345  compare_calibration(exp, ci);
346 }
347 
348 // Test load of unresolved "package:" URL files
349 TEST(GetInfo, unresolvedLoads)
350 {
351  ros::NodeHandle node;
353 
354  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://")));
355  EXPECT_FALSE(cinfo.isCalibrated());
356 
357  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package:///calibration.yaml")));
358  EXPECT_FALSE(cinfo.isCalibrated());
359 
360  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://no_such_package/calibration.yaml")));
361  EXPECT_FALSE(cinfo.isCalibrated());
362 
363  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://camera_info_manager/no_such_file.yaml")));
364  EXPECT_FALSE(cinfo.isCalibrated());
365 }
366 
367 // Test load of "package:" URL after changing name
368 TEST(GetInfo, nameChange)
369 {
370  ros::NodeHandle node;
371  const std::string missing_file("no_such_file");
372 
373  // first declare using non-existent camera name
374  camera_info_manager::CameraInfoManager cinfo(node, missing_file,
375  g_package_name_url);
376  EXPECT_FALSE(cinfo.isCalibrated());
377 
378  // set name so it resolves to a test file that does exist
379  EXPECT_TRUE(cinfo.setCameraName(g_test_name));
380  EXPECT_TRUE(cinfo.isCalibrated());
381  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
382  sensor_msgs::CameraInfo exp(expected_calibration());
383  compare_calibration(exp, ci);
384 }
385 
386 // Test load of invalid CameraInfo URLs
387 TEST(GetInfo, invalidLoads)
388 {
389  ros::NodeHandle node;
391 
392  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("flash:///")));
393  EXPECT_FALSE(cinfo.isCalibrated());
394 
395  EXPECT_FALSE(cinfo.loadCameraInfo(std::string("html://ros.org/wiki/camera_info_manager")));
396  EXPECT_FALSE(cinfo.isCalibrated());
397 
398  sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
399  sensor_msgs::CameraInfo exp;
400  compare_calibration(exp, ci);
401 }
402 
403 // Test ability to set CameraInfo directly
404 TEST(SetInfo, setCameraInfo)
405 {
406  ros::NodeHandle node;
408 
409  // issue calibration service request
410  sensor_msgs::CameraInfo exp(expected_calibration());
411  bool success = cinfo.setCameraInfo(exp);
412  EXPECT_TRUE(success);
413 
414  // only check results if the service succeeded, avoiding confusing
415  // and redundant failure messages
416  if (success)
417  {
418  // check that it worked
419  EXPECT_TRUE(cinfo.isCalibrated());
420  sensor_msgs::CameraInfo ci = cinfo.getCameraInfo();
421  compare_calibration(exp, ci);
422  }
423 }
424 
425 // Test ability to set calibrated CameraInfo
426 TEST(SetInfo, setCalibration)
427 {
428  ros::NodeHandle node;
430 
431  // issue calibration service request
432  sensor_msgs::CameraInfo exp(expected_calibration());
433  bool success = set_calibration(node, exp);
434 
435  // only check results if the service succeeded, avoiding confusing
436  // and redundant failure messages
437  if (success)
438  {
439  // check that it worked
440  EXPECT_TRUE(cinfo.isCalibrated());
441  sensor_msgs::CameraInfo ci = cinfo.getCameraInfo();
442  compare_calibration(exp, ci);
443  }
444 }
445 
446 // Test ability to save calibrated CameraInfo in default URL
447 TEST(SetInfo, saveCalibrationDefault)
448 {
449  ros::NodeHandle node;
450  sensor_msgs::CameraInfo exp(expected_calibration());
451  bool success;
452 
453  // Set ${ROS_HOME} to /tmp, then delete the /tmp/camera_info
454  // directory and everything in it.
455  setenv("ROS_HOME", "/tmp", true);
457 
458  {
459  // create instance to save calibrated data
461  EXPECT_FALSE(cinfo.isCalibrated());
462 
463  // issue calibration service request
464  success = set_calibration(node, exp);
465  EXPECT_TRUE(cinfo.isCalibrated());
466  }
467 
468  // only check results if the service succeeded, avoiding confusing
469  // and redundant failure messages
470  if (success)
471  {
472  // create a new instance to load saved calibration
474  EXPECT_TRUE(cinfo2.isCalibrated());
475  if (cinfo2.isCalibrated())
476  {
477  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
478  compare_calibration(exp, ci);
479  }
480  }
481 }
482 
483 // Test ability to save calibrated CameraInfo to default location with
484 // explicit camera name
485 TEST(SetInfo, saveCalibrationCameraName)
486 {
487  ros::NodeHandle node;
488  sensor_msgs::CameraInfo exp(expected_calibration());
489  bool success;
490 
491  // set ${ROS_HOME} to /tmp, delete the calibration file
492  std::string ros_home("/tmp");
493  setenv("ROS_HOME", ros_home.c_str(), true);
494  std::string tmpFile(ros_home + "/camera_info/" + g_camera_name + ".yaml");
495  delete_file(tmpFile);
496 
497  {
498  // create instance to save calibrated data
499  camera_info_manager::CameraInfoManager cinfo(node, g_camera_name);
500  success = set_calibration(node, exp);
501  EXPECT_TRUE(cinfo.isCalibrated());
502  }
503 
504  // only check results if the service succeeded, avoiding confusing
505  // and redundant failure messages
506  if (success)
507  {
508  // create a new instance to load saved calibration
510  std::string url = "file://" + tmpFile;
511  cinfo2.loadCameraInfo(std::string(url));
512  EXPECT_TRUE(cinfo2.isCalibrated());
513  if (cinfo2.isCalibrated())
514  {
515  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
516  compare_calibration(exp, ci);
517  }
518  }
519 }
520 
521 // Test ability to save calibrated CameraInfo in a file
522 TEST(SetInfo, saveCalibrationFile)
523 {
524  return;
525 
526  ros::NodeHandle node;
527  sensor_msgs::CameraInfo exp(expected_calibration());
528  std::string cname("camera");
529  std::string tmpFile("/tmp/camera_info_manager_calibration_test.yaml");
530  std::string url = "file://" + tmpFile;
531  bool success;
532 
533  // first, delete the file
534  delete_file(tmpFile);
535 
536  {
537  // create instance to save calibrated data
538  camera_info_manager::CameraInfoManager cinfo(node, cname, url);
539  success = set_calibration(node, exp);
540  EXPECT_TRUE(cinfo.isCalibrated());
541  }
542 
543  // only check results if the service succeeded, avoiding confusing
544  // and redundant failure messages
545  if (success)
546  {
547  // create a new instance to load saved calibration
548  camera_info_manager::CameraInfoManager cinfo2(node, cname, url);
549  EXPECT_TRUE(cinfo2.isCalibrated());
550  if (cinfo2.isCalibrated())
551  {
552  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
553  compare_calibration(exp, ci);
554  }
555  }
556 }
557 
558 // Test ability to save calibrated CameraInfo in a package
559 // (needs write access).
560 TEST(SetInfo, saveCalibrationPackage)
561 {
562  ros::NodeHandle node;
563  sensor_msgs::CameraInfo exp(expected_calibration());
564  std::string pkgPath(ros::package::getPath(g_package_name));
565  std::string filename(pkgPath + g_package_filename);
566  bool success;
567 
568  // first, delete the file
569  delete_file(filename);
570 
571  {
572  // create instance to save calibrated data
573  camera_info_manager::CameraInfoManager cinfo(node, g_camera_name,
574  g_package_url);
575  success = set_calibration(node, exp);
576  EXPECT_TRUE(cinfo.isCalibrated());
577  }
578 
579  // only check results if the service succeeded, avoiding confusing
580  // and redundant failure messages
581  if (success)
582  {
583  // create a new instance to load saved calibration
584  camera_info_manager::CameraInfoManager cinfo2(node, g_camera_name,
585  g_package_url);
586  EXPECT_TRUE(cinfo2.isCalibrated());
587  if (cinfo2.isCalibrated())
588  {
589  sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
590  compare_calibration(exp, ci);
591  }
592  }
593 }
594 
595 TEST(UrlSubstitution, cameraName)
596 {
597  ros::NodeHandle node;
598  std::string name_url;
599  std::string exp_url;
600 
601  // resolve a GUID camera name
602  name_url = "package://" + g_package_name + "/tests/${NAME}.yaml";
603  exp_url = "package://" + g_package_name + "/tests/" + g_camera_name + ".yaml";
604  check_url_substitution(node, name_url, exp_url, g_camera_name);
605 
606  // substitute camera name "test"
607  name_url = "package://" + g_package_name + "/tests/${NAME}_calibration.yaml";
608  std::string test_name("test");
609  exp_url = "package://" + g_package_name + "/tests/" + test_name
610  + "_calibration.yaml";
611  check_url_substitution(node, name_url, exp_url, test_name);
612 
613  // with an '_' in the name
614  test_name = "camera_1024x768";
615  exp_url = "package://" + g_package_name + "/tests/" + test_name
616  + "_calibration.yaml";
617  check_url_substitution(node, name_url, exp_url, test_name);
618 
619  // substitute empty camera name
620  name_url = "package://" + g_package_name + "/tests/${NAME}_calibration.yaml";
621  std::string empty_name("");
622  exp_url = "package://" + g_package_name + "/tests/" + empty_name
623  + "_calibration.yaml";
624  check_url_substitution(node, name_url, exp_url, empty_name);
625 
626  // substitute test camera calibration from this package
627  check_url_substitution(node, g_package_name_url, g_package_url, g_test_name);
628 }
629 
630 TEST(UrlSubstitution, rosHome)
631 {
632  ros::NodeHandle node;
633  std::string name_url;
634  std::string exp_url;
635  char *home_env = getenv("HOME");
636  std::string home(home_env);
637 
638  // resolve ${ROS_HOME} with environment variable undefined
639  unsetenv("ROS_HOME");
640  name_url = "file://${ROS_HOME}/camera_info/test_camera.yaml";
641  exp_url = "file://" + home + "/.ros/camera_info/test_camera.yaml";
642  check_url_substitution(node, name_url, exp_url, g_camera_name);
643 
644  // resolve ${ROS_HOME} with environment variable defined
645  setenv("ROS_HOME", "/my/ros/home", true);
646  name_url = "file://${ROS_HOME}/camera_info/test_camera.yaml";
647  exp_url = "file:///my/ros/home/camera_info/test_camera.yaml";
648  check_url_substitution(node, name_url, exp_url, g_camera_name);
649 }
650 
651 TEST(UrlSubstitution, unmatchedDollarSigns)
652 {
653  ros::NodeHandle node;
654 
655  // test for "$$" in the URL (NAME should be resolved)
656  std::string name_url("file:///tmp/$${NAME}.yaml");
657  std::string exp_url("file:///tmp/$" + g_camera_name + ".yaml");
658  check_url_substitution(node, name_url, exp_url, g_camera_name);
659 
660  // test for "$" in middle of string
661  name_url = "file:///$whatever.yaml";
662  check_url_substitution(node, name_url, name_url, g_camera_name);
663 
664  // test for "$$" in middle of string
665  name_url = "file:///something$$whatever.yaml";
666  check_url_substitution(node, name_url, name_url, g_camera_name);
667 
668  // test for "$$" at end of string
669  name_url = "file:///$$";
670  check_url_substitution(node, name_url, name_url, g_camera_name);
671 }
672 
673 TEST(UrlSubstitution, emptyURL)
674 {
675  // test that empty URL is handled correctly
676  ros::NodeHandle node;
677  std::string empty_url("");
678  check_url_substitution(node, empty_url, empty_url, g_camera_name);
679 }
680 
681 TEST(UrlSubstitution, invalidVariables)
682 {
683  ros::NodeHandle node;
684  std::string name_url;
685 
686  // missing "{...}"
687  name_url = "file:///tmp/$NAME.yaml";
688  check_url_substitution(node, name_url, name_url, g_camera_name);
689 
690  // invalid substitution variable name
691  name_url = "file:///tmp/${INVALID}/calibration.yaml";
692  check_url_substitution(node, name_url, name_url, g_camera_name);
693 
694  // truncated substitution variable
695  name_url = "file:///tmp/${NAME";
696  check_url_substitution(node, name_url, name_url, g_camera_name);
697 
698  // missing substitution variable
699  name_url = "file:///tmp/${}";
700  check_url_substitution(node, name_url, name_url, g_camera_name);
701 
702  // no exception thrown for single "$" at end of string
703  name_url = "file:///$";
704  check_url_substitution(node, name_url, name_url, g_camera_name);
705 }
706 
707 // Run all the tests that were declared with TEST()
708 int main(int argc, char **argv)
709 {
710  ros::init(argc, argv, "camera_info_manager_unit_test");
711  testing::InitGoogleTest(&argc, argv);
712 
713  // create asynchronous thread for handling service requests
714  ros::AsyncSpinner spinner(1);
715  spinner.start();
716 
717  // run the tests in this thread
718  return RUN_ALL_TESTS();
719 }
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:208
void delete_tmp_camera_info_directory(void)
Definition: unit_test.cpp:128
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
bool set_calibration(ros::NodeHandle node, const sensor_msgs::CameraInfo &calib)
Definition: unit_test.cpp:195
void make_tmp_camera_info_directory(void)
Definition: unit_test.cpp:133
sensor_msgs::CameraInfo getCameraInfo(void)
void do_system(const std::string &command)
Definition: unit_test.cpp:121
bool loadCameraInfo(const std::string &url)
sensor_msgs::CameraInfo expected_calibration(void)
Definition: unit_test.cpp:139
std::string resolveURL(const std::string &url, const std::string &cname)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
int main(int argc, char **argv)
Definition: unit_test.cpp:708
CameraInfo Manager interface.
void delete_file(std::string filename)
Definition: unit_test.cpp:103
TEST(CameraName, validNames)
Definition: unit_test.cpp:223
bool validateURL(const std::string &url)
ROSLIB_DECL std::string getPath(const std::string &package_name)
void delete_default_file(void)
Definition: unit_test.cpp:113
#define ROS_INFO_STREAM(args)
bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
void compare_calibration(const sensor_msgs::CameraInfo &exp, const sensor_msgs::CameraInfo &ci)
Definition: unit_test.cpp:68
bool setCameraName(const std::string &cname)


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Thu Jun 6 2019 19:22:55