camera_info_manager.cpp
Go to the documentation of this file.
1 /* $Id$ */
2 
3 /*********************************************************************
4 * Software License Agreement (BSD License)
5 *
6 * Copyright (c) 2010-2012 Jack O'Quin
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the author nor other contributors may be
20 * used to endorse or promote products derived from this software
21 * without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *********************************************************************/
36 
37 #include <string>
38 #include <locale>
39 #include <stdlib.h>
40 #include <sys/types.h>
41 #include <sys/stat.h>
42 #include <unistd.h>
43 #include <ros/ros.h>
44 #include <ros/package.h>
45 #include <boost/algorithm/string.hpp>
47 
49 
60 namespace camera_info_manager
61 {
62 
63 using namespace camera_calibration_parsers;
64 
66 const std::string
67  default_camera_info_url = "file://${ROS_HOME}/camera_info/${NAME}.yaml";
68 
79  const std::string &cname,
80  const std::string &url):
81  nh_(nh),
82  camera_name_(cname),
83  url_(url),
84  loaded_cam_info_(false)
85 {
86  // register callback for camera calibration service request
87  info_service_ = nh_.advertiseService("set_camera_info",
89 }
90 
106 sensor_msgs::CameraInfo CameraInfoManager::getCameraInfo(void)
107 {
108  while (ros::ok())
109  {
110  std::string cname;
111  std::string url;
112  {
113  boost::mutex::scoped_lock lock_(mutex_);
114  if (loaded_cam_info_)
115  {
116  return cam_info_; // all done
117  }
118 
119  // load being attempted now
120  loaded_cam_info_ = true;
121 
122  // copy the name and URL strings
123  url = url_;
124  cname = camera_name_;
125 
126  } // release the lock
127 
128  // attempt load without the lock, it is not recursive
129  loadCalibration(url, cname);
130  }
131 
132  return sensor_msgs::CameraInfo();
133 }
134 
140 std::string CameraInfoManager::getPackageFileName(const std::string &url)
141 {
142  ROS_DEBUG_STREAM("camera calibration URL: " << url);
143 
144  // Scan URL from after "package://" until next '/' and extract
145  // package name. The parseURL() already checked that it's present.
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));
149 
150  // Look up the ROS package path name.
151  std::string pkgPath(ros::package::getPath(package));
152  if (pkgPath.empty()) // package not found?
153  {
154  ROS_WARN_STREAM("unknown package: " << package << " (ignored)");
155  return pkgPath;
156  }
157  else
158  {
159  // Construct file name from package location and remainder of URL.
160  return pkgPath + url.substr(rest);
161  }
162 }
163 
174 {
175  while (true)
176  {
177  std::string cname;
178  std::string url;
179  {
180  boost::mutex::scoped_lock lock_(mutex_);
181  if (loaded_cam_info_)
182  {
183  return (cam_info_.K[0] != 0.0);
184  }
185 
186  // load being attempted now
187  loaded_cam_info_ = true;
188 
189  // copy the name and URL strings
190  url = url_;
191  cname = camera_name_;
192 
193  } // release the lock
194 
195  // attempt load without the lock, it is not recursive
196  loadCalibration(url, cname);
197  }
198 }
199 
210 bool CameraInfoManager::loadCalibration(const std::string &url,
211  const std::string &cname)
212 {
213  bool success = false; // return value
214 
215  const std::string resURL(resolveURL(url, cname));
216  url_type_t url_type = parseURL(resURL);
217 
218  if (url_type != URL_empty)
219  {
220  ROS_INFO_STREAM("camera calibration URL: " << resURL);
221  }
222 
223  switch (url_type)
224  {
225  case URL_empty:
226  {
227  ROS_INFO("using default calibration URL");
228  success = loadCalibration(default_camera_info_url, cname);
229  break;
230  }
231  case URL_file:
232  {
233  success = loadCalibrationFile(resURL.substr(7), cname);
234  break;
235  }
236  case URL_flash:
237  {
238  ROS_WARN("[CameraInfoManager] reading from flash not implemented yet");
239  break;
240  }
241  case URL_package:
242  {
243  std::string filename(getPackageFileName(resURL));
244  if (!filename.empty())
245  success = loadCalibrationFile(filename, cname);
246  break;
247  }
248  default:
249  {
250  ROS_ERROR_STREAM("Invalid camera calibration URL: " << resURL);
251  break;
252  }
253  }
254 
255  return success;
256 }
257 
268 bool CameraInfoManager::loadCalibrationFile(const std::string &filename,
269  const std::string &cname)
270 {
271  bool success = false;
272 
273  ROS_DEBUG_STREAM("reading camera calibration from " << filename);
274  std::string cam_name;
275  sensor_msgs::CameraInfo cam_info;
276 
277  if (readCalibration(filename, cam_name, cam_info))
278  {
279  if (cname != cam_name)
280  {
281  ROS_WARN_STREAM("[" << cname << "] does not match name "
282  << cam_name << " in file " << filename);
283  }
284  success = true;
285  {
286  // lock only while updating cam_info_
287  boost::mutex::scoped_lock lock(mutex_);
288  cam_info_ = cam_info;
289  }
290  }
291  else
292  {
293  ROS_WARN_STREAM("Camera calibration file " << filename << " not found.");
294  }
295 
296  return success;
297 }
298 
310 bool CameraInfoManager::loadCameraInfo(const std::string &url)
311 {
312  std::string cname;
313  {
314  boost::mutex::scoped_lock lock(mutex_);
315  url_ = url;
316  cname = camera_name_;
317  loaded_cam_info_ = true;
318  }
319 
320  // load using copies of the parameters, no need to hold the lock
321  return loadCalibration(url, cname);
322 }
323 
324 
333 std::string CameraInfoManager::resolveURL(const std::string &url,
334  const std::string &cname)
335 {
336  std::string resolved;
337  size_t rest = 0;
338 
339  while (true)
340  {
341  // find the next '$' in the URL string
342  size_t dollar = url.find('$', rest);
343 
344  if (dollar >= url.length())
345  {
346  // no more variables left in the URL
347  resolved += url.substr(rest);
348  break;
349  }
350 
351  // copy characters up to the next '$'
352  resolved += url.substr(rest, dollar-rest);
353 
354  if (url.substr(dollar+1, 1) != "{")
355  {
356  // no '{' follows, so keep the '$'
357  resolved += "$";
358  }
359  else if (url.substr(dollar+1, 6) == "{NAME}")
360  {
361  // substitute camera name
362  resolved += cname;
363  dollar += 6;
364  }
365  else if (url.substr(dollar+1, 10) == "{ROS_HOME}")
366  {
367  // substitute $ROS_HOME
368  std::string ros_home;
369  char *ros_home_env;
370  if ((ros_home_env = getenv("ROS_HOME")))
371  {
372  // use environment variable
373  ros_home = ros_home_env;
374  }
375  else if ((ros_home_env = getenv("HOME")))
376  {
377  // use "$HOME/.ros"
378  ros_home = ros_home_env;
379  ros_home += "/.ros";
380  }
381  resolved += ros_home;
382  dollar += 10;
383  }
384  else
385  {
386  // not a valid substitution variable
387  ROS_ERROR_STREAM("[CameraInfoManager]"
388  " invalid URL substitution (not resolved): "
389  << url);
390  resolved += "$"; // keep the bogus '$'
391  }
392 
393  // look for next '$'
394  rest = dollar + 1;
395  }
396 
397  return resolved;
398 }
399 
408 {
409  if (url == "")
410  {
411  return URL_empty;
412  }
413  if (boost::iequals(url.substr(0, 8), "file:///"))
414  {
415  return URL_file;
416  }
417  if (boost::iequals(url.substr(0, 9), "flash:///"))
418  {
419  return URL_flash;
420  }
421  if (boost::iequals(url.substr(0, 10), "package://"))
422  {
423  // look for a '/' following the package name, make sure it is
424  // there, the name is not empty, and something follows it
425  size_t rest = url.find('/', 10);
426  if (rest < url.length()-1 && rest > 10)
427  return URL_package;
428  }
429  return URL_invalid;
430 }
431 
442 bool
443 CameraInfoManager::saveCalibration(const sensor_msgs::CameraInfo &new_info,
444  const std::string &url,
445  const std::string &cname)
446 {
447  bool success = false;
448 
449  const std::string resURL(resolveURL(url, cname));
450 
451  switch (parseURL(resURL))
452  {
453  case URL_empty:
454  {
455  // store using default file name
456  success = saveCalibration(new_info, default_camera_info_url, cname);
457  break;
458  }
459  case URL_file:
460  {
461  success = saveCalibrationFile(new_info, resURL.substr(7), cname);
462  break;
463  }
464  case URL_package:
465  {
466  std::string filename(getPackageFileName(resURL));
467  if (!filename.empty())
468  success = saveCalibrationFile(new_info, filename, cname);
469  break;
470  }
471  default:
472  {
473  // invalid URL, save to default location
474  ROS_ERROR_STREAM("invalid url: " << resURL << " (ignored)");
475  success = saveCalibration(new_info, default_camera_info_url, cname);
476  break;
477  }
478  }
479 
480  return success;
481 }
482 
492 bool
493 CameraInfoManager::saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
494  const std::string &filename,
495  const std::string &cname)
496 {
497  ROS_INFO_STREAM("writing calibration data to " << filename);
498 
499  // isolate the name of the containing directory
500  size_t last_slash = filename.rfind('/');
501  if (last_slash >= filename.length())
502  {
503  // No slash in the name. This should never happen, the URL
504  // parser ensures there is at least one '/' at the beginning.
505  ROS_ERROR_STREAM("filename [" << filename << "] has no '/'");
506  return false; // not a valid URL
507  }
508 
509  // make sure the directory exists and is writable
510  std::string dirname(filename.substr(0, last_slash+1));
511  struct stat stat_data;
512  int rc = stat(dirname.c_str(), &stat_data);
513  if (rc != 0)
514  {
515  if (errno == ENOENT)
516  {
517  // directory does not exist, try to create it and its parents
518  std::string command("mkdir -p " + dirname);
519  rc = system(command.c_str());
520  if (rc != 0)
521  {
522  // mkdir failed
523  ROS_ERROR_STREAM("unable to create path to directory ["
524  << dirname << "]");
525  return false;
526  }
527  }
528  else
529  {
530  // not accessible, or something screwy
531  ROS_ERROR_STREAM("directory [" << dirname << "] not accessible");
532  return false;
533  }
534  }
535  else if (!S_ISDIR(stat_data.st_mode))
536  {
537  // dirname exists but is not a directory
538  ROS_ERROR_STREAM("[" << dirname << "] is not a directory");
539  return false;
540  }
541 
542  // Directory exists and is accessible. Permissions might still be bad.
543 
544  // Currently, writeCalibration() always returns true no matter what
545  // (ros-pkg ticket #5010).
546  return writeCalibration(filename, cname, new_info);
547 }
548 
557 bool
558 CameraInfoManager::setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
559  sensor_msgs::SetCameraInfo::Response &rsp)
560 {
561  // copies of class variables needed for saving calibration
562  std::string url_copy;
563  std::string cname;
564  {
565  boost::mutex::scoped_lock lock(mutex_);
566  cam_info_ = req.camera_info;
567  url_copy = url_;
568  cname = camera_name_;
569  loaded_cam_info_ = true;
570  }
571 
572  if (!nh_.ok())
573  {
574  ROS_ERROR("set_camera_info service called, but driver not running.");
575  rsp.status_message = "Camera driver not running.";
576  rsp.success = false;
577  return false;
578  }
579 
580  rsp.success = saveCalibration(req.camera_info, url_copy, cname);
581  if (!rsp.success)
582  rsp.status_message = "Error storing camera calibration.";
583 
584  return true;
585 }
586 
597 bool CameraInfoManager::setCameraName(const std::string &cname)
598 {
599  // the camera name may not be empty
600  if (cname.empty())
601  return false;
602 
603  // validate the camera name characters
604  for (unsigned i = 0; i < cname.size(); ++i)
605  {
606  if (!isalnum(cname[i]) && cname[i] != '_')
607  return false;
608  }
609 
610  // The name is valid, so update our private copy. Since the new
611  // name might cause the existing URL to resolve somewhere else,
612  // force @c cam_info_ to be reloaded before being used again.
613  {
614  boost::mutex::scoped_lock lock(mutex_);
615  camera_name_ = cname;
616  loaded_cam_info_ = false;
617  }
618 
619  return true;
620 }
621 
630 bool CameraInfoManager::setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
631 {
632  boost::mutex::scoped_lock lock(mutex_);
633 
634  cam_info_ = camera_info;
635  loaded_cam_info_ = true;
636 
637  return true;
638 }
639 
647 bool CameraInfoManager::validateURL(const std::string &url)
648 {
649  std::string cname; // copy of camera name
650  {
651  boost::mutex::scoped_lock lock(mutex_);
652  cname = camera_name_;
653  } // release the lock
654 
655  url_type_t url_type = parseURL(resolveURL(url, cname));
656  return (url_type < URL_invalid);
657 }
658 
659 } // namespace camera_info_manager
bool saveCalibration(const sensor_msgs::CameraInfo &new_info, const std::string &url, const std::string &cname)
sensor_msgs::CameraInfo getCameraInfo(void)
string package
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)
#define ROS_WARN(...)
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)
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
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)
bool ok() const
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR(...)
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)
bool setCameraName(const std::string &cname)


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Thu Jun 6 2019 19:22:55