Skip to content

Commit 122123f

Browse files
redtail 2.0
1. Added Stereo DNN models and inference library. 2. Migrated to JetPack 3.2. 3. Added support for INT8 inference.
1 parent 17011c1 commit 122123f

File tree

132 files changed

+7751
-306
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

132 files changed

+7751
-306
lines changed

README.md

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@ This project contains deep neural networks, computer vision and control code, ha
66

77
The project's deep neural networks (DNNs) can be trained from scratch using publicly available data. A few [pre-trained DNNs](../blob/master/models/pretrained/) are also available as a part of this project. In case you want to train TrailNet DNN from scratch, follow the steps on [this page](./Models).
88

9+
The project also contains [Stereo DNN](../blob/master/stereoDNN/) models and runtime which allow to estimate depth from stereo camera on NVIDIA platforms.
10+
911
## References and Demos
1012
* [arXiv paper](https://arxiv.org/abs/1705.02550)
1113
* GTC 2017 talk: [slides](http://on-demand.gputechconf.com/gtc/2017/presentation/s7172-nikolai-smolyanskiy-autonomous-drone-navigation-with-deep-learning.pdf), [video](http://on-demand.gputechconf.com/gtc/2017/video/s7172-smolyanskiy-autonomous-drone-navigation-with-deep-learning%20(1).PNG.mp4)
@@ -14,8 +16,15 @@ The project's deep neural networks (DNNs) can be trained from scratch using publ
1416
* [Demo video showing generalization to ground vehicle control and other environments](https://www.youtube.com/watch?v=ZKF5N8xUxfw)
1517

1618
# News
17-
* **2018-02-15**: added support for the TBS discovery platform.
18-
* Step by step instructions on how to assemble the [TBS discovery drone](../../wiki/Skypad-TBS-Discovery-Setup).
19+
**GTC 2018**: in case you will be at [GTC 2018](https://www.nvidia.com/en-us/gtc/) next week, you may be interested in attending our [Stereo DNN session](https://2018gputechconf.smarteventscloud.com/connect/sessionDetail.ww?SESSION_ID=152050). We'll be happy to chat about redtail in general and some of the interesting work that we've been doing.
20+
21+
* **2018-03-22**: redtail 2.0.
22+
* Added Stereo DNN models and inference library (TensorFlow/TensorRT). For more details, see the [README](../blob/master/stereoDNN/).
23+
* Migrated to JetPack 3.2. This change brings latest components such as CUDA 9.0, cuDNN 7.0, TensorRT 3.0, OpenCV 3.3 and others to Jetson platform. Note that this is a breaking change.
24+
* Added support for INT8 inference. This enables fast inference on devices that have hardware implementation of INT8 instructions. More details are on [our wiki](../../wiki/ROS-Nodes#int8-inference).
25+
26+
* **2018-02-15**: added support for the TBS Discovery platform.
27+
* Step by step instructions on how to assemble the [TBS Discovery drone](../../wiki/Skypad-TBS-Discovery-Setup).
1928
* Instructions on how to attach and use a [ZED stereo camera](https://www.stereolabs.com/zed/).
2029
* Detailed instructions on how to calibrate, test and fly the drone.
2130

ros/packages/caffe_ros/CMakeLists.txt

Lines changed: 9 additions & 66 deletions
Original file line numberDiff line numberDiff line change
@@ -12,64 +12,13 @@ find_package(catkin REQUIRED COMPONENTS
1212
## System dependencies are found with CMake's conventions
1313
#find_package(Boost REQUIRED COMPONENTS system)
1414
find_package(CUDA)
15-
# OpenCV 2.4.13 is default on Jetson. Might be required to install in simulation environment.
16-
find_package(OpenCV 2.4.13 REQUIRED)
17-
18-
## Uncomment this if the package has a setup.py. This macro ensures
19-
## modules and global scripts declared therein get installed
20-
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
21-
# catkin_python_setup()
22-
23-
################################################
24-
## Declare ROS messages, services and actions ##
25-
################################################
26-
27-
## To declare and build messages, services or actions from within this
28-
## package, follow these steps:
29-
## * Let MSG_DEP_SET be the set of packages whose message types you use in
30-
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
31-
## * In the file package.xml:
32-
## * add a build_depend tag for "message_generation"
33-
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
34-
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
35-
## but can be declared for certainty nonetheless:
36-
## * add a run_depend tag for "message_runtime"
37-
## * In this file (CMakeLists.txt):
38-
## * add "message_generation" and every package in MSG_DEP_SET to
39-
## find_package(catkin REQUIRED COMPONENTS ...)
40-
## * add "message_runtime" and every package in MSG_DEP_SET to
41-
## catkin_package(CATKIN_DEPENDS ...)
42-
## * uncomment the add_*_files sections below as needed
43-
## and list every .msg/.srv/.action file to be processed
44-
## * uncomment the generate_messages entry below
45-
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
46-
47-
## Generate messages in the 'msg' folder
48-
# add_message_files(
49-
# FILES
50-
# Message1.msg
51-
# Message2.msg
52-
# )
53-
54-
## Generate services in the 'srv' folder
55-
# add_service_files(
56-
# FILES
57-
# Service1.srv
58-
# Service2.srv
59-
# )
60-
61-
## Generate actions in the 'action' folder
62-
# add_action_files(
63-
# FILES
64-
# Action1.action
65-
# Action2.action
66-
# )
67-
68-
## Generate added messages and services with any dependencies listed here
69-
# generate_messages(
70-
# DEPENDENCIES
71-
# std_msgs
72-
# )
15+
# OpenCV 3.3.1 is default on Jetson starting JetPack 3.2. Might be required to install in simulation environment.
16+
# PATHS is required as ROS Kinetic installs its own version of OpenCV 3.3.1 without CUDA support.
17+
find_package(OpenCV 3.3.1 REQUIRED
18+
CONFIG
19+
PATHS /usr/local /usr
20+
NO_DEFAULT_PATH
21+
)
7322

7423
###################################
7524
## catkin specific configuration ##
@@ -95,8 +44,8 @@ set (CMAKE_CXX_STANDARD 14)
9544
set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall")
9645

9746
set(
98-
CUDA_NVCC_FLAGS
99-
${CUDA_NVCC_FLAGS};
47+
CUDA_NVCC_FLAGS
48+
${CUDA_NVCC_FLAGS};
10049
-O3 -gencode arch=compute_53,code=sm_53
10150
)
10251

@@ -108,11 +57,6 @@ include_directories(
10857
${catkin_INCLUDE_DIRS}
10958
)
11059

111-
## Declare a C++ library
112-
# add_library(caffe_ros
113-
# src/${PROJECT_NAME}/caffe_ros.cpp
114-
# )
115-
11660
## Add cmake target dependencies of the library
11761
## as an example, code may need to be generated before libraries
11862
## either from message generation or dynamic reconfigure
@@ -134,7 +78,6 @@ target_link_libraries(caffe_ros_node
13478
nvinfer
13579
opencv_core
13680
opencv_imgproc
137-
opencv_gpu
13881
opencv_highgui
13982
)
14083

Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
// Copyright (c) 2017, NVIDIA CORPORATION. All rights reserved.
2+
// Full license terms provided in LICENSE.md file.
3+
4+
#ifndef CAFFE_ROS_INT8_CALIBRATOR_H
5+
#define CAFFE_ROS_INT8_CALIBRATOR_H
6+
7+
#include <NvInfer.h>
8+
#include <string>
9+
#include "internal_utils.h"
10+
11+
namespace caffe_ros
12+
{
13+
class Int8EntropyCalibrator : public nvinfer1::IInt8EntropyCalibrator
14+
{
15+
public:
16+
Int8EntropyCalibrator(ConstStr& src, ConstStr& calib_cache);
17+
~Int8EntropyCalibrator();
18+
19+
int getBatchSize() const override { return 1; }
20+
bool getBatch(void* bindings[], const char* names[], int nbBindings) override;
21+
22+
const void* readCalibrationCache(size_t& length) override;
23+
void writeCalibrationCache(const void* cache, size_t length) override;
24+
25+
void setInputDims(nvinfer1::DimsCHW dims);
26+
27+
private:
28+
std::string src_;
29+
std::string calib_cache_;
30+
31+
std::deque<std::string> files_;
32+
33+
nvinfer1::DimsCHW dims_ = nvinfer1::DimsCHW(0, 0, 0);
34+
35+
float* img_d_ = nullptr;
36+
};
37+
38+
}
39+
40+
#endif
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
// Copyright (c) 2017, NVIDIA CORPORATION. All rights reserved.
2+
// Full license terms provided in LICENSE.md file.
3+
4+
#ifndef CAFFE_ROS_INTERNAL_UTILS_H
5+
#define CAFFE_ROS_INTERNAL_UTILS_H
6+
7+
#include <opencv2/opencv.hpp>
8+
9+
namespace caffe_ros
10+
{
11+
using ConstStr = const std::string;
12+
13+
// Formats of the input layer. BGR is usually used by most of the frameworks that use OpenCV.
14+
enum class InputFormat
15+
{
16+
BGR = 0,
17+
RGB
18+
};
19+
20+
// Performs image preprocessing (resizing, scaling, format conversion etc)
21+
// that is done before feeding the image into the networ.
22+
cv::Mat preprocessImage(cv::Mat img, int dst_img_w, int dst_img_h, InputFormat inp_fmt, ConstStr& encoding,
23+
float inp_scale, float inp_shift);
24+
25+
}
26+
27+
#endif

ros/packages/caffe_ros/include/caffe_ros/tensor_net.h

Lines changed: 21 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -7,22 +7,23 @@
77
#include <ros/ros.h>
88
#include <NvInfer.h>
99
#include <opencv2/opencv.hpp>
10-
#include <opencv2/gpu/gpu.hpp>
10+
// REVIEW alexeyk: OpenCV that comes with JetPack 3.2 is compiled without CUDA support.
11+
// #include <opencv2/core/cuda.hpp>
12+
13+
#include "int8_calibrator.h"
1114

1215
namespace caffe_ros
1316
{
1417

1518
class TensorNet
1619
{
1720
public:
18-
using ConstStr = const std::string;
19-
2021
TensorNet();
2122
virtual ~TensorNet();
2223

23-
void loadNetwork(ConstStr& prototxtPath, ConstStr& modelPath,
24-
ConstStr& inputBlob = "data", ConstStr& outputBlob = "prob",
25-
bool useFP16 = true, bool use_cached_model = true);
24+
void loadNetwork(ConstStr& prototxt_path, ConstStr& model_path,
25+
ConstStr& input_blob, ConstStr& output_blob,
26+
nvinfer1::DataType data_type, bool use_cached_model);
2627

2728
void forward(const unsigned char* input, size_t w, size_t h, size_t c, const std::string& encoding);
2829

@@ -36,15 +37,15 @@ class TensorNet
3637

3738
const float* getOutput() const { return out_h_; }
3839

39-
void setInputFormat(ConstStr& inputFormat)
40+
void setInputFormat(ConstStr& input_format)
4041
{
41-
if (inputFormat == "BGR")
42+
if (input_format == "BGR")
4243
inp_fmt_ = InputFormat::BGR;
43-
else if (inputFormat == "RGB")
44+
else if (input_format == "RGB")
4445
inp_fmt_ = InputFormat::RGB;
4546
else
4647
{
47-
ROS_FATAL("Input format %s is not supported. Supported formats: BGR and RGB", inputFormat.c_str());
48+
ROS_FATAL("Input format %s is not supported. Supported formats: BGR and RGB", input_format.c_str());
4849
ros::shutdown();
4950
}
5051
}
@@ -68,16 +69,12 @@ class TensorNet
6869
context_->setProfiler(on ? &s_profiler : nullptr);
6970
}
7071

71-
protected:
72+
void createInt8Calibrator(ConstStr& int8_calib_src, ConstStr& int8_calib_cache);
7273

73-
// Formats of the input layer. BGR is usually used by most of the frameworks that use OpenCV.
74-
enum class InputFormat
75-
{
76-
BGR = 0,
77-
RGB
78-
};
74+
protected:
7975

80-
void profileModel(ConstStr& prototxtPath, ConstStr& modelPath, bool useFP16, ConstStr& outputBlob, std::ostream& model);
76+
void profileModel(ConstStr& prototxt_path, ConstStr& model_path, nvinfer1::DataType data_type,
77+
ConstStr& input_blob, ConstStr& output_blob, std::ostream& model);
8178

8279
class Logger : public nvinfer1::ILogger
8380
{
@@ -109,9 +106,7 @@ class TensorNet
109106

110107
cv::Mat in_h_;
111108
cv::Mat in_final_h_;
112-
// cv::gpu::GpuMat m_inOrigD;
113-
// cv::gpu::GpuMat m_inD;
114-
cv::gpu::GpuMat in_d_;
109+
float* in_d_ = nullptr;
115110
float* out_h_ = nullptr;
116111
float* out_d_ = nullptr;
117112

@@ -121,8 +116,13 @@ class TensorNet
121116
// This is a separate flag from ROS_DEBUG to enable only specific profiling
122117
// of data preparation and DNN feed forward.
123118
bool debug_mode_ = false;
119+
120+
std::unique_ptr<Int8EntropyCalibrator> int8_calib_;
124121
};
125122

123+
nvinfer1::DataType parseDataType(const std::string& src);
124+
std::string toString(nvinfer1::DataType src);
125+
126126
}
127127

128128
#endif

ros/packages/caffe_ros/launch/caffe_gscam.launch

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<arg name="model_path" />
44
<arg name="input_layer" default="data" />
55
<arg name="output_layer" default="prob" />
6-
<arg name="use_fp16" default="true" />
6+
<arg name="data_type" default="fp16" />
77
<arg name="mean" default="0" />
88
<arg name="debug_mode" default="false" />
99

@@ -29,7 +29,7 @@
2929
<param name="model_path" value="$(arg model_path)" />
3030
<param name="input_layer" value="$(arg input_layer)" />
3131
<param name="output_layer" value="$(arg output_layer)" />
32-
<param name="use_fp16" value="$(arg use_fp16)" />
32+
<param name="data_type" value="$(arg data_type)" />
3333
<param name="mean" value="$(arg mean)" />
3434
<param name="debug_mode" value="$(arg debug_mode)" />
3535
</node>

ros/packages/caffe_ros/launch/caffe_gscam_h264.launch

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<arg name="model_path" />
44
<arg name="input_layer" default="data" />
55
<arg name="output_layer" default="prob" />
6-
<arg name="use_fp16" default="true" />
6+
<arg name="data_type" default="fp16" />
77
<arg name="mean" default="0" />
88
<arg name="debug_mode" default="false" />
99

@@ -26,7 +26,7 @@
2626
<param name="model_path" value="$(arg model_path)" />
2727
<param name="input_layer" value="$(arg input_layer)" />
2828
<param name="output_layer" value="$(arg output_layer)" />
29-
<param name="use_fp16" value="$(arg use_fp16)" />
29+
<param name="data_type" value="$(arg data_type)" />
3030
<param name="mean" value="$(arg mean)" />
3131
<param name="debug_mode" value="$(arg debug_mode)" />
3232
</node>

ros/packages/caffe_ros/launch/caffe_gscam_h265.launch

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<arg name="model_path" />
44
<arg name="input_layer" default="data" />
55
<arg name="output_layer" default="prob" />
6-
<arg name="use_fp16" default="true" />
6+
<arg name="data_type" default="fp16" />
77
<arg name="mean" default="0" />
88
<arg name="debug_mode" default="false" />
99

@@ -26,7 +26,7 @@
2626
<param name="model_path" value="$(arg model_path)" />
2727
<param name="input_layer" value="$(arg input_layer)" />
2828
<param name="output_layer" value="$(arg output_layer)" />
29-
<param name="use_fp16" value="$(arg use_fp16)" />
29+
<param name="data_type" value="$(arg data_type)" />
3030
<param name="mean" value="$(arg mean)" />
3131
<param name="debug_mode" value="$(arg debug_mode)" />
3232
</node>

ros/packages/caffe_ros/launch/everything.launch

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,13 @@
22
<arg name="trail_prototxt_path" default="/home/nvidia/redtail/models/pretrained/TrailNet_SResNet-18.prototxt" />
33
<arg name="trail_model_path" default="/home/nvidia/redtail/models/pretrained/TrailNet_SResNet-18.caffemodel" />
44
<arg name="trail_output_layer" default="out" />
5-
<arg name="trail_use_fp16" default="true" />
5+
<arg name="trail_data_type" default="fp16" />
66
<arg name="trail_rate_hz" default="30" />
77

88
<arg name="object_prototxt_path" default="/home/nvidia/redtail/models/pretrained/yolo-relu.prototxt" />
99
<arg name="object_model_path" default="/home/nvidia/redtail/models/pretrained/yolo-relu.caffemodel" />
1010
<arg name="object_output_layer" default="fc25" />
11-
<arg name="object_use_fp16" default="true" />
11+
<arg name="object_data_type" default="fp16" />
1212
<arg name="object_rate_hz" default="1" />
1313
<arg name="obj_det_threshold" default="0.2" />
1414

@@ -40,7 +40,7 @@
4040
<param name="prototxt_path" value="$(arg trail_prototxt_path)" />
4141
<param name="model_path" value="$(arg trail_model_path)" />
4242
<param name="output_layer" value="$(arg trail_output_layer)" />
43-
<param name="use_fp16" value="$(arg trail_use_fp16)" />
43+
<param name="data_type" value="$(arg trail_data_type)" />
4444
<param name="max_rate_hz" value="$(arg trail_rate_hz)" />
4545
</node>
4646

@@ -54,7 +54,7 @@
5454
<param name="post_proc" value="YOLO" />
5555
<param name="obj_det_threshold" value="$(arg obj_det_threshold)" />
5656
<param name="iou_threshold" value="0.2" />
57-
<param name="use_fp16" value="$(arg object_use_fp16)" />
57+
<param name="data_type" value="$(arg object_data_type)" />
5858
<param name="max_rate_hz" value="$(arg object_rate_hz)" />
5959
</node>
6060

0 commit comments

Comments
 (0)