40 #include <sys/types.h>
44 #define S_ISDIR(mode) (((mode) & S_IFMT) == S_IFDIR)
52 #include <boost/algorithm/string.hpp>
86 const std::string &cname,
87 const std::string &url):
91 loaded_cam_info_(false)
120 boost::mutex::scoped_lock lock_(
mutex_);
139 return sensor_msgs::CameraInfo();
153 size_t prefix_len = std::string(
"package://").length();
154 size_t rest = url.find(
'/', prefix_len);
155 std::string
package(url.substr(prefix_len, rest - prefix_len));
167 return pkgPath + url.substr(rest);
187 boost::mutex::scoped_lock lock_(
mutex_);
218 const std::string &cname)
220 bool success =
false;
222 const std::string resURL(
resolveURL(url, cname));
234 ROS_INFO(
"using default calibration URL");
245 ROS_WARN(
"[CameraInfoManager] reading from flash not implemented yet");
251 if (!filename.empty())
276 const std::string &cname)
278 bool success =
false;
281 std::string cam_name;
282 sensor_msgs::CameraInfo cam_info;
286 if (cname != cam_name)
289 << cam_name <<
" in file " << filename);
294 boost::mutex::scoped_lock lock(
mutex_);
300 ROS_WARN_STREAM(
"Camera calibration file " << filename <<
" not found.");
321 boost::mutex::scoped_lock lock(
mutex_);
341 const std::string &cname)
343 std::string resolved;
349 size_t dollar = url.find(
'$', rest);
351 if (dollar >= url.length())
354 resolved += url.substr(rest);
359 resolved += url.substr(rest, dollar-rest);
361 if (url.substr(dollar+1, 1) !=
"{")
366 else if (url.substr(dollar+1, 6) ==
"{NAME}")
372 else if (url.substr(dollar+1, 10) ==
"{ROS_HOME}")
375 std::string ros_home;
377 if ((ros_home_env = getenv(
"ROS_HOME")))
380 ros_home = ros_home_env;
382 else if ((ros_home_env = getenv(
"HOME")))
385 ros_home = ros_home_env;
388 resolved += ros_home;
395 " invalid URL substitution (not resolved): "
420 if (boost::iequals(url.substr(0, 8),
"file:///"))
424 if (boost::iequals(url.substr(0, 9),
"flash:///"))
428 if (boost::iequals(url.substr(0, 10),
"package://"))
432 size_t rest = url.find(
'/', 10);
433 if (rest < url.length()-1 && rest > 10)
451 const std::string &url,
452 const std::string &cname)
454 bool success =
false;
456 const std::string resURL(
resolveURL(url, cname));
474 if (!filename.empty())
501 const std::string &filename,
502 const std::string &cname)
507 size_t last_slash = filename.rfind(
'/');
508 if (last_slash >= filename.length())
517 std::string dirname(filename.substr(0, last_slash+1));
518 struct stat stat_data;
519 int rc = stat(dirname.c_str(), &stat_data);
525 std::string
command(
"mkdir -p " + dirname);
542 else if (!S_ISDIR(stat_data.st_mode))
566 sensor_msgs::SetCameraInfo::Response &rsp)
569 std::string url_copy;
572 boost::mutex::scoped_lock lock(
mutex_);
581 ROS_ERROR(
"set_camera_info service called, but driver not running.");
582 rsp.status_message =
"Camera driver not running.";
589 rsp.status_message =
"Error storing camera calibration.";
611 for (
unsigned i = 0; i < cname.size(); ++i)
613 if (!isalnum(cname[i]) && cname[i] !=
'_')
621 boost::mutex::scoped_lock lock(
mutex_);
639 boost::mutex::scoped_lock lock(
mutex_);
658 boost::mutex::scoped_lock lock(
mutex_);