├── bin └── README.md ├── images ├── README.md ├── image_1.png └── image_2.png ├── result └── README.md ├── src ├── README.md └── orb_segmentation.cpp ├── model ├── README.md └── segnet_pascal.prototxt ├── CMakeLists.txt └── README.md /bin/README.md: -------------------------------------------------------------------------------- 1 | 可执行文件文件夹 2 | -------------------------------------------------------------------------------- /images/README.md: -------------------------------------------------------------------------------- 1 | 输入图像文件夹 2 | -------------------------------------------------------------------------------- /result/README.md: -------------------------------------------------------------------------------- 1 | 输出结果文件夹 2 | -------------------------------------------------------------------------------- /src/README.md: -------------------------------------------------------------------------------- 1 | 源文件文件夹 2 | -------------------------------------------------------------------------------- /images/image_1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wangzhaodong123/ORB_Segmentation/HEAD/images/image_1.png -------------------------------------------------------------------------------- /images/image_2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/wangzhaodong123/ORB_Segmentation/HEAD/images/image_2.png -------------------------------------------------------------------------------- /model/README.md: -------------------------------------------------------------------------------- 1 | 深度学习模型文件夹 2 | segnet_pascal.caffemodel文件太大,这是链接:http://mi.eng.cam.ac.uk/~agk34/resources/SegNet/ 3 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | PROJECT(orb_segmentation) 2 | CMAKE_MINIMUM_REQUIRED(VERSION 2.8) 3 | 4 | SET(CMAKE_BUILD_TYPE Debug) 5 | # 设置编译选项,允许c++11标准、O3优化、多线程。match选项可避免一些cpu上的问题 6 | SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -march=native -O3 -pthread") 7 | 8 | find_package( OpenCV REQUIRED ) 9 | 10 | find_package( Caffe REQUIRED ) 11 | include_directories(${Caffe_INCLUDE_DIRS}) 12 | add_definitions(${Caffe_DEFINITIONS}) 13 | 14 | SET(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin) 15 | #二进制文件输出到bin 16 | 17 | set(build_libraries ${Caffe_LIBRARIES} ${OpenCV_LIBS} ${BOOST_LIBRARIES}) 18 | add_executable(orb_segmentation src/orb_segmentation.cpp) 19 | target_link_libraries(orb_segmentation ${build_libraries}) 20 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ORB_Segmenttation 2 | 使用语义分割将图像中的人分离出来,将原始图像中提取的ORB特征点落在人身上的剔除(用于SLAM的位姿估计). 3 | # 参考 4 | 1,caffe之特征图可视化及特征提取 5 | 6 | 博客链接:https://blog.csdn.net/zxj942405301/article/details/71195267 7 | 8 | 2,caffe-segnet-cudnn5的test_segmentation.cpp 9 | 10 | 链接:https://github.com/TimoSaemann/caffe-segnet-cudnn5/tree/master/examples/SegNet_with_C%2B%2B 11 | # 编译运行 12 | 1,首先安装caffe-segnet-cudnn5 13 | 14 | github地址:https://github.com/TimoSaemann/caffe-segnet-cudnn5 15 | 16 | 2,编译 17 | 18 | cd ORB_Segmenttation 19 | 20 | mkdir build 21 | 22 | cd build 23 | 24 | cmake .. 25 | 26 | make 27 | 28 | 3,运行 29 | 30 | cd ORB_Segmenttation 31 | 32 | ./bin/orb_segmentation model/segnet_pascal.prototxt model/segnet_pascal.caffemodel images/image_1.png images/image_2.png 33 | 34 | 4,输出结果将保存在result/文件夹下 35 | 36 | -------------------------------------------------------------------------------- /src/orb_segmentation.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * 3 | * Created on: Jan 21, 2017 4 | * Author: Timo Sämann 5 | * 6 | * The basis for the creation of this script was the classification.cpp example (caffe/examples/cpp_classification/classification.cpp) 7 | * 8 | * This script visualize the semantic segmentation for your input image. 9 | * 10 | * To compile this script you can use a IDE like Eclipse. To include Caffe and OpenCV in Eclipse please refer to 11 | * http://tzutalin.blogspot.de/2015/05/caffe-on-ubuntu-eclipse-cc.html 12 | * and http://rodrigoberriel.com/2014/10/using-opencv-3-0-0-with-eclipse/ , respectively 13 | * 14 | * 15 | */ 16 | 17 | //实验一 18 | //单帧的特征检测和特征匹配 19 | 20 | 21 | #define USE_OPENCV 1 22 | #include "/home/ubuntu/caffe-segnet/include/caffe/caffe.hpp" 23 | 24 | #ifdef USE_OPENCV 25 | #include 26 | #include 27 | #include 28 | #include 29 | #endif // USE_OPENCV 30 | 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | //#include //Just for time measurement. This library requires compiler and library support for the ISO C++ 2011 standard. This support is currently experimental in Caffe, and must be enabled with the -std=c++11 or -std=gnu++11 compiler options. 39 | 40 | 41 | #ifdef USE_OPENCV 42 | using namespace caffe; // NOLINT(build/namespaces) 43 | using namespace std; 44 | using namespace cv; 45 | 46 | #define MATCH_DISTANCE 180 47 | #define CLASS_PEOPLE 15 48 | 49 | //Mat img prediction; 50 | class Classifier 51 | { 52 | public: 53 | Classifier(const string& model_file,const string& trained_file); 54 | 55 | void Predict(const cv::Mat& img, cv::Mat& img_segment); 56 | 57 | private: 58 | void WrapInputLayer(std::vector* input_channels); 59 | 60 | void Preprocess(const cv::Mat& img,std::vector* input_channels); 61 | 62 | private: 63 | boost::shared_ptr > net_; 64 | cv::Size input_geometry_; 65 | int num_channels_; 66 | }; 67 | 68 | Classifier::Classifier(const string& model_file,const string& trained_file) 69 | { 70 | Caffe::set_mode(Caffe::GPU); 71 | 72 | /* Load the network. */ 73 | net_.reset(new Net(model_file, TEST)); 74 | net_->CopyTrainedLayersFrom(trained_file); 75 | 76 | CHECK_EQ(net_->num_inputs(), 1) << "Network should have exactly one input."; 77 | CHECK_EQ(net_->num_outputs(), 1) << "Network should have exactly one output."; 78 | 79 | Blob* input_layer = net_->input_blobs()[0]; 80 | num_channels_ = input_layer->channels(); 81 | CHECK(num_channels_ == 3 || num_channels_ == 1)<< "Input layer should have 1 or 3 channels."; 82 | input_geometry_ = cv::Size(input_layer->width(), input_layer->height()); 83 | } 84 | 85 | void Classifier::Predict(const cv::Mat& img, cv::Mat& img_segment) 86 | { 87 | Blob* input_layer = net_->input_blobs()[0]; 88 | input_layer->Reshape(1, num_channels_,input_geometry_.height, input_geometry_.width); 89 | 90 | /* Forward dimension change to all layers. */ 91 | net_->Reshape(); 92 | 93 | std::vector input_channels; 94 | WrapInputLayer(&input_channels); 95 | 96 | Preprocess(img, &input_channels); 97 | 98 | struct timeval time; 99 | gettimeofday(&time, NULL); // Start Time 100 | long totalTime = (time.tv_sec * 1000) + (time.tv_usec / 1000); 101 | //std::chrono::steady_clock::time_point begin = std::chrono::steady_clock::now(); //Just for time measurement 102 | 103 | net_->Forward(); 104 | 105 | gettimeofday(&time, NULL); //END-TIME 106 | totalTime = (((time.tv_sec * 1000) + (time.tv_usec / 1000)) - totalTime); 107 | std::cout << "Processing time = " << totalTime << " ms" << std::endl; 108 | 109 | /* Copy the output layer to a std::vector */ 110 | Blob* output_layer = net_->output_blobs()[0]; 111 | 112 | //获得只有人的灰度图像 113 | // 仿照博客: caffe之特征图可视化及特征提取 https://blog.csdn.net/zxj942405301/article/details/71195267 114 | //将测试图片经过最后一个卷积层的特征图可视化 115 | //这一层的名字叫做 prob 116 | string blobName="prob"; 117 | assert(net_->has_blob(blobName)); //为免出错,我们必须断言,网络中确实有名字为blobName的特征图 118 | boost::shared_ptr > conv1Blob=net_->blob_by_name(blobName); 119 | //为了可视化,仍然需要归一化到0~255 120 | //下面的代码,跟上一篇博客中是一样的 121 | float maxValue=-10000000,minValue=10000000; 122 | const float* tmpValue=conv1Blob->cpu_data(); 123 | for(int i=0;icount();i++) 124 | { 125 | maxValue=std::max(maxValue,tmpValue[i]); 126 | minValue=std::min(minValue,tmpValue[i]); 127 | } 128 | int width=conv1Blob->shape(2); //响应图的宽度 129 | int height=conv1Blob->shape(3); //响应图的高度 130 | //获取第15类 "人" 131 | Mat img_i(width,height,CV_8UC1); 132 | for(int i=0;idata_at(0,CLASS_PEOPLE,i,j); 137 | img_i.at(i,j)=(value-minValue)/(maxValue-minValue)*255; 138 | } 139 | } 140 | //转化成与原图片相同的格式 141 | resize(img_i,img_i,Size(640,480)); 142 | //将结果输出 143 | img_segment = img_i.clone(); 144 | } 145 | 146 | void Classifier::WrapInputLayer(std::vector* input_channels) 147 | { 148 | Blob* input_layer = net_->input_blobs()[0]; 149 | 150 | int width = input_layer->width(); 151 | int height = input_layer->height(); 152 | float* input_data = input_layer->mutable_cpu_data(); 153 | for (int i = 0; i < input_layer->channels(); ++i) { 154 | cv::Mat channel(height, width, CV_32FC1, input_data); 155 | input_channels->push_back(channel); 156 | input_data += width * height; 157 | } 158 | } 159 | 160 | void Classifier::Preprocess(const cv::Mat& img,std::vector* input_channels) 161 | { 162 | /* Convert the input image to the input image format of the network. */ 163 | cv::Mat sample; 164 | if (img.channels() == 3 && num_channels_ == 1) 165 | cv::cvtColor(img, sample, cv::COLOR_BGR2GRAY); 166 | else if (img.channels() == 4 && num_channels_ == 1) 167 | cv::cvtColor(img, sample, cv::COLOR_BGRA2GRAY); 168 | else if (img.channels() == 4 && num_channels_ == 3) 169 | cv::cvtColor(img, sample, cv::COLOR_BGRA2BGR); 170 | else if (img.channels() == 1 && num_channels_ == 3) 171 | cv::cvtColor(img, sample, cv::COLOR_GRAY2BGR); 172 | else 173 | sample = img; 174 | 175 | cv::Mat sample_resized; 176 | if (sample.size() != input_geometry_) 177 | cv::resize(sample, sample_resized, input_geometry_); 178 | else 179 | sample_resized = sample; 180 | 181 | cv::Mat sample_float; 182 | if (num_channels_ == 3) 183 | sample_resized.convertTo(sample_float, CV_32FC3); 184 | else 185 | sample_resized.convertTo(sample_float, CV_32FC1); 186 | 187 | /* This operation will write the separate BGR planes directly to the 188 | * input layer of the network because it is wrapped by the cv::Mat 189 | * objects in input_channels. */ 190 | cv::split(sample_float, *input_channels); 191 | 192 | CHECK(reinterpret_cast(input_channels->at(0).data) 193 | == net_->input_blobs()[0]->cpu_data()) 194 | << "Input channels are not wrapping the input layer of the network."; 195 | } 196 | 197 | int main(int argc,char *argv[]) 198 | { 199 | //初始化 200 | ::google::InitGoogleLogging(argv[0]); 201 | 202 | //参数校验 203 | if ( argc!=5 ) 204 | { 205 | std::cout<<" usage: ./bin/orb_segmentation *.prototxt *.caffemodel image1 image2 "< keypoints1,keypoints2; 230 | //定义存储描述子的容器 231 | cv::Mat descriptors1,descriptors2; 232 | //orb特征检测对象 233 | cv::ORB orb_obj( 1000, 1.2f, 1, 31, 0, 2, ORB::HARRIS_SCORE, 31 ); 234 | //特征检测 235 | orb_obj.detect(img_1,keypoints1); 236 | orb_obj.detect(img_2,keypoints2); 237 | std::cout<<" 两帧图像分别检测到 "< matches; 257 | vector good_matches; 258 | orb_matcher.match(descriptors1,descriptors2,matches); 259 | //根据距离进行筛选 260 | double max_dist=0,min_dist=1000; 261 | for( int i=0;imax_dist) 267 | max_dist=distance; 268 | } 269 | for( int j=0;j keypoints_seg_1,keypoints_seg_2; 302 | cv::Mat descriptors_seg_1,descriptors_seg_2; 303 | for ( int i=0;i(keypoints1[i].pt.y,keypoints1[i].pt.x) == 0) 306 | { 307 | keypoints_seg_1.push_back(keypoints1[i]); 308 | } 309 | } 310 | for ( int i=0;i(keypoints2[i].pt.y,keypoints2[i].pt.x) == 0) 313 | { 314 | keypoints_seg_2.push_back(keypoints2[i]); 315 | } 316 | } 317 | std::cout<<" 筛选后分别有 "< matches_seg; 333 | vector good_matches_seg; 334 | orb_matcher.match(descriptors_seg_1,descriptors_seg_2,matches_seg); 335 | //根据距离进行筛选 336 | max_dist=0; 337 | min_dist=1000; 338 | for( int i=0;imax_dist) 344 | max_dist=distance; 345 | } 346 | for( int j=0;j