00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <string>
00038 #include <locale>
00039 #include <stdlib.h>
00040 #include <sys/types.h>
00041 #include <sys/stat.h>
00042 #include <unistd.h>
00043 #include <ros/ros.h>
00044 #include <ros/package.h>
00045 #include <boost/algorithm/string.hpp>
00046 #include <camera_calibration_parsers/parse.h>
00047
00048 #include "camera_info_manager/camera_info_manager.h"
00049
00060 namespace camera_info_manager
00061 {
00062
00063 using namespace camera_calibration_parsers;
00064
00066 const std::string
00067 default_camera_info_url = "file://${ROS_HOME}/camera_info/${NAME}.yaml";
00068
00078 CameraInfoManager::CameraInfoManager(ros::NodeHandle nh,
00079 const std::string &cname,
00080 const std::string &url):
00081 nh_(nh),
00082 camera_name_(cname)
00083 {
00084
00085 loadCameraInfo(url);
00086
00087
00088 info_service_ = nh_.advertiseService("set_camera_info",
00089 &CameraInfoManager::setCameraInfo, this);
00090 }
00091
00097 std::string CameraInfoManager::getPackageFileName(const std::string &url)
00098 {
00099 ROS_DEBUG_STREAM("camera calibration URL: " << url);
00100
00101
00102
00103 size_t prefix_len = std::string("package://").length();
00104 size_t rest = url.find('/', prefix_len);
00105 std::string package(url.substr(prefix_len, rest - prefix_len));
00106
00107
00108 std::string pkgPath(ros::package::getPath(package));
00109 if (pkgPath.empty())
00110 {
00111 ROS_WARN_STREAM("unknown package: " << package << " (ignored)");
00112 return pkgPath;
00113 }
00114 else
00115 {
00116
00117 return pkgPath + url.substr(rest);
00118 }
00119 }
00120
00131 bool CameraInfoManager::loadCalibration(const std::string &url,
00132 const std::string &cname)
00133 {
00134 bool success = false;
00135
00136 const std::string resURL(resolveURL(url, cname));
00137 url_type_t url_type = parseURL(resURL);
00138
00139 if (url_type != URL_empty)
00140 {
00141 ROS_INFO_STREAM("camera calibration URL: " << resURL);
00142 }
00143
00144 switch (url_type)
00145 {
00146 case URL_empty:
00147 {
00148 ROS_INFO("using default calibration URL");
00149 success = loadCalibration(default_camera_info_url, cname);
00150 break;
00151 }
00152 case URL_file:
00153 {
00154 success = loadCalibrationFile(resURL.substr(7), cname);
00155 break;
00156 }
00157 case URL_flash:
00158 {
00159 ROS_WARN("[CameraInfoManager] reading from flash not implemented yet");
00160 break;
00161 }
00162 case URL_package:
00163 {
00164 std::string filename(getPackageFileName(resURL));
00165 if (!filename.empty())
00166 success = loadCalibrationFile(filename, cname);
00167 break;
00168 }
00169 default:
00170 {
00171 ROS_ERROR_STREAM("Invalid camera calibration URL: " << resURL);
00172 break;
00173 }
00174 }
00175
00176 return success;
00177 }
00178
00189 bool CameraInfoManager::loadCalibrationFile(const std::string &filename,
00190 const std::string &cname)
00191 {
00192 bool success = false;
00193
00194 ROS_DEBUG_STREAM("reading camera calibration from " << filename);
00195 std::string cam_name;
00196 sensor_msgs::CameraInfo cam_info;
00197
00198 if (readCalibration(filename, cam_name, cam_info))
00199 {
00200 if (cname != cam_name)
00201 {
00202 ROS_WARN_STREAM("[" << cname << "] does not match name "
00203 << cam_name << " in file " << filename);
00204 }
00205 success = true;
00206 {
00207
00208 boost::mutex::scoped_lock lock(mutex_);
00209 cam_info_ = cam_info;
00210 }
00211 }
00212 else
00213 {
00214 ROS_WARN_STREAM("Camera calibration file " << filename << " not found.");
00215 }
00216
00217 return success;
00218 }
00219
00227 bool CameraInfoManager::loadCameraInfo(const std::string &url)
00228 {
00229 std::string cname;
00230 {
00231 boost::mutex::scoped_lock lock(mutex_);
00232 url_ = url;
00233 cname = camera_name_;
00234 }
00235
00236
00237 return loadCalibration(url, cname);
00238 }
00239
00240
00249 std::string CameraInfoManager::resolveURL(const std::string &url,
00250 const std::string &cname)
00251 {
00252 std::string resolved;
00253 size_t rest = 0;
00254
00255 while (true)
00256 {
00257
00258 size_t dollar = url.find('$', rest);
00259
00260 if (dollar >= url.length())
00261 {
00262
00263 resolved += url.substr(rest);
00264 break;
00265 }
00266
00267
00268 resolved += url.substr(rest, dollar-rest);
00269
00270 if (url.substr(dollar+1, 1) != "{")
00271 {
00272
00273 resolved += "$";
00274 }
00275 else if (url.substr(dollar+1, 6) == "{NAME}")
00276 {
00277
00278 resolved += cname;
00279 dollar += 6;
00280 }
00281 else if (url.substr(dollar+1, 10) == "{ROS_HOME}")
00282 {
00283
00284 std::string ros_home;
00285 char *ros_home_env;
00286 if ((ros_home_env = getenv("ROS_HOME")))
00287 {
00288
00289 ros_home = ros_home_env;
00290 }
00291 else if ((ros_home_env = getenv("HOME")))
00292 {
00293
00294 ros_home = ros_home_env;
00295 ros_home += "/.ros";
00296 }
00297 resolved += ros_home;
00298 dollar += 10;
00299 }
00300 else
00301 {
00302
00303 ROS_ERROR_STREAM("[CameraInfoManager]"
00304 " invalid URL substitution (not resolved): "
00305 << url);
00306 resolved += "$";
00307 }
00308
00309
00310 rest = dollar + 1;
00311 }
00312
00313 return resolved;
00314 }
00315
00323 CameraInfoManager::url_type_t CameraInfoManager::parseURL(const std::string &url)
00324 {
00325 if (url == "")
00326 {
00327 return URL_empty;
00328 }
00329 if (boost::iequals(url.substr(0, 8), "file:///"))
00330 {
00331 return URL_file;
00332 }
00333 if (boost::iequals(url.substr(0, 9), "flash:///"))
00334 {
00335 return URL_flash;
00336 }
00337 if (boost::iequals(url.substr(0, 10), "package://"))
00338 {
00339
00340
00341 size_t rest = url.find('/', 10);
00342 if (rest < url.length()-1 && rest > 10)
00343 return URL_package;
00344 }
00345 return URL_invalid;
00346 }
00347
00358 bool
00359 CameraInfoManager::saveCalibration(const sensor_msgs::CameraInfo &new_info,
00360 const std::string &url,
00361 const std::string &cname)
00362 {
00363 bool success = false;
00364
00365 const std::string resURL(resolveURL(url, cname));
00366
00367 switch (parseURL(resURL))
00368 {
00369 case URL_empty:
00370 {
00371
00372 success = saveCalibration(new_info, default_camera_info_url, cname);
00373 break;
00374 }
00375 case URL_file:
00376 {
00377 success = saveCalibrationFile(new_info, resURL.substr(7), cname);
00378 break;
00379 }
00380 case URL_package:
00381 {
00382 std::string filename(getPackageFileName(resURL));
00383 if (!filename.empty())
00384 success = saveCalibrationFile(new_info, filename, cname);
00385 break;
00386 }
00387 default:
00388 {
00389
00390 ROS_ERROR_STREAM("invalid url: " << resURL << " (ignored)");
00391 success = saveCalibration(new_info, default_camera_info_url, cname);
00392 break;
00393 }
00394 }
00395
00396 return success;
00397 }
00398
00408 bool
00409 CameraInfoManager::saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
00410 const std::string &filename,
00411 const std::string &cname)
00412 {
00413 ROS_INFO_STREAM("writing calibration data to " << filename);
00414
00415
00416 size_t last_slash = filename.rfind('/');
00417 if (last_slash >= filename.length())
00418 {
00419
00420
00421 ROS_ERROR_STREAM("filename [" << filename << "] has no '/'");
00422 return false;
00423 }
00424
00425
00426 std::string dirname(filename.substr(0, last_slash+1));
00427 struct stat stat_data;
00428 int rc = stat(dirname.c_str(), &stat_data);
00429 if (rc != 0)
00430 {
00431 if (errno == ENOENT)
00432 {
00433
00434 std::string command("mkdir -p " + dirname);
00435 rc = system(command.c_str());
00436 if (rc != 0)
00437 {
00438
00439 ROS_ERROR_STREAM("unable to create path to directory ["
00440 << dirname << "]");
00441 return false;
00442 }
00443 }
00444 else
00445 {
00446
00447 ROS_ERROR_STREAM("directory [" << dirname << "] not accessible");
00448 return false;
00449 }
00450 }
00451 else if (!S_ISDIR(stat_data.st_mode))
00452 {
00453
00454 ROS_ERROR_STREAM("[" << dirname << "] is not a directory");
00455 return false;
00456 }
00457
00458
00459
00460
00461
00462 return writeCalibration(filename, cname, new_info);
00463 }
00464
00473 bool
00474 CameraInfoManager::setCameraInfo(sensor_msgs::SetCameraInfo::Request &req,
00475 sensor_msgs::SetCameraInfo::Response &rsp)
00476 {
00477
00478 std::string url_copy;
00479 std::string cname;
00480 {
00481 boost::mutex::scoped_lock lock(mutex_);
00482 cam_info_ = req.camera_info;
00483 url_copy = url_;
00484 cname = camera_name_;
00485 }
00486
00487 if (!nh_.ok())
00488 {
00489 ROS_ERROR("set_camera_info service called, but driver not running.");
00490 rsp.status_message = "Camera driver not running.";
00491 rsp.success = false;
00492 return false;
00493 }
00494
00495 rsp.success = saveCalibration(req.camera_info, url_copy, cname);
00496 if (!rsp.success)
00497 rsp.status_message = "Error storing camera calibration.";
00498
00499 return true;
00500 }
00501
00511 bool CameraInfoManager::setCameraName(const std::string &cname)
00512 {
00513
00514 if (cname.empty())
00515 return false;
00516
00517
00518 for (unsigned i = 0; i < cname.size(); ++i)
00519 {
00520 if (!isalnum(cname[i]) && cname[i] != '_')
00521 return false;
00522 }
00523
00524
00525 std::string url;
00526 {
00527 boost::mutex::scoped_lock lock(mutex_);
00528 camera_name_ = cname;
00529 url = url_;
00530 }
00531
00532
00533
00534 loadCalibration(url, cname);
00535
00536 return true;
00537 }
00538
00546 bool CameraInfoManager::validateURL(const std::string &url)
00547 {
00548 std::string cname;
00549 {
00550 boost::mutex::scoped_lock lock(mutex_);
00551 cname = camera_name_;
00552 }
00553
00554 url_type_t url_type = parseURL(resolveURL(url, cname));
00555 return (url_type < URL_invalid);
00556 }
00557
00558 }