【slam十四讲第二版】【课本例题代码向】【第五讲~相机与图像】【opencv3.4.1安装】【OpenCV、图像去畸变、双目和RGB-D、遍历图像像素14种】

【slam十四讲第二版】【课本例题代码向】【第五讲~相机与图像】【opencv3.4.1安装】【OpenCV、图像去畸变、双目和RGB-D、遍历图像像素14种】

  • 0 前言
  • 1 opencv3.4.1安装
    • 1.1 安装依赖遇见的问题
  • 2 占坑用
  • 3 OpenCV基本使用方法
    • 3.1 imageBasics.cpp
    • 3.2 CMakeListx.txt
    • 3.3 运行
  • 4 图像去畸变
    • 4.1 undistortImage.cpp
    • 4.2 CMakeLits.txt
  • 5 双目视觉 | 使用pangolin画出点云 | 计算视差
    • 5.1 stereoVision.cpp
    • 5.2 CMakeLists.txt
  • 6 RGB-D视觉
    • 6.1 joinMap.cpp
    • 6.2 CMakeLists.txt
  • 7 遍历图像像素的14种方法
    • 7.1 bian_li_tupian.cpp
    • 7.2 CMakeLists.txt
    • 7.3 注意事项

【slam十四讲第二版】【课本例题代码向】【第三~四讲刚体运动、李群和李代数】【eigen3.3.4和pangolin安装,Sophus及fim的安装使用】【绘制轨迹】【计算轨迹误差】

0 前言

看完课本,就打算把课后的代码都实现一遍,虽然前四讲确实不难,但是发现之后在实现的过程中会遇到越来越多的问题,考虑到自己的记性实在太差,为了解决学过之后,某些问题有印象但是不知道从何找起的难题,所以有了这篇记录

  • 总之本篇文章内容包括:
  1. 第二版slam十四讲,第五讲开始的所有代码复现、遇到的问题、感悟(之所以是第五讲,因为前四将看过了)
  2. 待续

1 opencv3.4.1安装

  • opencv3.4.1的安装
  • 此处的opencv版本为3.4.1 ,opencv的安装可以参照Ubuntu18.04下 ORB_SLAM2的安装与配置
  • 如果上文中中的opencv网盘链接失效,可以看下面的
    链接:https://pan.baidu.com/s/1Wcnfj1eC7Dp6sgspBnOr_g
    提取码:tgqh
  • 安装亲测没有问题
  1. 安装依赖
sudo apt-get install build-essential libgtk2.0-dev libavcodec-dev libavformat-dev libjpeg.dev libtiff5.dev libswscale-dev libjasper-dev  

可能会遇到问题,参考1.1
2. 编译

cd opencv-3.4.1/
mkdir build
cd build
cmake -D CMAKE_BUILD_TYPE=Release –D CMAKE_INSTALL_PREFIX=/usr/local ..
sudo make
sudo make install
  1. 配置环境
sudo gedit /etc/ld.so.conf.d/opencv.conf 

在opencv.conf 中添加如下内容

/usr/local/lib  

然后使刚配置路径生效

sudo ldconfig  
  1. 打开bash文件,配置bash
sudo gedit /etc/bash.bashrc  

在打开的bash.bashrc的最末尾添加如下代码

PKG_CONFIG_PATH=$PKG_CONFIG_PATH:/usr/local/lib/pkgconfig  
export PKG_CONFIG_PATH  

保存关闭文件,使刚才的配置生效

source /etc/bash.bashrc  

完成

1.1 安装依赖遇见的问题

  • 问题描述
bupo@bupo-vpc:~/anzhuang/opencv-3.4.1$ sudo apt-get install build-essential libgtk2.0-dev libavcodec-dev libavformat-dev libjpeg.dev libtiff5.dev libswscale-dev libjasper-dev  
[sudo] bupo 的密码: 
正在读取软件包列表... 完成
正在分析软件包的依赖关系树       
正在读取状态信息... 完成       
注意,根据正则表达式 'libjpeg.dev' 选中了 'libjpeg-dev'
注意,根据正则表达式 'libtiff5.dev' 选中了 'libtiff5-dev'
E: 无法定位软件包 libjasper-dev
  • 解决方案
sudo add-apt-repository "deb http://security.ubuntu.com/ubuntu xenial-security main"
sudo apt update
sudo apt install libjasper1 libjasper-dev

成功后重新安装依赖

  • 参考:嵌入式程序调试与opencv图像库

2 占坑用

3 OpenCV基本使用方法

  • 可以参考我的:【Opencv】【OpenCV实践】【OpenCV的使用学习记录】

3.1 imageBasics.cpp

#include 
#include 

using namespace std;

#include 
#include 

