unit_test.cpp
Go to the documentation of this file.
00001 /* $Id$ */
00002 
00003 /*********************************************************************
00004 * Software License Agreement (BSD License)
00005 *
00006 *  Copyright (c) 2010 Jack O'Quin
00007 *  All rights reserved.
00008 *
00009 *  Redistribution and use in source and binary forms, with or without
00010 *  modification, are permitted provided that the following conditions
00011 *  are met:
00012 *
00013 *   * Redistributions of source code must retain the above copyright
00014 *     notice, this list of conditions and the following disclaimer.
00015 *   * Redistributions in binary form must reproduce the above
00016 *     copyright notice, this list of conditions and the following
00017 *     disclaimer in the documentation and/or other materials provided
00018 *     with the distribution.
00019 *   * Neither the name of the author nor other contributors may be
00020 *     used to endorse or promote products derived from this software
00021 *     without specific prior written permission.
00022 *
00023 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 *  POSSIBILITY OF SUCH DAMAGE.
00035 *********************************************************************/
00036 
00037 #include <unistd.h>
00038 #include <stdlib.h>
00039 #include <ros/ros.h>
00040 #include <ros/package.h>
00041 #include "camera_info_manager/camera_info_manager.h"
00042 #include <sensor_msgs/distortion_models.h>
00043 #include <string>
00044 #include <gtest/gtest.h>
00045 
00047 // global test data
00049 
00050 namespace
00051 {
00052   const std::string g_package_name("camera_info_manager");
00053   const std::string g_test_name("test_calibration");
00054   const std::string g_package_filename("/tests/" + g_test_name +".yaml");
00055   const std::string g_package_url("package://" + g_package_name
00056                                   + g_package_filename);
00057   const std::string g_package_name_url("package://" + g_package_name
00058                                        + "/tests/${NAME}.yaml");
00059   const std::string g_default_url("file://${ROS_HOME}/camera_info/${NAME}.yaml");
00060   const std::string g_camera_name("08144361026320a0");
00061 }
00062 
00064 // utility functions
00066 
00067 // compare CameraInfo fields that are saved and loaded for calibration
00068 void compare_calibration(const sensor_msgs::CameraInfo &exp,
00069                          const sensor_msgs::CameraInfo &ci)
00070 {
00071   // check image size
00072   EXPECT_EQ(exp.width, ci.width);
00073   EXPECT_EQ(exp.height, ci.height);
00074 
00075   // check distortion coefficients
00076   EXPECT_EQ(exp.distortion_model, ci.distortion_model);
00077   EXPECT_EQ(exp.D.size(), ci.D.size());
00078   for (unsigned i = 0; i < ci.D.size(); ++i)
00079     {
00080       EXPECT_EQ(exp.D[i], ci.D[i]);
00081     }
00082 
00083   // check camera matrix
00084   for (unsigned i = 0; i < ci.K.size(); ++i)
00085     {
00086       EXPECT_EQ(exp.K[i], ci.K[i]);
00087     }
00088 
00089   // check rectification matrix
00090   for (unsigned i = 0; i < ci.R.size(); ++i)
00091     {
00092       EXPECT_EQ(exp.R[i], ci.R[i]);
00093     }
00094 
00095   // check projection matrix
00096   for (unsigned i = 0; i < ci.P.size(); ++i)
00097     {
00098       EXPECT_EQ(exp.P[i], ci.P[i]);
00099     }
00100 }
00101 
00102 // make sure this file does not exist
00103 void delete_file(std::string filename)
00104 {
00105   int rc = unlink(filename.c_str());
00106   if (rc != 0)
00107     {
00108       if (errno != ENOENT)
00109         ROS_INFO_STREAM("unexpected unlink() error: " << errno);
00110     }
00111 }
00112 
00113 void delete_default_file(void)
00114 {
00115   std::string ros_home("/tmp");
00116   setenv("ROS_HOME", ros_home.c_str(), true);
00117   std::string tmpFile(ros_home + "/camera_info/camera.yaml");
00118   delete_file(tmpFile);
00119 }
00120 
00121 void do_system(const std::string &command)
00122 {
00123   int rc = system(command.c_str());
00124   if (rc)
00125     std::cout << command << " returns " << rc;
00126 }
00127 
00128 void delete_tmp_camera_info_directory(void)
00129 {
00130   do_system(std::string("rm -rf /tmp/camera_info"));
00131 }
00132 
00133 void make_tmp_camera_info_directory(void)
00134 {
00135   do_system(std::string("mkdir -p /tmp/camera_info"));
00136 }
00137 
00138 // These data must match the contents of test_calibration.yaml.
00139 sensor_msgs::CameraInfo expected_calibration(void)
00140 {
00141   sensor_msgs::CameraInfo ci;
00142 
00143   ci.width = 640u;
00144   ci.height = 480u;
00145 
00146   // set distortion coefficients
00147   ci.distortion_model = sensor_msgs::distortion_models::PLUMB_BOB;
00148   ci.D.resize(5);
00149   ci.D[0] = -1.04482;
00150   ci.D[1] = 1.59252;
00151   ci.D[2] = -0.0196308;
00152   ci.D[3] = 0.0287906;
00153   ci.D[4] = 0.0;
00154 
00155   // set camera matrix
00156   ci.K[0] = 1168.68;
00157   ci.K[1] = 0.0;
00158   ci.K[2] = 295.015;
00159   ci.K[3] = 0.0;
00160   ci.K[4] = 1169.01;
00161   ci.K[5] = 252.247;
00162   ci.K[6] = 0.0;
00163   ci.K[7] = 0.0;
00164   ci.K[8] = 1.0;
00165 
00166   // set rectification matrix
00167   ci.R[0] = 1.0;
00168   ci.R[1] = 0.0;
00169   ci.R[2] = 0.0;
00170   ci.R[3] = 0.0;
00171   ci.R[4] = 1.0;
00172   ci.R[5] = 0.0;
00173   ci.R[6] = 0.0;
00174   ci.R[7] = 0.0;
00175   ci.R[8] = 1.0;
00176 
00177   // set projection matrix
00178   ci.P[0] = ci.K[0];
00179   ci.P[1] = ci.K[1];
00180   ci.P[2] = ci.K[2];
00181   ci.P[3] = 0.0;
00182   ci.P[4] = ci.K[3];
00183   ci.P[5] = ci.K[4];
00184   ci.P[6] = ci.K[5];
00185   ci.P[7] = 0.0;
00186   ci.P[8] = ci.K[6];
00187   ci.P[9] = ci.K[7];
00188   ci.P[10] = ci.K[8];
00189   ci.P[11] = 0.0;
00190 
00191   return ci;
00192 }
00193 
00194 // issue SetCameraInfo service request
00195 bool set_calibration(ros::NodeHandle node,
00196                      const sensor_msgs::CameraInfo &calib)
00197 {
00198   ros::ServiceClient client =
00199     node.serviceClient<sensor_msgs::SetCameraInfo>("set_camera_info");
00200   sensor_msgs::SetCameraInfo set_camera_info;
00201   set_camera_info.request.camera_info = calib;
00202   bool success;
00203   EXPECT_TRUE((success = client.call(set_camera_info)));
00204   return success;
00205 }
00206 
00207 // resolve URL string, result should be as expected
00208 void check_url_substitution(ros::NodeHandle node,
00209                             const std::string &url,
00210                             const std::string &exp_url,
00211                             const std::string &camera_name)
00212 {
00213   camera_info_manager::CameraInfoManager cinfo(node, camera_name, url);
00214   std::string sub_url = cinfo.resolveURL(url, camera_name);
00215   EXPECT_EQ(sub_url, exp_url);
00216 }
00217 
00219 // Test cases
00221 
00222 // Test that valid camera names are accepted
00223 TEST(CameraName, validNames)
00224 {
00225   ros::NodeHandle node;
00226   camera_info_manager::CameraInfoManager cinfo(node);
00227 
00228   EXPECT_TRUE(cinfo.setCameraName(std::string("a")));
00229   EXPECT_TRUE(cinfo.setCameraName(std::string("1")));
00230   EXPECT_TRUE(cinfo.setCameraName(std::string("_")));
00231   EXPECT_TRUE(cinfo.setCameraName(std::string("abcdefghijklmnopqrstuvwxyz")));
00232   EXPECT_TRUE(cinfo.setCameraName(std::string("ABCDEFGHIJKLMNOPQRSTUVWXYZ")));
00233   EXPECT_TRUE(cinfo.setCameraName(std::string("0123456789")));
00234   EXPECT_TRUE(cinfo.setCameraName(std::string("0123456789abcdef")));
00235   EXPECT_TRUE(cinfo.setCameraName(std::string("A1")));
00236   EXPECT_TRUE(cinfo.setCameraName(std::string("9z")));
00237   EXPECT_TRUE(cinfo.setCameraName(std::string("08144361026320a0_640x480_mono8")));
00238 
00239 }
00240 
00241 // Test that invalid camera names are rejected
00242 TEST(CameraName, invalidNames)
00243 {
00244   ros::NodeHandle node;
00245   camera_info_manager::CameraInfoManager cinfo(node);
00246 
00247   EXPECT_FALSE(cinfo.setCameraName(std::string("")));
00248   EXPECT_FALSE(cinfo.setCameraName(std::string("-21")));
00249   EXPECT_FALSE(cinfo.setCameraName(std::string("C++")));
00250   EXPECT_FALSE(cinfo.setCameraName(std::string("file:///tmp/url.yaml")));
00251   EXPECT_FALSE(cinfo.setCameraName(std::string("file://${INVALID}/xxx.yaml")));
00252 }
00253 
00254 // Test that valid URLs are accepted
00255 TEST(UrlValidation, validURLs)
00256 {
00257   ros::NodeHandle node;
00258   camera_info_manager::CameraInfoManager cinfo(node);
00259 
00260   EXPECT_TRUE(cinfo.validateURL(std::string("")));
00261   EXPECT_TRUE(cinfo.validateURL(std::string("file:///")));
00262   EXPECT_TRUE(cinfo.validateURL(std::string("file:///tmp/url.yaml")));
00263   EXPECT_TRUE(cinfo.validateURL(std::string("File:///tmp/url.ini")));
00264   EXPECT_TRUE(cinfo.validateURL(std::string("FILE:///tmp/url.yaml")));
00265   EXPECT_TRUE(cinfo.validateURL(g_default_url));
00266   EXPECT_TRUE(cinfo.validateURL(g_package_url));
00267   EXPECT_TRUE(cinfo.validateURL(std::string("package://no_such_package/calibration.yaml")));
00268   EXPECT_TRUE(cinfo.validateURL(std::string("packAge://camera_info_manager/x")));
00269 }
00270 
00271 // Test that invalid URLs are rejected
00272 TEST(UrlValidation, invalidURLs)
00273 {
00274   ros::NodeHandle node;
00275   camera_info_manager::CameraInfoManager cinfo(node);
00276 
00277   EXPECT_FALSE(cinfo.validateURL(std::string("file://")));
00278   EXPECT_FALSE(cinfo.validateURL(std::string("flash:///")));
00279   EXPECT_FALSE(cinfo.validateURL(std::string("html://ros.org/wiki/camera_info_manager")));
00280   EXPECT_FALSE(cinfo.validateURL(std::string("package://")));
00281   EXPECT_FALSE(cinfo.validateURL(std::string("package:///")));
00282   EXPECT_FALSE(cinfo.validateURL(std::string("package://calibration.yaml")));
00283   EXPECT_FALSE(cinfo.validateURL(std::string("package://camera_info_manager/")));
00284 }
00285 
00286 // Test ability to provide uncalibrated CameraInfo
00287 TEST(GetInfo, uncalibrated)
00288 {
00289   ros::NodeHandle node;
00290 
00291   delete_default_file();
00292 
00293   camera_info_manager::CameraInfoManager cinfo(node);
00294   EXPECT_FALSE(cinfo.isCalibrated());
00295 
00296   sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
00297   sensor_msgs::CameraInfo exp;
00298   compare_calibration(exp, ci);
00299 }
00300 
00301 // Test ability to load calibrated CameraInfo
00302 TEST(GetInfo, calibrated)
00303 {
00304   ros::NodeHandle node;
00305 
00306   delete_default_file();
00307 
00308   camera_info_manager::CameraInfoManager cinfo(node);
00309   EXPECT_FALSE(cinfo.isCalibrated());
00310 
00311   std::string pkgPath(ros::package::getPath(g_package_name));
00312   std::string url("file://" + pkgPath + "/tests/test_calibration.yaml");
00313   EXPECT_TRUE(cinfo.loadCameraInfo(url));
00314   EXPECT_TRUE(cinfo.isCalibrated());
00315 
00316   sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
00317   sensor_msgs::CameraInfo exp(expected_calibration());
00318   compare_calibration(exp, ci);
00319 }
00320 
00321 // Test ability to load calibrated CameraInfo from package
00322 TEST(GetInfo, fromPackage)
00323 {
00324   ros::NodeHandle node;
00325   camera_info_manager::CameraInfoManager cinfo(node);
00326 
00327   EXPECT_TRUE(cinfo.loadCameraInfo(g_package_url));
00328   EXPECT_TRUE(cinfo.isCalibrated());
00329 
00330   sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
00331   sensor_msgs::CameraInfo exp(expected_calibration());
00332   compare_calibration(exp, ci);
00333 }
00334 
00335 // Test ability to access named calibrated CameraInfo from package
00336 TEST(GetInfo, fromPackageWithName)
00337 {
00338   ros::NodeHandle node;
00339   camera_info_manager::CameraInfoManager cinfo(node, g_test_name,
00340                                                g_package_name_url);
00341   EXPECT_TRUE(cinfo.isCalibrated());
00342 
00343   sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
00344   sensor_msgs::CameraInfo exp(expected_calibration());
00345   compare_calibration(exp, ci);
00346 }
00347 
00348 // Test load of unresolved "package:" URL files
00349 TEST(GetInfo, unresolvedLoads)
00350 {
00351   ros::NodeHandle node;
00352   camera_info_manager::CameraInfoManager cinfo(node);
00353 
00354   EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://")));
00355   EXPECT_FALSE(cinfo.isCalibrated());
00356 
00357   EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package:///calibration.yaml")));
00358   EXPECT_FALSE(cinfo.isCalibrated());
00359 
00360   EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://no_such_package/calibration.yaml")));
00361   EXPECT_FALSE(cinfo.isCalibrated());
00362 
00363   EXPECT_FALSE(cinfo.loadCameraInfo(std::string("package://camera_info_manager/no_such_file.yaml")));
00364   EXPECT_FALSE(cinfo.isCalibrated());
00365 }
00366 
00367 // Test load of "package:" URL after changing name
00368 TEST(GetInfo, nameChange)
00369 {
00370   ros::NodeHandle node;
00371   const std::string missing_file("no_such_file");
00372 
00373   // first declare using non-existent camera name
00374   camera_info_manager::CameraInfoManager cinfo(node, missing_file,
00375                                                g_package_name_url);
00376   EXPECT_FALSE(cinfo.isCalibrated());
00377 
00378   // set name so it resolves to a test file that does exist
00379   EXPECT_TRUE(cinfo.setCameraName(g_test_name));
00380   EXPECT_TRUE(cinfo.isCalibrated());
00381   sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
00382   sensor_msgs::CameraInfo exp(expected_calibration());
00383   compare_calibration(exp, ci);
00384 }
00385 
00386 // Test load of invalid CameraInfo URLs
00387 TEST(GetInfo, invalidLoads)
00388 {
00389   ros::NodeHandle node;
00390   camera_info_manager::CameraInfoManager cinfo(node);
00391 
00392   EXPECT_FALSE(cinfo.loadCameraInfo(std::string("flash:///")));
00393   EXPECT_FALSE(cinfo.isCalibrated());
00394 
00395   EXPECT_FALSE(cinfo.loadCameraInfo(std::string("html://ros.org/wiki/camera_info_manager")));
00396   EXPECT_FALSE(cinfo.isCalibrated());
00397 
00398   sensor_msgs::CameraInfo ci(cinfo.getCameraInfo());
00399   sensor_msgs::CameraInfo exp;
00400   compare_calibration(exp, ci);
00401 }
00402 
00403 // Test ability to set CameraInfo directly
00404 TEST(SetInfo, setCameraInfo)
00405 {
00406   ros::NodeHandle node;
00407   camera_info_manager::CameraInfoManager cinfo(node);
00408 
00409   // issue calibration service request
00410   sensor_msgs::CameraInfo exp(expected_calibration());
00411   bool success = cinfo.setCameraInfo(exp);
00412   EXPECT_TRUE(success);
00413 
00414   // only check results if the service succeeded, avoiding confusing
00415   // and redundant failure messages
00416   if (success)
00417     {
00418       // check that it worked
00419       EXPECT_TRUE(cinfo.isCalibrated());
00420       sensor_msgs::CameraInfo ci = cinfo.getCameraInfo();
00421       compare_calibration(exp, ci);
00422     }
00423 }
00424 
00425 // Test ability to set calibrated CameraInfo
00426 TEST(SetInfo, setCalibration)
00427 {
00428   ros::NodeHandle node;
00429   camera_info_manager::CameraInfoManager cinfo(node);
00430 
00431   // issue calibration service request
00432   sensor_msgs::CameraInfo exp(expected_calibration());
00433   bool success = set_calibration(node, exp);
00434 
00435   // only check results if the service succeeded, avoiding confusing
00436   // and redundant failure messages
00437   if (success)
00438     {
00439       // check that it worked
00440       EXPECT_TRUE(cinfo.isCalibrated());
00441       sensor_msgs::CameraInfo ci = cinfo.getCameraInfo();
00442       compare_calibration(exp, ci);
00443     }
00444 }
00445 
00446 // Test ability to save calibrated CameraInfo in default URL
00447 TEST(SetInfo, saveCalibrationDefault)
00448 {
00449   ros::NodeHandle node;
00450   sensor_msgs::CameraInfo exp(expected_calibration());
00451   bool success;
00452 
00453   // Set ${ROS_HOME} to /tmp, then delete the /tmp/camera_info
00454   // directory and everything in it.
00455   setenv("ROS_HOME", "/tmp", true);
00456   delete_tmp_camera_info_directory();
00457 
00458   {
00459     // create instance to save calibrated data
00460     camera_info_manager::CameraInfoManager cinfo(node);
00461     EXPECT_FALSE(cinfo.isCalibrated());
00462 
00463     // issue calibration service request
00464     success = set_calibration(node, exp);
00465     EXPECT_TRUE(cinfo.isCalibrated());
00466   }
00467 
00468   // only check results if the service succeeded, avoiding confusing
00469   // and redundant failure messages
00470   if (success)
00471     {
00472       // create a new instance to load saved calibration
00473       camera_info_manager::CameraInfoManager cinfo2(node);
00474       EXPECT_TRUE(cinfo2.isCalibrated());
00475       if (cinfo2.isCalibrated())
00476         {
00477           sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
00478           compare_calibration(exp, ci);
00479         }
00480     }
00481 }
00482 
00483 // Test ability to save calibrated CameraInfo to default location with
00484 // explicit camera name
00485 TEST(SetInfo, saveCalibrationCameraName)
00486 {
00487   ros::NodeHandle node;
00488   sensor_msgs::CameraInfo exp(expected_calibration());
00489   bool success;
00490 
00491   // set ${ROS_HOME} to /tmp, delete the calibration file
00492   std::string ros_home("/tmp");
00493   setenv("ROS_HOME", ros_home.c_str(), true);
00494   std::string tmpFile(ros_home + "/camera_info/" + g_camera_name + ".yaml");
00495   delete_file(tmpFile);
00496 
00497   {
00498     // create instance to save calibrated data
00499     camera_info_manager::CameraInfoManager cinfo(node, g_camera_name);
00500     success = set_calibration(node, exp);
00501     EXPECT_TRUE(cinfo.isCalibrated());
00502   }
00503 
00504   // only check results if the service succeeded, avoiding confusing
00505   // and redundant failure messages
00506   if (success)
00507     {
00508       // create a new instance to load saved calibration
00509       camera_info_manager::CameraInfoManager cinfo2(node);
00510       std::string url = "file://" + tmpFile;
00511       cinfo2.loadCameraInfo(std::string(url));
00512       EXPECT_TRUE(cinfo2.isCalibrated());
00513       if (cinfo2.isCalibrated())
00514         {
00515           sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
00516           compare_calibration(exp, ci);
00517         }
00518     }
00519 }
00520 
00521 // Test ability to save calibrated CameraInfo in a file
00522 TEST(SetInfo, saveCalibrationFile)
00523 {
00524   return;
00525 
00526   ros::NodeHandle node;
00527   sensor_msgs::CameraInfo exp(expected_calibration());
00528   std::string cname("camera");
00529   std::string tmpFile("/tmp/camera_info_manager_calibration_test.yaml");
00530   std::string url = "file://" + tmpFile;
00531   bool success;
00532 
00533   // first, delete the file
00534   delete_file(tmpFile);
00535 
00536   {
00537     // create instance to save calibrated data
00538     camera_info_manager::CameraInfoManager cinfo(node, cname, url);
00539     success = set_calibration(node, exp);
00540     EXPECT_TRUE(cinfo.isCalibrated());
00541   }
00542 
00543   // only check results if the service succeeded, avoiding confusing
00544   // and redundant failure messages
00545   if (success)
00546     {
00547       // create a new instance to load saved calibration
00548       camera_info_manager::CameraInfoManager cinfo2(node, cname, url);
00549       EXPECT_TRUE(cinfo2.isCalibrated());
00550       if (cinfo2.isCalibrated())
00551         {
00552           sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
00553           compare_calibration(exp, ci);
00554         }
00555     }
00556 }
00557 
00558 // Test ability to save calibrated CameraInfo in a package
00559 // (needs write access).
00560 TEST(SetInfo, saveCalibrationPackage)
00561 {
00562   ros::NodeHandle node;
00563   sensor_msgs::CameraInfo exp(expected_calibration());
00564   std::string pkgPath(ros::package::getPath(g_package_name));
00565   std::string filename(pkgPath + g_package_filename);
00566   bool success;
00567 
00568   // first, delete the file
00569   delete_file(filename);
00570 
00571   {
00572     // create instance to save calibrated data
00573     camera_info_manager::CameraInfoManager cinfo(node, g_camera_name,
00574                                                  g_package_url);
00575     success = set_calibration(node, exp);
00576     EXPECT_TRUE(cinfo.isCalibrated());
00577   }
00578 
00579   // only check results if the service succeeded, avoiding confusing
00580   // and redundant failure messages
00581   if (success)
00582     {
00583       // create a new instance to load saved calibration
00584       camera_info_manager::CameraInfoManager cinfo2(node, g_camera_name,
00585                                                     g_package_url);
00586       EXPECT_TRUE(cinfo2.isCalibrated());
00587       if (cinfo2.isCalibrated())
00588         {
00589           sensor_msgs::CameraInfo ci(cinfo2.getCameraInfo());
00590           compare_calibration(exp, ci);
00591         }
00592     }
00593 }
00594 
00595 TEST(UrlSubstitution, cameraName)
00596 {
00597   ros::NodeHandle node;
00598   std::string name_url;
00599   std::string exp_url;
00600 
00601   // resolve a GUID camera name
00602   name_url = "package://" + g_package_name + "/tests/${NAME}.yaml";
00603   exp_url = "package://" + g_package_name + "/tests/" + g_camera_name + ".yaml";
00604   check_url_substitution(node, name_url, exp_url, g_camera_name);
00605 
00606   // substitute camera name "test"
00607   name_url = "package://" + g_package_name + "/tests/${NAME}_calibration.yaml";
00608   std::string test_name("test");
00609   exp_url = "package://" + g_package_name + "/tests/" + test_name
00610     + "_calibration.yaml";
00611   check_url_substitution(node, name_url, exp_url, test_name);
00612 
00613   // with an '_' in the name
00614   test_name = "camera_1024x768";
00615   exp_url = "package://" + g_package_name + "/tests/" + test_name
00616     + "_calibration.yaml";
00617   check_url_substitution(node, name_url, exp_url, test_name);
00618 
00619   // substitute empty camera name
00620   name_url = "package://" + g_package_name + "/tests/${NAME}_calibration.yaml";
00621   std::string empty_name("");
00622   exp_url = "package://" + g_package_name + "/tests/" + empty_name
00623     + "_calibration.yaml";
00624   check_url_substitution(node, name_url, exp_url, empty_name);
00625 
00626   // substitute test camera calibration from this package
00627   check_url_substitution(node, g_package_name_url, g_package_url, g_test_name);
00628 }
00629 
00630 TEST(UrlSubstitution, rosHome)
00631 {
00632   ros::NodeHandle node;
00633   std::string name_url;
00634   std::string exp_url;
00635   char *home_env = getenv("HOME");
00636   std::string home(home_env);
00637 
00638   // resolve ${ROS_HOME} with environment variable undefined
00639   unsetenv("ROS_HOME");
00640   name_url = "file://${ROS_HOME}/camera_info/test_camera.yaml";
00641   exp_url = "file://" + home + "/.ros/camera_info/test_camera.yaml";
00642   check_url_substitution(node, name_url, exp_url, g_camera_name);
00643 
00644   // resolve ${ROS_HOME} with environment variable defined
00645   setenv("ROS_HOME", "/my/ros/home", true);
00646   name_url = "file://${ROS_HOME}/camera_info/test_camera.yaml";
00647   exp_url = "file:///my/ros/home/camera_info/test_camera.yaml";
00648   check_url_substitution(node, name_url, exp_url, g_camera_name);
00649 }
00650 
00651 TEST(UrlSubstitution, unmatchedDollarSigns)
00652 {
00653   ros::NodeHandle node;
00654 
00655   // test for "$$" in the URL (NAME should be resolved)
00656   std::string name_url("file:///tmp/$${NAME}.yaml");
00657   std::string exp_url("file:///tmp/$" + g_camera_name + ".yaml");
00658   check_url_substitution(node, name_url, exp_url, g_camera_name);
00659 
00660   // test for "$" in middle of string
00661   name_url = "file:///$whatever.yaml";
00662   check_url_substitution(node, name_url, name_url, g_camera_name);
00663 
00664   // test for "$$" in middle of string
00665   name_url = "file:///something$$whatever.yaml";
00666   check_url_substitution(node, name_url, name_url, g_camera_name);
00667 
00668   // test for "$$" at end of string
00669   name_url = "file:///$$";
00670   check_url_substitution(node, name_url, name_url, g_camera_name);
00671 }
00672 
00673 TEST(UrlSubstitution, emptyURL)
00674 {
00675   // test that empty URL is handled correctly
00676   ros::NodeHandle node;
00677   std::string empty_url("");
00678   check_url_substitution(node, empty_url, empty_url, g_camera_name);
00679 }
00680 
00681 TEST(UrlSubstitution, invalidVariables)
00682 {
00683   ros::NodeHandle node;
00684   std::string name_url;
00685 
00686   // missing "{...}"
00687   name_url = "file:///tmp/$NAME.yaml";
00688   check_url_substitution(node, name_url, name_url, g_camera_name);
00689 
00690   // invalid substitution variable name
00691   name_url = "file:///tmp/${INVALID}/calibration.yaml";
00692   check_url_substitution(node, name_url, name_url, g_camera_name);
00693 
00694   // truncated substitution variable
00695   name_url = "file:///tmp/${NAME";
00696   check_url_substitution(node, name_url, name_url, g_camera_name);
00697 
00698   // missing substitution variable
00699   name_url = "file:///tmp/${}";
00700   check_url_substitution(node, name_url, name_url, g_camera_name);
00701 
00702   // no exception thrown for single "$" at end of string
00703   name_url = "file:///$";
00704   check_url_substitution(node, name_url, name_url, g_camera_name);
00705 }
00706 
00707 // Run all the tests that were declared with TEST()
00708 int main(int argc, char **argv)
00709 {
00710   ros::init(argc, argv, "camera_info_manager_unit_test");
00711   testing::InitGoogleTest(&argc, argv);
00712 
00713   // create asynchronous thread for handling service requests
00714   ros::AsyncSpinner spinner(1);
00715   spinner.start();
00716 
00717   // run the tests in this thread
00718   return RUN_ALL_TESTS();
00719 }


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Tue Jun 6 2017 02:33:45