camera_info_manager.h
Go to the documentation of this file.
00001 /* -*- mode: C++ -*- */
00002 /* $Id$ */
00003 
00004 /*********************************************************************
00005 * Software License Agreement (BSD License)
00006 *
00007 *  Copyright (c) 2010-2012 Jack O'Quin
00008 *  All rights reserved.
00009 *
00010 *  Redistribution and use in source and binary forms, with or without
00011 *  modification, are permitted provided that the following conditions
00012 *  are met:
00013 *
00014 *   * Redistributions of source code must retain the above copyright
00015 *     notice, this list of conditions and the following disclaimer.
00016 *   * Redistributions in binary form must reproduce the above
00017 *     copyright notice, this list of conditions and the following
00018 *     disclaimer in the documentation and/or other materials provided
00019 *     with the distribution.
00020 *   * Neither the name of the author nor other contributors may be
00021 *     used to endorse or promote products derived from this software
00022 *     without specific prior written permission.
00023 *
00024 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035 *  POSSIBILITY OF SUCH DAMAGE.
00036 *********************************************************************/
00037 
00038 #ifndef _CAMERA_INFO_MANAGER_H_
00039 #define _CAMERA_INFO_MANAGER_H_
00040 
00041 #include <ros/ros.h>
00042 #include <boost/thread/mutex.hpp>
00043 #include <sensor_msgs/CameraInfo.h>
00044 #include <sensor_msgs/SetCameraInfo.h>
00045 
00053 namespace camera_info_manager
00054 {
00055 
00174 class CameraInfoManager
00175 {
00176  public:
00177 
00178   CameraInfoManager(ros::NodeHandle nh,
00179                     const std::string &cname="camera",
00180                     const std::string &url="");
00181 
00182   sensor_msgs::CameraInfo getCameraInfo(void);
00183   bool isCalibrated(void);
00184   bool loadCameraInfo(const std::string &url);
00185   std::string resolveURL(const std::string &url,
00186                          const std::string &cname);
00187   bool setCameraName(const std::string &cname);
00188   bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info);
00189   bool validateURL(const std::string &url);
00190 
00191  private:
00192 
00193   // recognized URL types
00194   typedef enum
00195     {
00196       // supported URLs
00197       URL_empty = 0,             // empty string
00198       URL_file,                  // file:
00199       URL_package,               // package: 
00200       // URLs not supported
00201       URL_invalid,               // anything >= is invalid
00202       URL_flash,                 // flash: 
00203     } url_type_t;
00204 
00205   // private methods
00206   std::string getPackageFileName(const std::string &url);
00207   bool loadCalibration(const std::string &url,
00208                        const std::string &cname);
00209   bool loadCalibrationFile(const std::string &filename,
00210                            const std::string &cname);
00211   url_type_t parseURL(const std::string &url);
00212   bool saveCalibration(const sensor_msgs::CameraInfo &new_info,
00213                        const std::string &url,
00214                        const std::string &cname);
00215   bool saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
00216                            const std::string &filename,
00217                            const std::string &cname);
00218   bool setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
00219                             sensor_msgs::SetCameraInfo::Response &rsp);
00220 
00229   boost::mutex mutex_;
00230 
00231   // private data
00232   ros::NodeHandle nh_;                  
00233   ros::ServiceServer info_service_;     
00234   std::string camera_name_;             
00235   std::string url_;                     
00236   sensor_msgs::CameraInfo cam_info_;    
00237   bool loaded_cam_info_;                
00238 
00239 }; // class CameraInfoManager
00240 
00241 }; // namespace camera_info_manager
00242 
00243 #endif // _CAMERA_INFO_MANAGER_H_


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Thu Jun 6 2019 21:20:02