diff --git a/hfnet_ros/.gitignore b/hfnet_ros/.gitignore new file mode 100644 index 0000000..f147b8c --- /dev/null +++ b/hfnet_ros/.gitignore @@ -0,0 +1,2 @@ +saved_models/ +.vscode/ diff --git a/hfnet_ros/CMakeLists.txt b/hfnet_ros/CMakeLists.txt new file mode 100644 index 0000000..2cfb5c6 --- /dev/null +++ b/hfnet_ros/CMakeLists.txt @@ -0,0 +1,72 @@ +cmake_minimum_required(VERSION 3.0.2) +project(hfnet_ros) + +## Compile as C++11, supported in ROS Kinetic and newer +add_compile_options(-std=c++11) + +find_package(CUDA) +include(FindProtobuf) +find_package(Protobuf REQUIRED "3.6.0") + +if (Protobuf_FOUND) + INCLUDE_DIRECTORIES(${PROTOBUF_INCLUDE_DIR}) +else (Protobuf_FOUND) + MESSAGE(FATAL_ERROR "PROTOBUF NOT FOUNED") +endif (Protobuf_FOUND) + +find_package(OpenCV REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + cv_bridge + image_transport + roscpp + rospy + std_msgs +) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES + CATKIN_DEPENDS +# DEPENDS system_lib +) + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${PROJECT_SOURCE_DIR} + "/usr/local/include/eigen3" + ${OpenCV_INCLUDE_DIRS} +) + +# tensorflow +include_directories(/usr/local/include/tf) +include_directories(/usr/local/include/tf/tensorflow) +#include_directories(/usr/local/include/tf/bazel-tensorflow/external/eigen_archive) +#include_directories(/usr/local/include/tf/bazel-tensorflow/external/protobuf_archive/src) +include_directories(/usr/local/include/tf/absl) +include_directories(/usr/local/include/tf/bazel-genfiles) +include_directories(/usr/local/include/tf/tensorflow/cc) +include_directories(/usr/local/include/tf/tensorflow/c) +include_directories(/usr/local/include/tf/tensorflow/core) + +link_directories(/usr/local/lib) + +add_executable(hfnet_ros_node src/hfnet_ros_node.cpp) +find_package(CUDA) +if(CUDA_FOUND) + message("FIND_CUDA") + target_link_libraries(hfnet_ros_node + ${CUDA_LIBRARIES} + ${PROTOBUF_LIBRARY} + ${OpenCV_LIBS} + /usr/local/lib/libtensorflow_cc.so + /usr/local/lib/libtensorflow_framework.so + ${catkin_LIBRARIES} + ) + +endif() + + diff --git a/hfnet_ros/README.md b/hfnet_ros/README.md new file mode 100644 index 0000000..e6371f6 --- /dev/null +++ b/hfnet_ros/README.md @@ -0,0 +1,72 @@ +## **A Cpp Version of HF-NET** + +![demo](data/hfnet-1660s-demo.gif) + +## **9ms in GeForce GTX 2080 Ti** + +## **15-20ms in GeForce GTX 1660s 6G** + +Since the origin HF-NET based on Python3, May be it is a little difficult integrate the code with your Cpp projects(some SLAM system). To run the `hfnet_ros` package, you need install the tensorflow from the source. For convience, you can using the docker image here to run this package. + +This package allows to: + +* Extract feature detectors and descriptors on standard image sequence +* Integrate other slam system which written in cpp. +* Combine the origin [hloc-cpp](https://github.com/ethz-asl/hfnet/tree/master/hloc-cpp) back-end and make a full cpp projects. +* It takes 15-20ms in GeForce GTX 1660s 6G. + +### Setup + +* python 2.7 +* Ubuntu 16.04 +* ROS Kinetic +* CUDA = 9.0 +* Cudnn = 7.0 +* Tensorflow cpp gpu == 1.12 (you need build and install tf1.12 from source, and copy the libs to /usr/local/lib) +* opencv > 3.0 + +### Docker + +Build tensorflow from source is annoying, So if you wanna test the code , you can using docker image. + +```bash +sudo docker pull xinliangzhong/1604-tf1.2cc-cuda9.0-cudnn7.0-ros:latest +``` + +```bash +sudo docker run --gpus all --name="hfnet-ros" --net=host -it -v /YOUR/PATH:/root/data xinliangzhong/1604-tf1.2cc-cuda9.0-cudnn7.0-ros:latest /bin/bash +``` + + + +### How to run + + +```bash +cd /root/data +mkdir -p catkin_ws/src +cd catkin_ws/src +git clone https://github.com/TurtleZhong/hfnet_ros.git + +# fetch model +cd hfnet_ros/model/ +chmod +x download.sh +./download.sh + +catkin_make -DCMAKE_BUILD_TYPE=Release +``` + +```bash +cd /root/data/catkin_ws/ +source devel/setup.bash +roslaunch hfnet_ros hfnet_ros_node.launch +``` +Then you will get this in terminal. +```bash +... +detected: 817 pts +IMAGE[480 x 752] cost: 18 ms +... +``` + +The results image is publish as ros msg. if your start docker container using `--net=host`, you can using rqt to view the results. diff --git a/hfnet_ros/data/1.png b/hfnet_ros/data/1.png new file mode 100644 index 0000000..4ea3336 Binary files /dev/null and b/hfnet_ros/data/1.png differ diff --git a/hfnet_ros/data/hfnet-1660s-demo.gif b/hfnet_ros/data/hfnet-1660s-demo.gif new file mode 100644 index 0000000..1d2aa7e Binary files /dev/null and b/hfnet_ros/data/hfnet-1660s-demo.gif differ diff --git a/hfnet_ros/data/sample.bag b/hfnet_ros/data/sample.bag new file mode 100644 index 0000000..3cd4d8b Binary files /dev/null and b/hfnet_ros/data/sample.bag differ diff --git a/hfnet_ros/include/hfnet_ros/tensorflow_net.h b/hfnet_ros/include/hfnet_ros/tensorflow_net.h new file mode 100644 index 0000000..f6f908a --- /dev/null +++ b/hfnet_ros/include/hfnet_ros/tensorflow_net.h @@ -0,0 +1,152 @@ +#ifndef HFNET_TENSORFLOW_NET_H_ +#define HFNET_TENSORFLOW_NET_H_ + +#include +#include +#include + + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include + + +using tensorflow::Status; +using tensorflow::Tensor; +using namespace tensorflow; + +class TensorflowNet { + public: + typedef Eigen::Matrix GlobalDescType; + typedef Eigen::Matrix KeyPointType; + typedef Eigen::Matrix LocalDescType; + + TensorflowNet(const std::string model_path , + const unsigned int topk_num = 2000, + const unsigned int nms_radius = 4): + topk_kpts_(topk_num), nms_radius_(nms_radius) { + CHECK(tensorflow::MaybeSavedModelDirectory(model_path)); + input_channels_ = 1; + descriptor_size_ = 4096; + std::string resample_path = "/usr/local/lib/_resampler_ops.so"; + TF_Status* tf_status = TF_NewStatus(); + + + TF_LoadLibrary(resample_path.c_str(),tf_status); + + std::cout << "TF_GetCode(tf_status): " << TF_GetCode(tf_status) << std::endl; + + LOG(INFO) << "HERE"; + + if (TF_GetCode(tf_status) !=TF_OK) { + std::cerr << "TF_LoadLibrary _resampler_ops.so ERROR, Load resampler.so failed, Please check.\n"; + } + + // Load model + tensorflow::SessionOptions session_options; + // tensorflow::graph::SetDefaultDevice("/gpu:0", &graph_def); + session_options.config.mutable_gpu_options()->set_allow_growth(true); + session_options.config.mutable_gpu_options()->set_per_process_gpu_memory_fraction(0.5); + Status status = tensorflow::LoadSavedModel( + session_options, tensorflow::RunOptions(), + model_path, {tensorflow::kSavedModelTagServe}, &bundle_); + if (!status.ok()) + LOG(FATAL) << status.ToString(); + + // Check input and output shapes + tensorflow::GraphDef graph_def = bundle_.meta_graph_def.graph_def(); + bool found_input = false, found_output = false; + for (auto& node : graph_def.node()) { + // check graph here + if(node.name() == "global_descriptor") + std::cout << "global_desc: " << node.name() << std::endl; + // std::cout << node.name() << std::endl; + } + + std::cout << "load suscessfully" << std::endl; + } + + void PerformInference(const cv::Mat& image, int &kpts_num, GlobalDescType* global_desc, KeyPointType* key_points, LocalDescType* local_desc) { + CHECK(image.data); + CHECK(image.isContinuous()); + + unsigned height = image.size().height, width = image.size().width; + // TODO: cleaner way to avoid copying when the image is already float + // or combine with tensor creation + cv::Mat *float_image_ptr, tmp; + if(image.type() != CV_32F) { + image.convertTo(tmp, CV_32F); + float_image_ptr = &tmp; + } else { + float_image_ptr = &const_cast(image); + } + + // Prepare input tensor + Tensor input_tensor( + tensorflow::DT_FLOAT, + tensorflow::TensorShape({1, height, width, input_channels_})); + Tensor keypoints_num(tensorflow::DT_INT32,TensorShape()); + Tensor radius(tensorflow::DT_INT32,TensorShape()); + keypoints_num.scalar()() = 2000; + radius.scalar()() = 4; + // TODO: avoid copy if possible + tensorflow::StringPiece tmp_data = input_tensor.tensor_data(); + std::memcpy(const_cast(tmp_data.data()), float_image_ptr->data, + height * width * input_channels_ * sizeof(float)); + + + // Run inference here average 15-20ms in 1660 + std::vector outputs; + Status status = bundle_.session->Run({{"image:0", input_tensor},{"pred/simple_nms/radius", radius},{"pred/top_k_keypoints/k",keypoints_num}}, + {"global_descriptor", "keypoints", "local_descriptors"}, {}, &outputs); + + if (!status.ok()) + LOG(FATAL) << status.ToString(); + // std::cout << "inference done" << std::endl; + // Copy result + float *descriptor_ptr = outputs[0].flat().data(); + Eigen::Map descriptor_map(descriptor_ptr, descriptor_size_); + Eigen::Matrix desc = + Eigen::Map>(descriptor_ptr, 4096, 1); + int kp_num = outputs[1].shape().dim_size(1); + kpts_num = kp_num; + std::cout << "detected: " << kp_num << " pts" << std::endl; + *global_desc = descriptor_map; // Copy + int *kpts_ptr = outputs[1].flat().data(); + Eigen::Matrix kpts_int = + Eigen::Map>(kpts_ptr, kp_num, 2); + Eigen::MatrixXf kpts = kpts_int.cast(); + *key_points = kpts; // Copy + + + float *local_desc_ptr = outputs[2].flat().data(); + static const int dim = 256; + Eigen::Matrix kpts_desc = + Eigen::Map>(local_desc_ptr, kp_num, dim); + *local_desc = kpts_desc; // Copy + } + + unsigned descriptor_size() { + return descriptor_size_; + } + + private: + tensorflow::SavedModelBundle bundle_; + unsigned descriptor_size_; + unsigned input_channels_; + unsigned int topk_kpts_; + unsigned int nms_radius_; +}; + +#endif // HFNET_TENSORFLOW_NET_H_ + diff --git a/hfnet_ros/launch/hfnet_ros_node.launch b/hfnet_ros/launch/hfnet_ros_node.launch new file mode 100644 index 0000000..76481e6 --- /dev/null +++ b/hfnet_ros/launch/hfnet_ros_node.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/hfnet_ros/model/download.sh b/hfnet_ros/model/download.sh new file mode 100755 index 0000000..06dbc5d --- /dev/null +++ b/hfnet_ros/model/download.sh @@ -0,0 +1,10 @@ +#!/bin/sh +echo "Download hfnet model..." +wget http://robotics.ethz.ch/~asl-datasets/2019_CVPR_hierarchical_localization/hfnet_tf.tar.gz +echo "Download suscess! start extract..." +tar -xavf hfnet_tf.tar.gz + +rm -rf hfnet +rm *.gz + +echo "Done!" diff --git a/hfnet_ros/package.xml b/hfnet_ros/package.xml new file mode 100644 index 0000000..cc69f94 --- /dev/null +++ b/hfnet_ros/package.xml @@ -0,0 +1,74 @@ + + + hfnet_ros + 0.0.0 + The hfnet_ros package + + + + + root + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + cv_bridge + image_transport + roscpp + rospy + std_msgs + cv_bridge + image_transport + roscpp + rospy + std_msgs + cv_bridge + image_transport + roscpp + rospy + std_msgs + + + + + + + + diff --git a/hfnet_ros/src/hfnet_ros_node.cpp b/hfnet_ros/src/hfnet_ros_node.cpp new file mode 100644 index 0000000..a2af4ab --- /dev/null +++ b/hfnet_ros/src/hfnet_ros_node.cpp @@ -0,0 +1,94 @@ +#include +#include + +#include +#include +#include +#include +#include + +#include "hfnet_ros/tensorflow_net.h" + +#include + +using namespace std; +using namespace tensorflow; + +static sensor_msgs::ImageConstPtr img0_cur; + +void img0_callback(const sensor_msgs::ImageConstPtr &img_msg) { + img0_cur = img_msg; +} + +int main(int argc, char **argv) { + ros::init(argc, argv, "hfnet_ros_node"); + ros::NodeHandle n("~"); + image_transport::ImageTransport it(n); + ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, + ros::console::levels::Info); + std::string model_dir = "/root/data/hfnet/hfnet_tf/saved_models/hfnet"; + std::string test_image = ""; + std::string input_img_topic = "/cam0"; + int topk_num = 2000; + int nms_radius = 4; + bool flag_show = false; + + n.param("model_dir", model_dir, model_dir); + n.param("test_image", test_image, test_image); + n.param("input_img_topic", input_img_topic, input_img_topic); + n.param("topk_kpts_num", topk_num, topk_num); + n.param("nms_radius", nms_radius, nms_radius); + n.param("opencv_show_image", flag_show, flag_show); + + + ros::Subscriber sub_img0 = + n.subscribe(input_img_topic, 1, img0_callback); + + image_transport::Publisher pub_image = + it.advertise("/debug_pts", 10); + + TensorflowNet network(model_dir, topk_num, nms_radius); + // read params here + TensorflowNet::GlobalDescType global_desc; + TensorflowNet::KeyPointType kpts; + TensorflowNet::LocalDescType local_desc; + int kpts_num = -1; + cv::Mat image = cv::imread(test_image, CV_LOAD_IMAGE_GRAYSCALE); + + auto start = chrono::system_clock::now(); + network.PerformInference(image, kpts_num, &global_desc, &kpts, &local_desc); + auto end = chrono::system_clock::now(); + std::cout << "cost: " << chrono::duration_cast(end-start).count() << " ms" << std::endl; + ROS_WARN_STREAM("Waiting " << input_img_topic << " image..."); + + + + ros::Rate loop_rate(30); + while (ros::ok()) { + ros::spinOnce(); // do callback + if (img0_cur) { + // run hfnet-cpp + cv_bridge::CvImageConstPtr srcImage = cv_bridge::toCvShare(img0_cur, sensor_msgs::image_encodings::MONO8); + + auto start = chrono::system_clock::now(); + network.PerformInference(srcImage->image, kpts_num, &global_desc, &kpts, &local_desc); + auto end = chrono::system_clock::now(); + std::cout << "IMAGE[" << srcImage->image.size << "] cost: " << chrono::duration_cast(end-start).count() << " ms" << std::endl; + + cv::Mat image_copy = srcImage->image.clone(); + cv::cvtColor(image_copy, image_copy, CV_GRAY2BGR); + for (size_t i = 0; i < kpts_num; i++) + { + cv::circle(image_copy, cv::Point(kpts.row(i)(0), kpts.row(i)(1)), 2, cv::Scalar(0,255,0), -1); + } + + std::string tmp = "total kpts: " + std::to_string(kpts_num) + ", cost: " + std::to_string(chrono::duration_cast(end-start).count()) + " ms"; + cv::putText(image_copy, tmp, cv::Point(20,20),CV_FONT_HERSHEY_SIMPLEX, 0.8, cv::Scalar(0,0,255),2); + sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image_copy).toImageMsg(); + pub_image.publish(msg); + img0_cur.reset(); + } + loop_rate.sleep(); +} +return 0; +}