40 #include <sys/types.h> 45 #include <boost/algorithm/string.hpp> 79 const std::string &cname,
80 const std::string &url):
84 loaded_cam_info_(false)
113 boost::mutex::scoped_lock lock_(
mutex_);
132 return sensor_msgs::CameraInfo();
146 size_t prefix_len = std::string(
"package://").length();
147 size_t rest = url.find(
'/', prefix_len);
148 std::string
package(url.substr(prefix_len, rest - prefix_len));
160 return pkgPath + url.substr(rest);
180 boost::mutex::scoped_lock lock_(
mutex_);
211 const std::string &cname)
213 bool success =
false;
215 const std::string resURL(
resolveURL(url, cname));
227 ROS_INFO(
"using default calibration URL");
238 ROS_WARN(
"[CameraInfoManager] reading from flash not implemented yet");
244 if (!filename.empty())
269 const std::string &cname)
271 bool success =
false;
274 std::string cam_name;
275 sensor_msgs::CameraInfo cam_info;
279 if (cname != cam_name)
282 << cam_name <<
" in file " << filename);
287 boost::mutex::scoped_lock lock(
mutex_);
293 ROS_WARN_STREAM(
"Camera calibration file " << filename <<
" not found.");
314 boost::mutex::scoped_lock lock(
mutex_);
334 const std::string &cname)
336 std::string resolved;
342 size_t dollar = url.find(
'$', rest);
344 if (dollar >= url.length())
347 resolved += url.substr(rest);
352 resolved += url.substr(rest, dollar-rest);
354 if (url.substr(dollar+1, 1) !=
"{")
359 else if (url.substr(dollar+1, 6) ==
"{NAME}")
365 else if (url.substr(dollar+1, 10) ==
"{ROS_HOME}")
368 std::string ros_home;
370 if ((ros_home_env = getenv(
"ROS_HOME")))
373 ros_home = ros_home_env;
375 else if ((ros_home_env = getenv(
"HOME")))
378 ros_home = ros_home_env;
381 resolved += ros_home;
388 " invalid URL substitution (not resolved): " 413 if (boost::iequals(url.substr(0, 8),
"file:///"))
417 if (boost::iequals(url.substr(0, 9),
"flash:///"))
421 if (boost::iequals(url.substr(0, 10),
"package://"))
425 size_t rest = url.find(
'/', 10);
426 if (rest < url.length()-1 && rest > 10)
444 const std::string &url,
445 const std::string &cname)
447 bool success =
false;
449 const std::string resURL(
resolveURL(url, cname));
467 if (!filename.empty())
494 const std::string &filename,
495 const std::string &cname)
500 size_t last_slash = filename.rfind(
'/');
501 if (last_slash >= filename.length())
510 std::string dirname(filename.substr(0, last_slash+1));
511 struct stat stat_data;
512 int rc = stat(dirname.c_str(), &stat_data);
518 std::string
command(
"mkdir -p " + dirname);
519 rc = system(command.c_str());
535 else if (!S_ISDIR(stat_data.st_mode))
559 sensor_msgs::SetCameraInfo::Response &rsp)
562 std::string url_copy;
565 boost::mutex::scoped_lock lock(
mutex_);
574 ROS_ERROR(
"set_camera_info service called, but driver not running.");
575 rsp.status_message =
"Camera driver not running.";
582 rsp.status_message =
"Error storing camera calibration.";
604 for (
unsigned i = 0; i < cname.size(); ++i)
606 if (!isalnum(cname[i]) && cname[i] !=
'_')
614 boost::mutex::scoped_lock lock(
mutex_);
632 boost::mutex::scoped_lock lock(
mutex_);
651 boost::mutex::scoped_lock lock(
mutex_);
bool saveCalibration(const sensor_msgs::CameraInfo &new_info, const std::string &url, const std::string &cname)
sensor_msgs::CameraInfo getCameraInfo(void)
bool loaded_cam_info_
cam_info_ load attempted
def readCalibration(file_name)
std::string url_
URL for calibration data.
std::string getPackageFileName(const std::string &url)
bool loadCameraInfo(const std::string &url)
std::string resolveURL(const std::string &url, const std::string &cname)
ros::ServiceServer info_service_
set_camera_info service
sensor_msgs::CameraInfo cam_info_
current CameraInfo
CameraInfo Manager interface.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const std::string default_camera_info_url
bool loadCalibrationFile(const std::string &filename, const std::string &cname)
url_type_t parseURL(const std::string &url)
bool validateURL(const std::string &url)
boost::mutex mutex_
mutual exclusion lock for private data
CameraInfoManager(ros::NodeHandle nh, const std::string &cname="camera", const std::string &url="")
ROSLIB_DECL std::string command(const std::string &cmd)
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
ros::NodeHandle nh_
node handle for service
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
ROSLIB_DECL std::string getPath(const std::string &package_name)
#define ROS_INFO_STREAM(args)
bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
bool loadCalibration(const std::string &url, const std::string &cname)
#define ROS_ERROR_STREAM(args)
bool setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
bool saveCalibrationFile(const sensor_msgs::CameraInfo &new_info, const std::string &filename, const std::string &cname)
std::string camera_name_
camera name
bool setCameraName(const std::string &cname)