44 #include <gtest/gtest.h>
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");
69 const sensor_msgs::CameraInfo &ci)
72 EXPECT_EQ(exp.width, ci.width);
73 EXPECT_EQ(exp.height, ci.height);
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)
80 EXPECT_EQ(exp.D[i], ci.D[i]);
84 for (
unsigned i = 0; i < ci.K.size(); ++i)
86 EXPECT_EQ(exp.K[i], ci.K[i]);
90 for (
unsigned i = 0; i < ci.R.size(); ++i)
92 EXPECT_EQ(exp.R[i], ci.R[i]);
96 for (
unsigned i = 0; i < ci.P.size(); ++i)
98 EXPECT_EQ(exp.P[i], ci.P[i]);
102 EXPECT_EQ(exp.binning_x, ci.binning_x);
103 EXPECT_EQ(exp.binning_y, ci.binning_y);
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);
116 int rc = unlink(filename.c_str());
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");
134 int rc = system(
command.c_str());
136 std::cout <<
command <<
" returns " << rc;
141 do_system(std::string(
"rm -rf /tmp/camera_info"));
146 do_system(std::string(
"mkdir -p /tmp/camera_info"));
152 sensor_msgs::CameraInfo ci;
162 ci.D[2] = -0.0196308;
205 ci.roi.x_offset = 20;
206 ci.roi.y_offset = 40;
215 const sensor_msgs::CameraInfo &calib)
218 node.
serviceClient<sensor_msgs::SetCameraInfo>(
"set_camera_info");
219 sensor_msgs::SetCameraInfo set_camera_info;
220 set_camera_info.request.camera_info = calib;
222 EXPECT_TRUE((success = client.
call(set_camera_info)));
228 const std::string &url,
229 const std::string &exp_url,
230 const std::string &camera_name)
233 std::string sub_url = cinfo.
resolveURL(url, camera_name);
234 EXPECT_EQ(sub_url, exp_url);
250 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"abcdefghijklmnopqrstuvwxyz")));
251 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"ABCDEFGHIJKLMNOPQRSTUVWXYZ")));
253 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"0123456789abcdef")));
256 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"08144361026320a0_640x480_mono8")));
269 EXPECT_FALSE(cinfo.
setCameraName(std::string(
"file:///tmp/url.yaml")));
270 EXPECT_FALSE(cinfo.
setCameraName(std::string(
"file://${INVALID}/xxx.yaml")));
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")));
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")));
291 TEST(UrlValidation, invalidURLs)
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/")));
316 sensor_msgs::CameraInfo exp;
331 std::string url(
"file://" + pkgPath +
"/tests/test_calibration.yaml");
355 TEST(GetInfo, fromPackageWithName)
376 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"package:///calibration.yaml")));
379 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"package://no_such_package/calibration.yaml")));
382 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"package://camera_info_manager/no_such_file.yaml")));
390 const std::string missing_file(
"no_such_file");
414 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"html://ros.org/wiki/camera_info_manager")));
418 sensor_msgs::CameraInfo exp;
431 EXPECT_TRUE(success);
466 TEST(SetInfo, saveCalibrationDefault)
474 setenv(
"ROS_HOME",
"/tmp",
true);
504 TEST(SetInfo, saveCalibrationCameraName)
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");
529 std::string url =
"file://" + tmpFile;
541 TEST(SetInfo, saveCalibrationFile)
547 std::string cname(
"camera");
548 std::string tmpFile(
"/tmp/camera_info_manager_calibration_test.yaml");
549 std::string url =
"file://" + tmpFile;
579 TEST(SetInfo, saveCalibrationPackage)
584 std::string filename(pkgPath + g_package_filename);
614 TEST(UrlSubstitution, cameraName)
617 std::string name_url;
621 name_url =
"package://" + g_package_name +
"/tests/${NAME}.yaml";
622 exp_url =
"package://" + g_package_name +
"/tests/" + g_camera_name +
".yaml";
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";
633 test_name =
"camera_1024x768";
634 exp_url =
"package://" + g_package_name +
"/tests/" + test_name
635 +
"_calibration.yaml";
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";
652 std::string name_url;
654 char *home_env = getenv(
"HOME");
655 std::string home(home_env);
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";
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";
670 TEST(UrlSubstitution, unmatchedDollarSigns)
675 std::string name_url(
"file:///tmp/$${NAME}.yaml");
676 std::string exp_url(
"file:///tmp/$" + g_camera_name +
".yaml");
680 name_url =
"file:///$whatever.yaml";
684 name_url =
"file:///something$$whatever.yaml";
688 name_url =
"file:///$$";
692 TEST(UrlSubstitution, emptyURL)
696 std::string empty_url(
"");
700 TEST(UrlSubstitution, invalidVariables)
703 std::string name_url;
706 name_url =
"file:///tmp/$NAME.yaml";
710 name_url =
"file:///tmp/${INVALID}/calibration.yaml";
714 name_url =
"file:///tmp/${NAME";
718 name_url =
"file:///tmp/${}";
722 name_url =
"file:///$";
727 int main(
int argc,
char **argv)
729 ros::init(argc, argv,
"camera_info_manager_unit_test");
730 testing::InitGoogleTest(&argc, argv);
737 return RUN_ALL_TESTS();