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 
54 {
55 
175 {
176  public:
177 
179  const std::string &cname="camera",
180  const std::string &url="");
181 
182  sensor_msgs::CameraInfo getCameraInfo(void);
183  bool isCalibrated(void);
184  bool loadCameraInfo(const std::string &url);
185  std::string resolveURL(const std::string &url,
186  const std::string &cname);
187  bool setCameraName(const std::string &cname);
188  bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info);
189  bool validateURL(const std::string &url);
190 
191  private:
192 
193  // recognized URL types
194  typedef enum
195  {
196  // supported URLs
197  URL_empty = 0, // empty string
198  URL_file, // file:
199  URL_package, // package:
200  // URLs not supported
201  URL_invalid, // anything >= is invalid
202  URL_flash, // flash:
203  } url_type_t;
204 
205  // private methods
206  std::string getPackageFileName(const std::string &url);
207  bool loadCalibration(const std::string &url,
208  const std::string &cname);
209  bool loadCalibrationFile(const std::string &filename,
210  const std::string &cname);
211  url_type_t parseURL(const std::string &url);
212  bool saveCalibration(const sensor_msgs::CameraInfo &new_info,
213  const std::string &url,
214  const std::string &cname);
215  bool saveCalibrationFile(const sensor_msgs::CameraInfo &new_info,
216  const std::string &filename,
217  const std::string &cname);
218  bool setCameraInfoService(sensor_msgs::SetCameraInfo::Request &req,
219  sensor_msgs::SetCameraInfo::Response &rsp);
220 
229  boost::mutex mutex_;
230 
231  // private data
234  std::string camera_name_;
235  std::string url_;
236  sensor_msgs::CameraInfo cam_info_;
238 
239 }; // class CameraInfoManager
240 
241 }; // namespace camera_info_manager
242 
243 #endif // _CAMERA_INFO_MANAGER_H_
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
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
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="")
ros::NodeHandle nh_
node handle for service
bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
bool loadCalibration(const std::string &url, const std::string &cname)
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