camera_info_manager.h
Go to the documentation of this file.
1 /* -*- mode: C++ -*- */
2 /* $Id$ */
3 
4 /*********************************************************************
5 * Software License Agreement (BSD License)
6 *
7 * Copyright (c) 2010-2012 Jack O'Quin
8 * All rights reserved.
9 *
10 * Redistribution and use in source and binary forms, with or without
11 * modification, are permitted provided that the following conditions
12 * are met:
13 *
14 * * Redistributions of source code must retain the above copyright
15 * notice, this list of conditions and the following disclaimer.
16 * * Redistributions in binary form must reproduce the above
17 * copyright notice, this list of conditions and the following
18 * disclaimer in the documentation and/or other materials provided
19 * with the distribution.
20 * * Neither the name of the author nor other contributors may be
21 * used to endorse or promote products derived from this software
22 * without specific prior written permission.
23 *
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35 * POSSIBILITY OF SUCH DAMAGE.
36 *********************************************************************/
37 
38 #ifndef _CAMERA_INFO_MANAGER_H_
39 #define _CAMERA_INFO_MANAGER_H_
40 
41 #include <ros/ros.h>
42 #include <boost/thread/mutex.hpp>
43 #include <sensor_msgs/CameraInfo.h>
44 #include <sensor_msgs/SetCameraInfo.h>
45 
46 #include <ros/macros.h>
47 
48 // Import/export for windows dll's and visibility for gcc shared libraries.
49 
50 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
51  #ifdef camera_info_manager_EXPORTS // we are building a shared lib/dll
52  #define CAMERA_INFO_MANAGER_DECL ROS_HELPER_EXPORT
53  #else // we are using shared lib/dll
54  #define CAMERA_INFO_MANAGER_DECL ROS_HELPER_IMPORT
55  #endif
56 #else // ros is being built around static libraries
57  #define CAMERA_INFO_MANAGER_DECL
58 #endif
59 
68 {
69 
189 {
190  public:
191 
193  const std::string &cname="camera",
194  const std::string &url="");
195  virtual ~CameraInfoManager();
196 
197  virtual sensor_msgs::CameraInfo getCameraInfo(void);
198  virtual bool isCalibrated(void);
199  virtual bool loadCameraInfo(const std::string &url);
200  virtual std::string resolveURL(const std::string &url,
201  const std::string &cname);
202  virtual bool setCameraName(const std::string &cname);
203  virtual bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info);
204  virtual bool validateURL(const std::string &url);
205 
206  private:
207 
208  // recognized URL types
209  typedef enum
210  {
211  // supported URLs
212  URL_empty = 0, // empty string
213  URL_file, // file:
214  URL_package, // package:
215  // URLs not supported
216  URL_invalid, // anything >= is invalid
217  URL_flash, // flash:
218  } url_type_t;
219 
220  // private methods
221  std::string getPackageFileName(const std::string &url);
222  virtual bool loadCalibration(const std::string &url,
223  const std::string &cname);
224  virtual bool loadCalibrationFile(const std::string &filename,
225  const std::string &cname);
226  virtual bool loadCalibrationFlash(const std::string &flashURL,
227  const std::string &cname);
228  url_type_t parseURL(const std::string &url);
229  virtual bool saveCalibration(const sensor_msgs::CameraInfo &new_info,
230  const std::string &url,
231  const std::string &cname);
232  virtual bool saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
233  const std::string &filename,
234  const std::string &cname);
235  virtual bool saveCalibrationFlash(const sensor_msgs::CameraInfo &new_info,
236  const std::string &flashURL,
237  const std::string &cname);
238  virtual bool setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
239  sensor_msgs::SetCameraInfo::Response &rsp);
240 
249  boost::mutex mutex_;
250 
251  // private data
254  std::string camera_name_;
255  std::string url_;
256  sensor_msgs::CameraInfo cam_info_;
258 
259 }; // class CameraInfoManager
260 
261 } // namespace camera_info_manager
262 
263 #endif // _CAMERA_INFO_MANAGER_H_
camera_info_manager::CameraInfoManager::info_service_
ros::ServiceServer info_service_
set_camera_info service
Definition: camera_info_manager.h:253
camera_info_manager::CameraInfoManager::camera_name_
std::string camera_name_
camera name
Definition: camera_info_manager.h:254
ros.h
camera_info_manager::CameraInfoManager::URL_file
@ URL_file
Definition: camera_info_manager.h:213
CAMERA_INFO_MANAGER_DECL
#define CAMERA_INFO_MANAGER_DECL
Definition: camera_info_manager.h:57
camera_info_manager::CameraInfoManager::URL_invalid
@ URL_invalid
Definition: camera_info_manager.h:216
ros::ServiceServer
camera_info_manager::CameraInfoManager::URL_package
@ URL_package
Definition: camera_info_manager.h:214
camera_info_manager::CameraInfoManager
CameraInfo Manager class.
Definition: camera_info_manager.h:188
camera_info_manager
Definition: camera_info_manager.h:67
camera_info_manager::CameraInfoManager::mutex_
boost::mutex mutex_
mutual exclusion lock for private data
Definition: camera_info_manager.h:249
camera_info_manager::CameraInfoManager::cam_info_
sensor_msgs::CameraInfo cam_info_
current CameraInfo
Definition: camera_info_manager.h:256
camera_info_manager::CameraInfoManager::loaded_cam_info_
bool loaded_cam_info_
cam_info_ load attempted
Definition: camera_info_manager.h:257
camera_info_manager::CameraInfoManager::URL_flash
@ URL_flash
Definition: camera_info_manager.h:217
macros.h
ros::NodeHandle
camera_info_manager::CameraInfoManager::url_
std::string url_
URL for calibration data.
Definition: camera_info_manager.h:255
camera_info_manager::CameraInfoManager::nh_
ros::NodeHandle nh_
node handle for service
Definition: camera_info_manager.h:252


camera_info_manager
Author(s): Jack O'Quin
autogenerated on Sat Jan 20 2024 03:14:54