int main(int argc, char **argv) {
    // 读取argv[1]指定的图像
    cv::Mat image;
    //image = cv::imread(argv[1]); //cv::imread函数读取指定路径下的图像
    image = cv::imread("./src/ubuntu.png");

    // 判断图像文件是否正确读取
    if (image.data == nullptr) { //数据不存在,可能是文件不存在
        cerr << "文件" << argv[1] << "不存在." << endl;
        return 0;
    }

    // 文件顺利读取, 首先输出一些基本信息
    cout << "图像宽为" << image.cols << ",高为" << image.rows << ",通道数为" << image.channels() << endl;
    cv::imshow("image", image);      // 用cv::imshow显示图像
    cv::waitKey(0);                  // 暂停程序,等待一个按键输入

    // 判断image的类型
    if (image.type() != CV_8UC1 && image.type() != CV_8UC3) {
        // 图像类型不符合要求
        cout << "请输入一张彩色图或灰度图." << endl;
        return 0;
    }

    // 遍历图像, 请注意以下遍历方式亦可使用于随机像素访问
    // 使用 std::chrono 来给算法计时
    chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
    for (size_t y = 0; y < image.rows; y++) {
        // 用cv::Mat::ptr获得图像的行指针
        unsigned char *row_ptr = image.ptr<unsigned char>(y);  // row_ptr是第y行的头指针
        for (size_t x = 0; x < image.cols; x++) {
            // 访问位于 x,y 处的像素
            unsigned char *data_ptr = &row_ptr[x * image.channels()]; // data_ptr 指向待访问的像素数据
            // 输出该像素的每个通道,如果是灰度图就只有一个通道
            for (int c = 0; c != image.channels(); c++) {
                unsigned char data = data_ptr[c]; // data为I(x,y)第c个通道的值
            }
        }
    }
    chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
    chrono::duration<double> time_used = chrono::duration_cast < chrono::duration < double >> (t2 - t1);
    cout << "遍历图像用时:" << time_used.count() << " 秒。" << endl;

    // 关于 cv::Mat 的拷贝
    // 直接赋值并不会拷贝数据
    cv::Mat image_another = image;
    // 修改 image_another 会导致 image 发生变化
    image_another(cv::Rect(0, 0, 100, 100)).setTo(0); // 将左上角100*100的块置零
    cv::imshow("image", image);
    cv::waitKey(0);

    // 使用clone函数来拷贝数据
    cv::Mat image_clone = image.clone();
    image_clone(cv::Rect(0, 0, 100, 100)).setTo(255);
    cv::imshow("image", image);
    cv::imshow("image_clone", image_clone);
    cv::waitKey(0);

    // 对于图像还有很多基本的操作,如剪切,旋转,缩放等,限于篇幅就不一一介绍了,请参看OpenCV官方文档查询每个函数的调用方法.
    cv::destroyAllWindows();
    return 0;
}

3.2 CMakeListx.txt

cmake_minimum_required(VERSION 2.8)
project(imageBasics)

set(CMAKE_CXX_FLAGS "-std=c++11")

find_package( OpenCV 3 REQUIRED )

include_directories(${OpenCV_INCLUDE_DIR})
add_executable(imageBasics src/imageBasics.cpp)

target_link_libraries( imageBasics ${OpenCV_LIBS} )

3.3 运行

  • 生成的可执行文件后面要加上一个参数,所操作的照片,照片自取:
    链接:https://pan.baidu.com/s/1qwCThVKViWPzZhJqUeXPqA
    提取码:l9r0

4 图像去畸变

  • 这里要学习的的去畸变的原理:畸变的像素图-》畸变的真实图-》去畸变的真实图-》去畸变的像素图
  • 相当于算出畸变点和去畸变点的对应关系,然后赋值

4.1 undistortImage.cpp

  • 其中用到的图片自取:
    链接:https://pan.baidu.com/s/1E7H_od_8p2vg4xfk3_p1aA
    提取码:qb36
#include 
using namespace std;
#include 
#include 
string image_file = "../src/test.png";

