cuda updated

This commit is contained in:
g-spacewhale
2019-03-15 09:42:59 +00:00
parent ea93237912
commit f4eb906896
4 changed files with 35 additions and 10 deletions

View File

@ -312,7 +312,7 @@ private:
const std::vector<unsigned char>& markers,
std::vector<T>& refined_vec) {
if (raw_vec.size() != markers.size()) {
ROS_WARN("The input size of raw_vec(%lu) and markers(%lu) does not match...",
ROS_WARN("The input size of raw_vec(%i) and markers(%i) does not match...",
raw_vec.size(), markers.size());
}
for (int i = 0; i < markers.size(); ++i) {
@ -367,8 +367,8 @@ 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_curr_img;
cv::cuda::GpuMat cam1_curr_img;
cv::cuda::GpuMat cam0_points_gpu;
cv::cuda::GpuMat cam1_points_gpu;

View File

@ -22,8 +22,8 @@ namespace 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);
void download(const cv::cuda::GpuMat& d_mat, std::vector<uchar>& vec);
void download(const cv::cuda::GpuMat& d_mat, std::vector<cv::Point2f>& vec);
Eigen::Isometry3d getTransformEigen(const ros::NodeHandle &nh,
const std::string &field);