35 lines
890 B
C++
35 lines
890 B
C++
#ifndef MSCKF_VIO_IMAGE_HANDLER_H
|
|
#define MSCKF_VIO_IMAGE_HANDLER_H
|
|
|
|
#include <ros/ros.h>
|
|
#include <string>
|
|
#include <opencv2/opencv.hpp>
|
|
#include <opencv2/video.hpp>
|
|
#include <cv_bridge/cv_bridge.h>
|
|
#include <Eigen/Geometry>
|
|
#include <vector>
|
|
|
|
namespace msckf_vio {
|
|
/*
|
|
* @brief utilities for msckf_vio
|
|
*/
|
|
namespace image_handler {
|
|
|
|
void undistortPoints(
|
|
const std::vector<cv::Point2f>& pts_in,
|
|
const cv::Vec4d& intrinsics,
|
|
const std::string& distortion_model,
|
|
const cv::Vec4d& distortion_coeffs,
|
|
std::vector<cv::Point2f>& pts_out,
|
|
const cv::Matx33d &rectification_matrix = cv::Matx33d::eye(),
|
|
const cv::Vec4d &new_intrinsics = cv::Vec4d(1,1,0,0));
|
|
|
|
std::vector<cv::Point2f> distortPoints(
|
|
const std::vector<cv::Point2f>& pts_in,
|
|
const cv::Vec4d& intrinsics,
|
|
const std::string& distortion_model,
|
|
const cv::Vec4d& distortion_coeffs);
|
|
}
|
|
}
|
|
#endif
|