int main(int argc,char** argv)
{

    // 本程序需要你自己实现去畸变部分的代码。尽管我们可以调用OpenCV的去畸变,但自己实现一遍有助于理解。
    // 畸变参数
    double k1 = -0.28340811, k2 = 0.07395907, p1 = 0.00019359, p2 = 1.76187114e-05;
    // 内参
    double fx = 458.654, fy = 457.296, cx = 367.215, cy = 248.375;

    cv::Mat image = cv::imread(image_file,0);   // 图像是灰度图,CV_8UC1
    int rows = image.rows, cols = image.cols;
    cv::Mat image_undistort = cv::Mat(rows, cols, CV_8UC1);   // 去畸变以后的图

    // 计算去畸变后图像的内容
    for (int v = 0; v < rows; v++)
        for (int u = 0; u < cols; u++) {

            double u_distorted = 0, v_distorted = 0;
            // TODO 按照公式,计算点(u,v)对应到畸变图像(原图像)中的坐标(u_distorted, v_distorted) (~6 lines)
            // start your code here
            double x = (u - cx) /fx, y = (v - cy)/fy;
            double r = sqrt(x*x+y*y);
            double x_distorted = x * (1 + k1*r*r + k2*r*r*r*r) + 2* p1*x*y + p2*(r*r+2*r*r);
            double y_distorted = y * (1 + k1*r*r + k2*r*r*r*r) + p1*(r*r+2*y*y)+2*p2*x*y;
            u_distorted = fx*x_distorted+cx;
            v_distorted = fy*y_distorted+cy;


            // end your code here

            // 赋值 (最近邻插值)
            if (u_distorted >= 0 && v_distorted >= 0 && u_distorted < cols && v_distorted < rows) {
                image_undistort.at<uchar>(v, u) = image.at<uchar>((int) v_distorted, (int) u_distorted);
            } else {
                image_undistort.at<uchar>(v, u) = 0;
            }
        }

    // 画图去畸变后图像
    cv::imshow("image undistorted", image_undistort);
    cv::imshow("image",image);
    cv::waitKey();


	return 0;
}

4.2 CMakeLits.txt

cmake_minimum_required(VERSION 2.8)

project( undistortImage )

set(CMAKE_CXX_FLAGS "-std=c++11")
find_package( OpenCV 3 REQUIRED )

include_directories(${OpenCV_INCLUDE_DIR})

add_executable(undistortImage src/undistortImage.cpp)

target_link_libraries(undistortImage ${OpenCV_LIBS})

5 双目视觉 | 使用pangolin画出点云 | 计算视差

  • 主要是演示了使用opencv的SGBM(Semi-Global Batch Matching)算法计算视差图和使用pangolin画出点云部分

  • 视差计算:cv::StereoSGBM

  • 转换点云的方式:像素图-》真实图和深度-》点云图

  • 需要两张图片自取:链接:链接: https://pan.baidu.com/s/1OKoOXDK_VnMTEYsoYjRknA 提取码: 79v5

5.1 stereoVision.cpp

#include 
using namespace std;
#include 
#include 
#include 
#include 
#include 

using namespace Eigen;
// 文件路径
string left_file = "../src/left.png";
string right_file = "../src/right.png";
string disparity_file = "../src/disparity.png";//no useful


// 在panglin中画图,已写好,无需调整
void showPointCloud(const vector<Vector4d, Eigen::aligned_allocator<Vector4d>> &pointcloud);

int main(int argc,char ** argv)
{
    // 内参
    double fx = 718.856 , fy = 718.856, cx = 607.1928, cy = 185.2157;
    // 基线
    double b = 0.573;
    // 读取图像
    cv::Mat left = cv::imread(left_file,0);
    cv::Mat right = cv::imread(right_file,0);
    //神奇的参数
    cv::Ptr<cv::StereoSGBM> sgbm = cv::StereoSGBM::create(0,96,9,8*9*9,32*9*9,1,63,10,100,32);
    cv::Mat disparity_sgbm, disparity;
    sgbm->compute(left,right,disparity_sgbm);
    disparity_sgbm.convertTo(disparity,CV_32F,1.0/16.0f);
    // 生成点云
    vector<Vector4d, Eigen::aligned_allocator<Vector4d>> pointcloud;
    // 如果你的机器慢,请把后面的v++和u++改成v+=2, u+=2
    for(int v  = 0; v < left.rows;v++)
    {
        for(int u = 0; u < left.cols; u++)
        {
            if(disparity.at<float>(v,u) <=10.0 || disparity.at<float>(v,u) >=96.0)
                continue;
            Vector4d point(0,0,0, left.at<uchar>(v,u)/255.0);//前三维为xyz,第四维为颜色
            // 根据双目模型计算 point 的位置
            double x = (u - cx)/fx;
            double y = (v - cy)/fy;
            //f*b/(d) = f*b/(dx/aierfa) = f*aierfa*b/dx = fx*b/dx
            double depth = fx * b/(disparity.at<float>(v,u));
            point[0] = x*depth;
            point[1] = y*depth;
            point[2] = depth;

            pointcloud.push_back(point);
        }
    }
    cv::imshow("disparity",disparity/96.0);
    cv::waitKey(0);
    // 画出点云
    showPointCloud(pointcloud);
    return 0;
}
void showPointCloud(const vector<Vector4d, Eigen::aligned_allocator<Vector4d>> &pointcloud) {

    if (pointcloud.empty()) {
        cerr << "Point cloud is empty!" << endl;
        return;
    }

    pangolin::CreateWindowAndBind("Point Cloud Viewer", 1024, 768);
    glEnable(GL_DEPTH_TEST);
    glEnable(GL_BLEND);
    glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);

    pangolin::OpenGlRenderState s_cam(
            pangolin::ProjectionMatrix(1024, 768, 500, 500, 512, 389, 0.1, 1000),
            pangolin::ModelViewLookAt(0, -0.1, -1.8, 0, 0, 0, 0.0, -1.0, 0.0)
    );

    pangolin::View &d_cam = pangolin::CreateDisplay()
            .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f / 768.0f)
            .SetHandler(new pangolin::Handler3D(s_cam));

    while (pangolin::ShouldQuit() == false) {
        glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);

        d_cam.Activate(s_cam);
        glClearColor(1.0f, 1.0f, 1.0f, 1.0f);

        glPointSize(2);
        glBegin(GL_POINTS);
        for (auto &p: pointcloud) {
            glColor3f(p[3], p[3], p[3]);
            glVertex3d(p[0], p[1], p[2]);
        }
        glEnd();
        pangolin::FinishFrame();
        usleep(5000);   // sleep 5 ms
    }
    return;
}

