41 #ifndef INCLUDE_OKVIS_ROSPARAMETERSREADER_HPP_
42 #define INCLUDE_OKVIS_ROSPARAMETERSREADER_HPP_
50 #pragma GCC diagnostic push
51 #pragma GCC diagnostic ignored "-Wnon-virtual-dtor"
53 #pragma GCC diagnostic pop
54 #include <ros/callback_queue.h>
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;
62 #include <visensor_msgs/visensor_calibration.h>
63 #include <visensor_msgs/visensor_calibration_service.h>
66 #ifdef HAVE_LIBVISENSOR
67 #include <visensor/visensor_api.hpp>
106 std::vector<
CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations,
107 cv::FileStorage& configurationFile);
115 std::vector<
CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations)
const;
124 std::vector<
CameraCalibration,Eigen::aligned_allocator<CameraCalibration>> & calibrations)
const;
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