Add common functions for loading calibration with some error checking
From Bernd
This commit is contained in:
34
include/msckf_vio/utils.h
Normal file
34
include/msckf_vio/utils.h
Normal file
@ -0,0 +1,34 @@
|
||||
/*
|
||||
* COPYRIGHT AND PERMISSION NOTICE
|
||||
* Penn Software MSCKF_VIO
|
||||
* Copyright (C) 2017 The Trustees of the University of Pennsylvania
|
||||
* All rights reserved.
|
||||
*/
|
||||
|
||||
#ifndef MSCKF_VIO_UTILS_H
|
||||
#define MSCKF_VIO_UTILS_H
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <string>
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
namespace msckf_vio {
|
||||
/*
|
||||
* @brief utilities for msckf_vio
|
||||
*/
|
||||
namespace utils {
|
||||
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
|
||||
const std::string &field);
|
||||
|
||||
cv::Mat getTransformCV(const ros::NodeHandle &nh,
|
||||
const std::string &field);
|
||||
|
||||
cv::Mat getVec16Transform(const ros::NodeHandle &nh,
|
||||
const std::string &field);
|
||||
|
||||
cv::Mat getKalibrStyleTransform(const ros::NodeHandle &nh,
|
||||
const std::string &field);
|
||||
}
|
||||
}
|
||||
#endif
|
Reference in New Issue
Block a user