5.2 CMakeLists.txt

  • Pangolin的安装同样可以参考Ubuntu18.04下 ORB_SLAM2的安装与配置
  • Pangolin安装包自取:链接:https://pan.baidu.com/s/1Gex6aEPUEJ82DjRMBRmiTw
    提取码:26b4
cmake_minimum_required(VERSION 3.0)

project( stereoVision )

set(CMAKE_CXX_FLAGS "-std=c++11")

include_directories("/usr/include/eigen3")
find_package(OpenCV 3 REQUIRED)
find_package(Pangolin REQUIRED)

include_directories(${OpenCV_INCLUDE_DIRS}})
include_directories(${Pangolin_INCLUDE_DIRS})

add_executable(stereoVision src/stereoVision.cpp)

target_link_libraries(stereoVision ${OpenCV_LIBRARIES} ${Pangolin_LIBRARIES} )

6 RGB-D视觉

  • 该项目需要pcl库,一般安装电脑都会自带pcl1.8版本的,但是会缺少一些库文件,我是参考第5讲 相机与图像,执行命令:
sudo apt install libpcl-dev pcl-tools
  • 由于该项目所需要的材料较多,所以我把整个项目放进来,自取:链接:链接: https://pan.baidu.com/s/1GntsZTBBLB7SkOeyKk7pjg 提取码: fvn6

  • 在OpenCV彩色图像中,通道的默认顺序是B、G、R

  • 可以得到如何使用RGB-D的图片

  • pcl::PointCloud,输出为.pcd格式的文件:

    typedef pcl::PointXYZRGB PointT; 
    typedef pcl::PointCloud<PointT> PointCloud;
    
    // 新建一个点云
    PointCloud::Ptr pointCloud( new PointCloud ); 
    pcl::io::savePCDFileBinary("map.pcd", *pointCloud );

6.1 joinMap.cpp

#include 

#include 
using namespace std;
#include 
#include 
#include 
#include   // for formating strings
#include 
#include 
#include 



