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]);
105 int rc = unlink(filename.c_str());
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");
123 int rc = system(command.c_str());
125 std::cout << command <<
" returns " << rc;
130 do_system(std::string(
"rm -rf /tmp/camera_info"));
135 do_system(std::string(
"mkdir -p /tmp/camera_info"));
141 sensor_msgs::CameraInfo ci;
151 ci.D[2] = -0.0196308;
196 const sensor_msgs::CameraInfo &calib)
199 node.
serviceClient<sensor_msgs::SetCameraInfo>(
"set_camera_info");
200 sensor_msgs::SetCameraInfo set_camera_info;
201 set_camera_info.request.camera_info = calib;
203 EXPECT_TRUE((success = client.
call(set_camera_info)));
209 const std::string &url,
210 const std::string &exp_url,
211 const std::string &camera_name)
214 std::string sub_url = cinfo.
resolveURL(url, camera_name);
215 EXPECT_EQ(sub_url, exp_url);
231 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"abcdefghijklmnopqrstuvwxyz")));
232 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"ABCDEFGHIJKLMNOPQRSTUVWXYZ")));
234 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"0123456789abcdef")));
237 EXPECT_TRUE(cinfo.
setCameraName(std::string(
"08144361026320a0_640x480_mono8")));
250 EXPECT_FALSE(cinfo.
setCameraName(std::string(
"file:///tmp/url.yaml")));
251 EXPECT_FALSE(cinfo.
setCameraName(std::string(
"file://${INVALID}/xxx.yaml")));
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")));
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")));
272 TEST(UrlValidation, invalidURLs)
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/")));
297 sensor_msgs::CameraInfo exp;
312 std::string url(
"file://" + pkgPath +
"/tests/test_calibration.yaml");
336 TEST(GetInfo, fromPackageWithName)
357 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"package:///calibration.yaml")));
360 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"package://no_such_package/calibration.yaml")));
363 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"package://camera_info_manager/no_such_file.yaml")));
371 const std::string missing_file(
"no_such_file");
395 EXPECT_FALSE(cinfo.
loadCameraInfo(std::string(
"html://ros.org/wiki/camera_info_manager")));
399 sensor_msgs::CameraInfo exp;
412 EXPECT_TRUE(success);
447 TEST(SetInfo, saveCalibrationDefault)
455 setenv(
"ROS_HOME",
"/tmp",
true);
485 TEST(SetInfo, saveCalibrationCameraName)
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");
510 std::string url =
"file://" + tmpFile;
522 TEST(SetInfo, saveCalibrationFile)
528 std::string cname(
"camera");
529 std::string tmpFile(
"/tmp/camera_info_manager_calibration_test.yaml");
530 std::string url =
"file://" + tmpFile;
560 TEST(SetInfo, saveCalibrationPackage)
565 std::string filename(pkgPath + g_package_filename);
595 TEST(UrlSubstitution, cameraName)
598 std::string name_url;
602 name_url =
"package://" + g_package_name +
"/tests/${NAME}.yaml";
603 exp_url =
"package://" + g_package_name +
"/tests/" + g_camera_name +
".yaml";
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";
614 test_name =
"camera_1024x768";
615 exp_url =
"package://" + g_package_name +
"/tests/" + test_name
616 +
"_calibration.yaml";
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";
633 std::string name_url;
635 char *home_env = getenv(
"HOME");
636 std::string home(home_env);
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";
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";
651 TEST(UrlSubstitution, unmatchedDollarSigns)
656 std::string name_url(
"file:///tmp/$${NAME}.yaml");
657 std::string exp_url(
"file:///tmp/$" + g_camera_name +
".yaml");
661 name_url =
"file:///$whatever.yaml";
665 name_url =
"file:///something$$whatever.yaml";
669 name_url =
"file:///$$";
673 TEST(UrlSubstitution, emptyURL)
677 std::string empty_url(
"");
681 TEST(UrlSubstitution, invalidVariables)
684 std::string name_url;
687 name_url =
"file:///tmp/$NAME.yaml";
691 name_url =
"file:///tmp/${INVALID}/calibration.yaml";
695 name_url =
"file:///tmp/${NAME";
699 name_url =
"file:///tmp/${}";
703 name_url =
"file:///$";
708 int main(
int argc,
char **argv)
710 ros::init(argc, argv,
"camera_info_manager_unit_test");
711 testing::InitGoogleTest(&argc, argv);
718 return RUN_ALL_TESTS();
void check_url_substitution(ros::NodeHandle node, const std::string &url, const std::string &exp_url, const std::string &camera_name)
void delete_tmp_camera_info_directory(void)
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)
void make_tmp_camera_info_directory(void)
sensor_msgs::CameraInfo getCameraInfo(void)
void do_system(const std::string &command)
bool loadCameraInfo(const std::string &url)
sensor_msgs::CameraInfo expected_calibration(void)
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)
CameraInfo Manager interface.
void delete_file(std::string filename)
TEST(CameraName, validNames)
bool validateURL(const std::string &url)
const std::string PLUMB_BOB
ROSLIB_DECL std::string getPath(const std::string &package_name)
void delete_default_file(void)
#define ROS_INFO_STREAM(args)
bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
CameraInfo Manager class.
void compare_calibration(const sensor_msgs::CameraInfo &exp, const sensor_msgs::CameraInfo &ci)
bool setCameraName(const std::string &cname)