initial commit
This commit is contained in:
@ -14,6 +14,10 @@
|
||||
#include <opencv2/opencv.hpp>
|
||||
#include <opencv2/video.hpp>
|
||||
|
||||
#include <opencv2/cudaoptflow.hpp>
|
||||
#include <opencv2/cudaimgproc.hpp>
|
||||
#include <opencv2/cudaarithm.hpp>
|
||||
|
||||
#include <ros/ros.h>
|
||||
#include <cv_bridge/cv_bridge.h>
|
||||
#include <image_transport/image_transport.h>
|
||||
@ -363,6 +367,11 @@ private:
|
||||
boost::shared_ptr<GridFeatures> prev_features_ptr;
|
||||
boost::shared_ptr<GridFeatures> curr_features_ptr;
|
||||
|
||||
cv::cuda::GpuMat curr_cam0_pyramid_gpu;
|
||||
cv::cuda::GpuMat curr_cam1_pyramid_gpu;
|
||||
cv::cuda::GpuMat cam0_points_gpu;
|
||||
cv::cuda::GpuMat cam1_points_gpu;
|
||||
|
||||
// Number of features after each outlier removal step.
|
||||
int before_tracking;
|
||||
int after_tracking;
|
||||
|
@ -11,6 +11,9 @@
|
||||
#include <ros/ros.h>
|
||||
#include <string>
|
||||
#include <opencv2/core/core.hpp>
|
||||
#include <opencv2/cudaoptflow.hpp>
|
||||
#include <opencv2/cudaimgproc.hpp>
|
||||
#include <opencv2/cudaarithm.hpp>
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
namespace msckf_vio {
|
||||
@ -18,6 +21,10 @@ namespace msckf_vio {
|
||||
* @brief utilities for msckf_vio
|
||||
*/
|
||||
namespace utils {
|
||||
|
||||
static void download(const cv::cuda::GpuMat& d_mat, std::vector<uchar>& vec);
|
||||
static void download(const cv::cuda::GpuMat& d_mat, std::vector<cv::Point2f>& vec);
|
||||
|
||||
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
|
||||
const std::string &field);
|
||||
|
||||
|
Reference in New Issue
Block a user