int main( int argc, char** argv )
{
    vector<cv::Mat> colorImgs, depthImgs;    // 彩色图和深度图
    vector<Eigen::Isometry3d, Eigen::aligned_allocator<Eigen::Isometry3d>> poses;         // 相机位姿

    ifstream fin("./src/pose.txt");
    if (!fin)
    {
        cerr<<"请在有pose.txt的目录下运行此程序"<<endl;
        return 1;
    }

    for ( int i=0; i<5; i++ )
    {
        boost::format fmt( "./%s/%d.%s" ); //图像文件格式
        colorImgs.push_back( cv::imread( (fmt%"color"%(i+1)%"png").str() ));
        depthImgs.push_back( cv::imread( (fmt%"depth"%(i+1)%"pgm").str(), -1 )); // 使用-1读取原始图像

        double data[7] = {0};
        for ( auto& d:data )
            fin>>d;
        Eigen::Quaterniond q( data[6], data[3], data[4], data[5] );
        Eigen::Isometry3d T(q);
        T.pretranslate( Eigen::Vector3d( data[0], data[1], data[2] ));
        poses.push_back( T );
    }

    // 计算点云并拼接
    // 相机内参
    double cx = 325.5;
    double cy = 253.5;
    double fx = 518.0;
    double fy = 519.0;
    double depthScale = 1000.0;

    cout<<"正在将图像转换为点云..."<<endl;

    // 定义点云使用的格式:这里用的是XYZRGB
    typedef pcl::PointXYZRGB PointT;
    typedef pcl::PointCloud<PointT> PointCloud;

    // 新建一个点云
    PointCloud::Ptr pointCloud( new PointCloud );
    for ( int i=0; i<5; i++ )
    {
        cout<<"转换图像中: "<<i+1<<endl;
        cv::Mat color = colorImgs[i];
        cv::Mat depth = depthImgs[i];
        Eigen::Isometry3d T = poses[i];
        for ( int v=0; v<color.rows; v++ )
            for ( int u=0; u<color.cols; u++ )
            {
                unsigned int d = depth.ptr<unsigned short> ( v )[u]; // 深度值
                if ( d==0 ) continue; // 为0表示没有测量到
                Eigen::Vector3d point;
                point[2] = double(d)/depthScale;
                point[0] = (u-cx)*point[2]/fx;
                point[1] = (v-cy)*point[2]/fy;
                Eigen::Vector3d pointWorld = T*point;

                PointT p ;
                p.x = pointWorld[0];
                p.y = pointWorld[1];
                p.z = pointWorld[2];
                p.b = color.data[ v*color.step+u*color.channels() ];//在OpenCV彩色图像中,通道的默认顺序是B、G、R
                p.g = color.data[ v*color.step+u*color.channels()+1 ];
                p.r = color.data[ v*color.step+u*color.channels()+2 ];
                pointCloud->points.push_back( p );

            }
    }

    pointCloud->is_dense = false;
    cout<<"点云共有"<<pointCloud->size()<<"个点."<<endl;
    pcl::io::savePCDFileBinary("map.pcd", *pointCloud );

    boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("3D Viewer"));
    viewer->setBackgroundColor (0, 0, 0);
    pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> rgb(pointCloud);
    viewer->addPointCloud<pcl::PointXYZRGB> (pointCloud, rgb, "sample cloud");
    viewer->setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "sample cloud");
    //viewer->addCoordinateSystem (1.0);
    viewer->initCameraParameters ();
    while (!viewer->wasStopped ())
    {
        //调用spinOnce,给视窗处理事件的时间,可以允许用户和电脑进行交互
        viewer->spinOnce (100);
        boost::this_thread::sleep (boost::posix_time::microseconds (100000));
    }



    return 0;
}

6.2 CMakeLists.txt

cmake_minimum_required( VERSION 2.8 )
project( joinMap )

set( CMAKE_BUILD_TYPE Release )
set( CMAKE_CXX_STANDARD 11 )#or 4

# opencv
find_package( OpenCV 3 REQUIRED )
include_directories( ${OpenCV_INCLUDE_DIRS} )

# eigen
include_directories("/usr/include/eigen3")

# pcl
#find_package( PCL REQUIRED COMPONENT common io)
find_package( PCL 1.8 REQUIRED)
set(PCL_INCLUDE_DIRS /usr/include/pcl-1.8)  #指定pcl1.8路径
include_directories( ${PCL_INCLUDE_DIRS} )
add_definitions( ${PCL_DEFINITIONS} )

add_executable( joinMap src/joinMap.cpp )
target_link_libraries( joinMap ${OpenCV_LIBS} ${PCL_LIBRARIES} )

7 遍历图像像素的14种方法

  • 所有方法是基于OpenCV的

7.1 bian_li_tupian.cpp

//--------------------------------------【程序说明】-------------------------------------------
//		程序说明:《OpenCV3编程入门》OpenCV2版书本配套示例程序24
//		程序描述:来自一本国外OpenCV2书籍的示例-遍历图像像素的14种方法
//		测试所用IDE版本:Visual Studio 2010
//		测试所用OpenCV版本:	2.4.9
//		2014年11月 Revised by @浅墨_毛星云
//------------------------------------------------------------------------------------------------


/*------------------------------------------------------------------------------------------*\
   This file contains material supporting chapter 2 of the cookbook:  
   Computer Vision Programming using the OpenCV Library. 
   by Robert Laganiere, Packt Publishing, 2011.
   This program is free software; permission is hereby granted to use, copy, modify, 
   and distribute this source code, or portions thereof, for any purpose, without fee, 
   subject to the restriction that the copyright notice may not be removed 
   or altered from any source or altered source distribution. 
   The software is released on an as-is basis and without any warranties of any kind. 
   In particular, the software is not guaranteed to be fault-tolerant or free from failure. 
   The author disclaims all warranties with regard to this software, any use, 
   and any consequent failure, is purely the responsibility of the user.
 
   Copyright (C) 2010-2011 Robert Laganiere, www.laganiere.name
\*------------------------------------------------------------------------------------------*/

//---------------------------------【头文件、命名空间包含部分】-----------------------------
//		描述:包含程序所使用的头文件和命名空间
//-------------------------------------------------------------------------------------------------
#include 
#include 
#include 
using namespace cv;
using namespace std;



//---------------------------------【宏定义部分】---------------------------------------------
//		描述:包含程序所使用宏定义
//-------------------------------------------------------------------------------------------------
#define NTESTS 14
#define NITERATIONS 20



