OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
RosParametersReader.hpp
Go to the documentation of this file.
1 /*********************************************************************************
2  * OKVIS - Open Keyframe-based Visual-Inertial SLAM
3  * Copyright (c) 2015, Autonomous Systems Lab / ETH Zurich
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of Autonomous Systems Lab / ETH Zurich nor the names of
14  * its contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: Jul 20, 2015
30  * Author: Andreas Forster (an.forster@gmail.com)
31  * Modified: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
32  *********************************************************************************/
33 
41 #ifndef INCLUDE_OKVIS_ROSPARAMETERSREADER_HPP_
42 #define INCLUDE_OKVIS_ROSPARAMETERSREADER_HPP_
43 
44 #include <string>
45 
47 #include <okvis/assert_macros.hpp>
48 #include <okvis/Parameters.hpp>
49 
50 #pragma GCC diagnostic push
51 #pragma GCC diagnostic ignored "-Wnon-virtual-dtor"
52 #include <ros/ros.h>
53 #pragma GCC diagnostic pop
54 #include <ros/callback_queue.h>
55 
56 #ifdef HAVE_VISENSOR
57  #ifdef USE_VISENSORNODE_V1_1 // TODO: remove this as soon as the public visensor_node gets updated!
58  #include <visensor_node/visensor_calibration.h>
59  #include <visensor_node/visensor_calibration_service.h>
60  namespace visensor_msgs = visensor_node;
61  #else
62  #include <visensor_msgs/visensor_calibration.h>
63  #include <visensor_msgs/visensor_calibration_service.h>
64  #endif
65 #endif
66 #ifdef HAVE_LIBVISENSOR
67  #include <visensor/visensor_api.hpp>
68 #endif
69 
71 namespace okvis {
72 
77  public:
78 
79  OKVIS_DEFINE_EXCEPTION(Exception,std::runtime_error)
80 
81 
83 
88  RosParametersReader(const std::string& filename);
89 
90  private:
91 
105  virtual bool getCameraCalibration(
106  std::vector<CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations,
107  cv::FileStorage& configurationFile);
108 
115  std::vector<CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations) const;
116 
124  std::vector<CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations) const;
125 
126 };
127 
128 }
129 
130 #endif /* INCLUDE_OKVIS_ROSPARAMETERSREADER_HPP_ */
virtual bool getCameraCalibration(std::vector< CameraCalibration, Eigen::aligned_allocator< CameraCalibration >> &calibrations, cv::FileStorage &configurationFile)
Get the camera calibration.
Definition: RosParametersReader.cpp:60
bool getCalibrationViaRosService(std::vector< CameraCalibration, Eigen::aligned_allocator< CameraCalibration >> &calibrations) const
Get the camera calibration via the ROS service advertised by the visensor node.
Definition: RosParametersReader.cpp:99
Struct that contains all the camera calibration information.
Definition: VioParametersReader.hpp:104
#define OKVIS_DEFINE_EXCEPTION(exceptionName, exceptionParent)
Macro for defining an exception with a given parent.
Definition: assert_macros.hpp:52
This file contains some useful assert macros.
bool getCalibrationViaRosTopic(std::vector< CameraCalibration, Eigen::aligned_allocator< CameraCalibration >> &calibrations) const
Get the camera calibration via the ROS topic /calibrationX.
Definition: RosParametersReader.cpp:168
Header file for the VioParametersReader class.
This class extends the VioParametersReader class in order to use ROS services and topics...
Definition: RosParametersReader.hpp:76
RosParametersReader()
The default constructor.
Definition: RosParametersReader.cpp:49
This file contains struct definitions that encapsulate parameters and settings.
This class reads and parses config file.
Definition: VioParametersReader.hpp:60