//----------------------------------------- 【方法一】-------------------------------------------
//		说明:利用.ptr 和 []
//-------------------------------------------------------------------------------------------------
void colorReduce0(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols * image.channels(); //每行元素的总元素数量

    for (int j=0; j<nl; j++)
    {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++)
        {

            //-------------开始处理每个像素-------------------

            data[i]= data[i]/div*div + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

//-----------------------------------【方法二】-------------------------------------------------
//		说明:利用 .ptr 和 * ++ 
//-------------------------------------------------------------------------------------------------
void colorReduce1(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols * image.channels(); //每行元素的总元素数量

    for (int j=0; j<nl; j++)
    {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++)
        {

            //-------------开始处理每个像素-------------------

            *data++= *data/div*div + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

//-----------------------------------------【方法三】-------------------------------------------
//		说明:利用.ptr 和 * ++ 以及模操作
//-------------------------------------------------------------------------------------------------
void colorReduce2(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols * image.channels(); //每行元素的总元素数量

    for (int j=0; j<nl; j++)
    {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++)
        {

            //-------------开始处理每个像素-------------------

            int v= *data;
            *data++= v - v%div + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

//----------------------------------------【方法四】---------------------------------------------
//		说明:利用.ptr 和 * ++ 以及位操作
//----------------------------------------------------------------------------------------------------
void colorReduce3(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols * image.channels(); //每行元素的总元素数量
    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 对于 div=16, mask= 0xF0

    for (int j=0; j<nl; j++) {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++) {

            //------------开始处理每个像素-------------------

            *data++= *data&mask + div/2;

            //-------------结束像素处理------------------------
        }  //单行处理结束
    }
}


//----------------------------------------【方法五】----------------------------------------------
//		说明:利用指针算术运算
//---------------------------------------------------------------------------------------------------
void colorReduce4(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols * image.channels(); //每行元素的总元素数量
    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    int step= image.step; //有效宽度
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 对于 div=16, mask= 0xF0

    //获取指向图像缓冲区的指针
    uchar *data= image.data;

    for (int j=0; j<nl; j++)
    {

        for (int i=0; i<nc; i++)
        {

            //-------------开始处理每个像素-------------------

            *(data+i)= *data&mask + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束

        data+= step;  // next line
    }
}

//---------------------------------------【方法六】----------------------------------------------
//		说明:利用 .ptr 和 * ++以及位运算、image.cols * image.channels()
//-------------------------------------------------------------------------------------------------
void colorReduce5(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 例如div=16, mask= 0xF0

    for (int j=0; j<nl; j++)
    {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<image.cols * image.channels(); i++)
        {

            //-------------开始处理每个像素-------------------

            *data++= *data&mask + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

// -------------------------------------【方法七】----------------------------------------------
//		说明:利用.ptr 和 * ++ 以及位运算(continuous)
//-------------------------------------------------------------------------------------------------
void colorReduce6(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols * image.channels(); //每行元素的总元素数量

    if (image.isContinuous())
    {
        //无填充像素
        nc= nc*nl;
        nl= 1;  // 为一维数列
    }

    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 比如div=16, mask= 0xF0

    for (int j=0; j<nl; j++) {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++) {

            //-------------开始处理每个像素-------------------

            *data++= *data&mask + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

//------------------------------------【方法八】------------------------------------------------
//		说明:利用 .ptr 和 * ++ 以及位运算 (continuous+channels)
//-------------------------------------------------------------------------------------------------
void colorReduce7(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols ; //列数

    if (image.isContinuous())
    {
        //无填充像素
        nc= nc*nl;
        nl= 1;  // 为一维数组
    }

    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 比如div=16, mask= 0xF0

    for (int j=0; j<nl; j++) {

        uchar* data= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++) {

            //-------------开始处理每个像素-------------------

            *data++= *data&mask + div/2;
            *data++= *data&mask + div/2;
            *data++= *data&mask + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}


// -----------------------------------【方法九】 ------------------------------------------------
//		说明:利用Mat_ iterator  //fastest
//-------------------------------------------------------------------------------------------------
void colorReduce8(Mat &image, int div=64) {

    //获取迭代器
    Mat_<Vec3b>::iterator it= image.begin<Vec3b>();
    Mat_<Vec3b>::iterator itend= image.end<Vec3b>();

    for ( ; it!= itend; ++it) {

        //-------------开始处理每个像素-------------------

        (*it)[0]= (*it)[0]/div*div + div/2;
        (*it)[1]= (*it)[1]/div*div + div/2;
        (*it)[2]= (*it)[2]/div*div + div/2;

        //-------------结束像素处理------------------------
    }//单行处理结束
}

//-------------------------------------【方法十】-----------------------------------------------
//		说明:利用Mat_ iterator以及位运算
//-------------------------------------------------------------------------------------------------
void colorReduce9(Mat &image, int div=64) {

    // div必须是2的幂
    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 比如 div=16, mask= 0xF0

    // 获取迭代器
    Mat_<Vec3b>::iterator it= image.begin<Vec3b>();
    Mat_<Vec3b>::iterator itend= image.end<Vec3b>();

    //扫描所有元素
    for ( ; it!= itend; ++it)
    {

        //-------------开始处理每个像素-------------------

        (*it)[0]= (*it)[0]&mask + div/2;
        (*it)[1]= (*it)[1]&mask + div/2;
        (*it)[2]= (*it)[2]&mask + div/2;

        //-------------结束像素处理------------------------
    }//单行处理结束
}

//------------------------------------【方法十一】---------------------------------------------
//		说明:利用Mat Iterator_
//-------------------------------------------------------------------------------------------------
void colorReduce10(Mat &image, int div=64) {

    //获取迭代器
    Mat_<Vec3b> cimage= image;
    Mat_<Vec3b>::iterator it=cimage.begin();
    Mat_<Vec3b>::iterator itend=cimage.end();

    for ( ; it!= itend; it++) {

        //-------------开始处理每个像素-------------------

        (*it)[0]= (*it)[0]/div*div + div/2;
        (*it)[1]= (*it)[1]/div*div + div/2;
        (*it)[2]= (*it)[2]/div*div + div/2;

        //-------------结束像素处理------------------------
    }
}

//--------------------------------------【方法十二】--------------------------------------------
//		说明:利用动态地址计算配合at
//-------------------------------------------------------------------------------------------------
void colorReduce11(Mat &image, int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols; //列数

    for (int j=0; j<nl; j++)
    {
        for (int i=0; i<nc; i++)
        {

            //-------------开始处理每个像素-------------------

            image.at<Vec3b>(j,i)[0]=	 image.at<Vec3b>(j,i)[0]/div*div + div/2;
            image.at<Vec3b>(j,i)[1]=	 image.at<Vec3b>(j,i)[1]/div*div + div/2;
            image.at<Vec3b>(j,i)[2]=	 image.at<Vec3b>(j,i)[2]/div*div + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

//----------------------------------【方法十三】----------------------------------------------- 
//		说明:利用图像的输入与输出
//-------------------------------------------------------------------------------------------------
void colorReduce12(const Mat &image, //输入图像
                   Mat &result,      // 输出图像
                   int div=64) {

    int nl= image.rows; //行数
    int nc= image.cols ; //列数

    //准备好初始化后的Mat给输出图像
    result.create(image.rows,image.cols,image.type());

    //创建无像素填充的图像
    nc= nc*nl;
    nl= 1;  //单维数组

    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g.比如div=16, mask= 0xF0

    for (int j=0; j<nl; j++) {

        uchar* data= result.ptr<uchar>(j);
        const uchar* idata= image.ptr<uchar>(j);

        for (int i=0; i<nc; i++) {

            //-------------开始处理每个像素-------------------

            *data++= (*idata++)&mask + div/2;
            *data++= (*idata++)&mask + div/2;
            *data++= (*idata++)&mask + div/2;

            //-------------结束像素处理------------------------

        } //单行处理结束
    }
}

//--------------------------------------【方法十四】------------------------------------------- 
//		说明:利用操作符重载
//-------------------------------------------------------------------------------------------------
void colorReduce13(Mat &image, int div=64) {

    int n= static_cast<int>(log(static_cast<double>(div))/log(2.0));
    //掩码值
    uchar mask= 0xFF<<n; // e.g. 比如div=16, mask= 0xF0

    //进行色彩还原
    image=(image&Scalar(mask,mask,mask))+Scalar(div/2,div/2,div/2);
}




//-----------------------------------【ShowHelpText( )函数】-----------------------------
//		描述:输出一些帮助信息
//----------------------------------------------------------------------------------------------
void ShowHelpText()
{
    //输出欢迎信息和OpenCV版本
    printf("\n\n\t\t\t非常感谢购买《OpenCV3编程入门》一书!\n");
    printf("\n\n\t\t\t此为本书OpenCV2版的第24个配套示例程序\n");
    printf("\n\n\t\t\t   当前使用的OpenCV版本为:" CV_VERSION );
    printf("\n\n  ----------------------------------------------------------------------------\n");

    printf("\n\n正在进行存取操作,请稍等……\n\n");
}




//-----------------------------------【main( )函数】--------------------------------------------
//		描述:控制台应用程序的入口函数,我们的程序从这里开始
//-------------------------------------------------------------------------------------------------
int main( )
{
    int64 t[NTESTS],tinit;
    Mat image0;
    Mat image1;
    Mat image2;

    //system("color 4F");

    ShowHelpText();

    image0= imread("../src/1.png");
    if (!image0.data)
        return 0;

    //时间值设为0
    for (int i=0; i<NTESTS; i++)
        t[i]= 0;


    // 多次重复测试
    int n=NITERATIONS;

    for (int k=0; k<n; k++)
    {
        cout << k << " of " << n << endl;

        image1= imread("../src/1.png");
        //【方法一】利用.ptr 和 []
        tinit= getTickCount();
        colorReduce0(image1);
        t[0]+= getTickCount()-tinit;

        //【方法二】利用 .ptr 和 * ++
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce1(image1);
        t[1]+= getTickCount()-tinit;

        //【方法三】利用.ptr 和 * ++ 以及模操作
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce2(image1);
        t[2]+= getTickCount()-tinit;

        //【方法四】 利用.ptr 和 * ++ 以及位操作
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce3(image1);
        t[3]+= getTickCount()-tinit;

        //【方法五】 利用指针的算术运算
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce4(image1);
        t[4]+= getTickCount()-tinit;

        //【方法六】利用 .ptr 和 * ++以及位运算、image.cols * image.channels()
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce5(image1);
        t[5]+= getTickCount()-tinit;

        //【方法七】利用.ptr 和 * ++ 以及位运算(continuous)
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce6(image1);
        t[6]+= getTickCount()-tinit;

        //【方法八】利用 .ptr 和 * ++ 以及位运算 (continuous+channels)
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce7(image1);
        t[7]+= getTickCount()-tinit;

        //【方法九】 利用Mat_ iterator
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce8(image1);
        t[8]+= getTickCount()-tinit;

        //【方法十】 利用Mat_ iterator以及位运算
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce9(image1);
        t[9]+= getTickCount()-tinit;

        //【方法十一】利用Mat Iterator_
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce10(image1);
        t[10]+= getTickCount()-tinit;

        //【方法十二】 利用动态地址计算配合at
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce11(image1);
        t[11]+= getTickCount()-tinit;

        //【方法十三】 利用图像的输入与输出
        image1= imread("../src/1.png");
        tinit= getTickCount();
        Mat result;
        colorReduce12(image1, result);
        t[12]+= getTickCount()-tinit;
        image2= result;

        //【方法十四】 利用操作符重载
        image1= imread("../src/1.png");
        tinit= getTickCount();
        colorReduce13(image1);
        t[13]+= getTickCount()-tinit;

        //------------------------------
    }
    //输出图像
    imshow("原始图像",image0);
    imshow("结果",image2);
    imshow("图像结果",image1);

    // 输出平均执行时间
    cout << endl << "-------------------------------------------" << endl << endl;
    cout << "\n【方法一】利用.ptr 和 []的方法所用时间为 " << 1000.*t[0]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法二】利用 .ptr 和 * ++ 的方法所用时间为" << 1000.*t[1]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法三】利用.ptr 和 * ++ 以及模操作的方法所用时间为" << 1000.*t[2]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法四】利用.ptr 和 * ++ 以及位操作的方法所用时间为" << 1000.*t[3]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法五】利用指针算术运算的方法所用时间为" << 1000.*t[4]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法六】利用 .ptr 和 * ++以及位运算、channels()的方法所用时间为" << 1000.*t[5]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法七】利用.ptr 和 * ++ 以及位运算(continuous)的方法所用时间为" << 1000.*t[6]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法八】利用 .ptr 和 * ++ 以及位运算 (continuous+channels)的方法所用时间为" << 1000.*t[7]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法九】利用Mat_ iterator 的方法所用时间为" << 1000.*t[8]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法十】利用Mat_ iterator以及位运算的方法所用时间为" << 1000.*t[9]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法十一】利用Mat Iterator_的方法所用时间为" << 1000.*t[10]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法十二】利用动态地址计算配合at 的方法所用时间为" << 1000.*t[11]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法十三】利用图像的输入与输出的方法所用时间为" << 1000.*t[12]/getTickFrequency()/n << "ms" << endl;
    cout << "\n【方法十四】利用操作符重载的方法所用时间为" << 1000.*t[13]/getTickFrequency()/n << "ms" << endl;

    waitKey();
    return 0;
}

7.2 CMakeLists.txt

cmake_minimum_required(VERSION 2.8)

project( bian_li_tupian )

find_package(OpenCV 3 REQUIRED)

include_directories(${OpenCV_INCLUDE_DIRS})

add_executable(bian_li_tupian src/bian_li_tupian.cpp)

target_link_libraries(bian_li_tupian ${OpenCV_LIBRARIES})

7.3 注意事项

  • 里面的图片地址自己改到自己对应的地址下
  • 如果不想创建,可以自取我的:链接:https://pan.baidu.com/s/1iswMhjbgXZqaKPIkEtvNvw
    提取码:8m4z

你可能感兴趣的:(视觉SLAM14讲,ubuntu,slam,c++,人工智能)