Răsfoiți Sursa

add percerption_camera_yolo_tenserrt, complete. add perception_camera_yolo, not complete.

yuchuli 4 luni în urmă
părinte
comite
e864c36446

+ 5 - 0
src/api/perception_camera_yolo/Readme.md

@@ -0,0 +1,5 @@
+
+https://pjreddie.com/darknet/yolo/
+
+
+

+ 805 - 0
src/api/perception_camera_yolo/darknet.h

@@ -0,0 +1,805 @@
+#ifndef DARKNET_API
+#define DARKNET_API
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+#include <pthread.h>
+
+#ifdef GPU
+    #define BLOCK 512
+
+    #include "cuda_runtime.h"
+    #include "curand.h"
+    #include "cublas_v2.h"
+
+    #ifdef CUDNN
+    #include "cudnn.h"
+    #endif
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define SECRET_NUM -1234
+extern int gpu_index;
+
+typedef struct{
+    int classes;
+    char **names;
+} metadata;
+
+metadata get_metadata(char *file);
+
+typedef struct{
+    int *leaf;
+    int n;
+    int *parent;
+    int *child;
+    int *group;
+    char **name;
+
+    int groups;
+    int *group_size;
+    int *group_offset;
+} tree;
+tree *read_tree(char *filename);
+
+typedef enum{
+    LOGISTIC, RELU, RELIE, LINEAR, RAMP, TANH, PLSE, LEAKY, ELU, LOGGY, STAIR, HARDTAN, LHTAN, SELU
+} ACTIVATION;
+
+typedef enum{
+    PNG, BMP, TGA, JPG
+} IMTYPE;
+
+typedef enum{
+    MULT, ADD, SUB, DIV
+} BINARY_ACTIVATION;
+
+typedef enum {
+    CONVOLUTIONAL,
+    DECONVOLUTIONAL,
+    CONNECTED,
+    MAXPOOL,
+    SOFTMAX,
+    DETECTION,
+    DROPOUT,
+    CROP,
+    ROUTE,
+    COST,
+    NORMALIZATION,
+    AVGPOOL,
+    LOCAL,
+    SHORTCUT,
+    ACTIVE,
+    RNN,
+    GRU,
+    LSTM,
+    CRNN,
+    BATCHNORM,
+    NETWORK,
+    XNOR,
+    REGION,
+    YOLO,
+    ISEG,
+    REORG,
+    UPSAMPLE,
+    LOGXENT,
+    L2NORM,
+    BLANK
+} LAYER_TYPE;
+
+typedef enum{
+    SSE, MASKED, L1, SEG, SMOOTH,WGAN
+} COST_TYPE;
+
+typedef struct{
+    int batch;
+    float learning_rate;
+    float momentum;
+    float decay;
+    int adam;
+    float B1;
+    float B2;
+    float eps;
+    int t;
+} update_args;
+
+struct network;
+typedef struct network network;
+
+struct layer;
+typedef struct layer layer;
+
+struct layer{
+    LAYER_TYPE type;
+    ACTIVATION activation;
+    COST_TYPE cost_type;
+    void (*forward)   (struct layer, struct network);
+    void (*backward)  (struct layer, struct network);
+    void (*update)    (struct layer, update_args);
+    void (*forward_gpu)   (struct layer, struct network);
+    void (*backward_gpu)  (struct layer, struct network);
+    void (*update_gpu)    (struct layer, update_args);
+    int batch_normalize;
+    int shortcut;
+    int batch;
+    int forced;
+    int flipped;
+    int inputs;
+    int outputs;
+    int nweights;
+    int nbiases;
+    int extra;
+    int truths;
+    int h,w,c;
+    int out_h, out_w, out_c;
+    int n;
+    int max_boxes;
+    int groups;
+    int size;
+    int side;
+    int stride;
+    int reverse;
+    int flatten;
+    int spatial;
+    int pad;
+    int sqrt;
+    int flip;
+    int index;
+    int binary;
+    int xnor;
+    int steps;
+    int hidden;
+    int truth;
+    float smooth;
+    float dot;
+    float angle;
+    float jitter;
+    float saturation;
+    float exposure;
+    float shift;
+    float ratio;
+    float learning_rate_scale;
+    float clip;
+    int noloss;
+    int softmax;
+    int classes;
+    int coords;
+    int background;
+    int rescore;
+    int objectness;
+    int joint;
+    int noadjust;
+    int reorg;
+    int log;
+    int tanh;
+    int *mask;
+    int total;
+
+    float alpha;
+    float beta;
+    float kappa;
+
+    float coord_scale;
+    float object_scale;
+    float noobject_scale;
+    float mask_scale;
+    float class_scale;
+    int bias_match;
+    int random;
+    float ignore_thresh;
+    float truth_thresh;
+    float thresh;
+    float focus;
+    int classfix;
+    int absolute;
+
+    int onlyforward;
+    int stopbackward;
+    int dontload;
+    int dontsave;
+    int dontloadscales;
+    int numload;
+
+    float temperature;
+    float probability;
+    float scale;
+
+    char  * cweights;
+    int   * indexes;
+    int   * input_layers;
+    int   * input_sizes;
+    int   * map;
+    int   * counts;
+    float ** sums;
+    float * rand;
+    float * cost;
+    float * state;
+    float * prev_state;
+    float * forgot_state;
+    float * forgot_delta;
+    float * state_delta;
+    float * combine_cpu;
+    float * combine_delta_cpu;
+
+    float * concat;
+    float * concat_delta;
+
+    float * binary_weights;
+
+    float * biases;
+    float * bias_updates;
+
+    float * scales;
+    float * scale_updates;
+
+    float * weights;
+    float * weight_updates;
+
+    float * delta;
+    float * output;
+    float * loss;
+    float * squared;
+    float * norms;
+
+    float * spatial_mean;
+    float * mean;
+    float * variance;
+
+    float * mean_delta;
+    float * variance_delta;
+
+    float * rolling_mean;
+    float * rolling_variance;
+
+    float * x;
+    float * x_norm;
+
+    float * m;
+    float * v;
+    
+    float * bias_m;
+    float * bias_v;
+    float * scale_m;
+    float * scale_v;
+
+
+    float *z_cpu;
+    float *r_cpu;
+    float *h_cpu;
+    float * prev_state_cpu;
+
+    float *temp_cpu;
+    float *temp2_cpu;
+    float *temp3_cpu;
+
+    float *dh_cpu;
+    float *hh_cpu;
+    float *prev_cell_cpu;
+    float *cell_cpu;
+    float *f_cpu;
+    float *i_cpu;
+    float *g_cpu;
+    float *o_cpu;
+    float *c_cpu;
+    float *dc_cpu; 
+
+    float * binary_input;
+
+    struct layer *input_layer;
+    struct layer *self_layer;
+    struct layer *output_layer;
+
+    struct layer *reset_layer;
+    struct layer *update_layer;
+    struct layer *state_layer;
+
+    struct layer *input_gate_layer;
+    struct layer *state_gate_layer;
+    struct layer *input_save_layer;
+    struct layer *state_save_layer;
+    struct layer *input_state_layer;
+    struct layer *state_state_layer;
+
+    struct layer *input_z_layer;
+    struct layer *state_z_layer;
+
+    struct layer *input_r_layer;
+    struct layer *state_r_layer;
+
+    struct layer *input_h_layer;
+    struct layer *state_h_layer;
+	
+    struct layer *wz;
+    struct layer *uz;
+    struct layer *wr;
+    struct layer *ur;
+    struct layer *wh;
+    struct layer *uh;
+    struct layer *uo;
+    struct layer *wo;
+    struct layer *uf;
+    struct layer *wf;
+    struct layer *ui;
+    struct layer *wi;
+    struct layer *ug;
+    struct layer *wg;
+
+    tree *softmax_tree;
+
+    size_t workspace_size;
+
+#ifdef GPU
+    int *indexes_gpu;
+
+    float *z_gpu;
+    float *r_gpu;
+    float *h_gpu;
+
+    float *temp_gpu;
+    float *temp2_gpu;
+    float *temp3_gpu;
+
+    float *dh_gpu;
+    float *hh_gpu;
+    float *prev_cell_gpu;
+    float *cell_gpu;
+    float *f_gpu;
+    float *i_gpu;
+    float *g_gpu;
+    float *o_gpu;
+    float *c_gpu;
+    float *dc_gpu; 
+
+    float *m_gpu;
+    float *v_gpu;
+    float *bias_m_gpu;
+    float *scale_m_gpu;
+    float *bias_v_gpu;
+    float *scale_v_gpu;
+
+    float * combine_gpu;
+    float * combine_delta_gpu;
+
+    float * prev_state_gpu;
+    float * forgot_state_gpu;
+    float * forgot_delta_gpu;
+    float * state_gpu;
+    float * state_delta_gpu;
+    float * gate_gpu;
+    float * gate_delta_gpu;
+    float * save_gpu;
+    float * save_delta_gpu;
+    float * concat_gpu;
+    float * concat_delta_gpu;
+
+    float * binary_input_gpu;
+    float * binary_weights_gpu;
+
+    float * mean_gpu;
+    float * variance_gpu;
+
+    float * rolling_mean_gpu;
+    float * rolling_variance_gpu;
+
+    float * variance_delta_gpu;
+    float * mean_delta_gpu;
+
+    float * x_gpu;
+    float * x_norm_gpu;
+    float * weights_gpu;
+    float * weight_updates_gpu;
+    float * weight_change_gpu;
+
+    float * biases_gpu;
+    float * bias_updates_gpu;
+    float * bias_change_gpu;
+
+    float * scales_gpu;
+    float * scale_updates_gpu;
+    float * scale_change_gpu;
+
+    float * output_gpu;
+    float * loss_gpu;
+    float * delta_gpu;
+    float * rand_gpu;
+    float * squared_gpu;
+    float * norms_gpu;
+#ifdef CUDNN
+    cudnnTensorDescriptor_t srcTensorDesc, dstTensorDesc;
+    cudnnTensorDescriptor_t dsrcTensorDesc, ddstTensorDesc;
+    cudnnTensorDescriptor_t normTensorDesc;
+    cudnnFilterDescriptor_t weightDesc;
+    cudnnFilterDescriptor_t dweightDesc;
+    cudnnConvolutionDescriptor_t convDesc;
+    cudnnConvolutionFwdAlgo_t fw_algo;
+    cudnnConvolutionBwdDataAlgo_t bd_algo;
+    cudnnConvolutionBwdFilterAlgo_t bf_algo;
+#endif
+#endif
+};
+
+void free_layer(layer);
+
+typedef enum {
+    CONSTANT, STEP, EXP, POLY, STEPS, SIG, RANDOM
+} learning_rate_policy;
+
+typedef struct network{
+    int n;
+    int batch;
+    size_t *seen;
+    int *t;
+    float epoch;
+    int subdivisions;
+    layer *layers;
+    float *output;
+    learning_rate_policy policy;
+
+    float learning_rate;
+    float momentum;
+    float decay;
+    float gamma;
+    float scale;
+    float power;
+    int time_steps;
+    int step;
+    int max_batches;
+    float *scales;
+    int   *steps;
+    int num_steps;
+    int burn_in;
+
+    int adam;
+    float B1;
+    float B2;
+    float eps;
+
+    int inputs;
+    int outputs;
+    int truths;
+    int notruth;
+    int h, w, c;
+    int max_crop;
+    int min_crop;
+    float max_ratio;
+    float min_ratio;
+    int center;
+    float angle;
+    float aspect;
+    float exposure;
+    float saturation;
+    float hue;
+    int random;
+
+    int gpu_index;
+    tree *hierarchy;
+
+    float *input;
+    float *truth;
+    float *delta;
+    float *workspace;
+    int train;
+    int index;
+    float *cost;
+    float clip;
+
+#ifdef GPU
+    float *input_gpu;
+    float *truth_gpu;
+    float *delta_gpu;
+    float *output_gpu;
+#endif
+
+} network;
+
+typedef struct {
+    int w;
+    int h;
+    float scale;
+    float rad;
+    float dx;
+    float dy;
+    float aspect;
+} augment_args;
+
+typedef struct {
+    int w;
+    int h;
+    int c;
+    float *data;
+} image;
+
+typedef struct{
+    float x, y, w, h;
+} box;
+
+typedef struct detection{
+    box bbox;
+    int classes;
+    float *prob;
+    float *mask;
+    float objectness;
+    int sort_class;
+} detection;
+
+typedef struct matrix{
+    int rows, cols;
+    float **vals;
+} matrix;
+
+
+typedef struct{
+    int w, h;
+    matrix X;
+    matrix y;
+    int shallow;
+    int *num_boxes;
+    box **boxes;
+} data;
+
+typedef enum {
+    CLASSIFICATION_DATA, DETECTION_DATA, CAPTCHA_DATA, REGION_DATA, IMAGE_DATA, COMPARE_DATA, WRITING_DATA, SWAG_DATA, TAG_DATA, OLD_CLASSIFICATION_DATA, STUDY_DATA, DET_DATA, SUPER_DATA, LETTERBOX_DATA, REGRESSION_DATA, SEGMENTATION_DATA, INSTANCE_DATA, ISEG_DATA
+} data_type;
+
+typedef struct load_args{
+    int threads;
+    char **paths;
+    char *path;
+    int n;
+    int m;
+    char **labels;
+    int h;
+    int w;
+    int out_w;
+    int out_h;
+    int nh;
+    int nw;
+    int num_boxes;
+    int min, max, size;
+    int classes;
+    int background;
+    int scale;
+    int center;
+    int coords;
+    float jitter;
+    float angle;
+    float aspect;
+    float saturation;
+    float exposure;
+    float hue;
+    data *d;
+    image *im;
+    image *resized;
+    data_type type;
+    tree *hierarchy;
+} load_args;
+
+typedef struct{
+    int id;
+    float x,y,w,h;
+    float left, right, top, bottom;
+} box_label;
+
+
+network *load_network(char *cfg, char *weights, int clear);
+load_args get_base_args(network *net);
+
+void free_data(data d);
+
+typedef struct node{
+    void *val;
+    struct node *next;
+    struct node *prev;
+} node;
+
+typedef struct list{
+    int size;
+    node *front;
+    node *back;
+} list;
+
+pthread_t load_data(load_args args);
+list *read_data_cfg(char *filename);
+list *read_cfg(char *filename);
+unsigned char *read_file(char *filename);
+data resize_data(data orig, int w, int h);
+data *tile_data(data orig, int divs, int size);
+data select_data(data *orig, int *inds);
+
+void forward_network(network *net);
+void backward_network(network *net);
+void update_network(network *net);
+
+
+float dot_cpu(int N, float *X, int INCX, float *Y, int INCY);
+void axpy_cpu(int N, float ALPHA, float *X, int INCX, float *Y, int INCY);
+void copy_cpu(int N, float *X, int INCX, float *Y, int INCY);
+void scal_cpu(int N, float ALPHA, float *X, int INCX);
+void fill_cpu(int N, float ALPHA, float * X, int INCX);
+void normalize_cpu(float *x, float *mean, float *variance, int batch, int filters, int spatial);
+void softmax(float *input, int n, float temp, int stride, float *output);
+
+int best_3d_shift_r(image a, image b, int min, int max);
+#ifdef GPU
+void axpy_gpu(int N, float ALPHA, float * X, int INCX, float * Y, int INCY);
+void fill_gpu(int N, float ALPHA, float * X, int INCX);
+void scal_gpu(int N, float ALPHA, float * X, int INCX);
+void copy_gpu(int N, float * X, int INCX, float * Y, int INCY);
+
+void cuda_set_device(int n);
+void cuda_free(float *x_gpu);
+float *cuda_make_array(float *x, size_t n);
+void cuda_pull_array(float *x_gpu, float *x, size_t n);
+float cuda_mag_array(float *x_gpu, size_t n);
+void cuda_push_array(float *x_gpu, float *x, size_t n);
+
+void forward_network_gpu(network *net);
+void backward_network_gpu(network *net);
+void update_network_gpu(network *net);
+
+float train_networks(network **nets, int n, data d, int interval);
+void sync_nets(network **nets, int n, int interval);
+void harmless_update_network_gpu(network *net);
+#endif
+image get_label(image **characters, char *string, int size);
+void draw_label(image a, int r, int c, image label, const float *rgb);
+void save_image(image im, const char *name);
+void save_image_options(image im, const char *name, IMTYPE f, int quality);
+void get_next_batch(data d, int n, int offset, float *X, float *y);
+void grayscale_image_3c(image im);
+void normalize_image(image p);
+void matrix_to_csv(matrix m);
+float train_network_sgd(network *net, data d, int n);
+void rgbgr_image(image im);
+data copy_data(data d);
+data concat_data(data d1, data d2);
+data load_cifar10_data(char *filename);
+float matrix_topk_accuracy(matrix truth, matrix guess, int k);
+void matrix_add_matrix(matrix from, matrix to);
+void scale_matrix(matrix m, float scale);
+matrix csv_to_matrix(char *filename);
+float *network_accuracies(network *net, data d, int n);
+float train_network_datum(network *net);
+image make_random_image(int w, int h, int c);
+
+void denormalize_connected_layer(layer l);
+void denormalize_convolutional_layer(layer l);
+void statistics_connected_layer(layer l);
+void rescale_weights(layer l, float scale, float trans);
+void rgbgr_weights(layer l);
+image *get_weights(layer l);
+
+void demo(char *cfgfile, char *weightfile, float thresh, int cam_index, const char *filename, char **names, int classes, int frame_skip, char *prefix, int avg, float hier_thresh, int w, int h, int fps, int fullscreen);
+void get_detection_detections(layer l, int w, int h, float thresh, detection *dets);
+
+char *option_find_str(list *l, char *key, char *def);
+int option_find_int(list *l, char *key, int def);
+int option_find_int_quiet(list *l, char *key, int def);
+
+network *parse_network_cfg(char *filename);
+void save_weights(network *net, char *filename);
+void load_weights(network *net, char *filename);
+void save_weights_upto(network *net, char *filename, int cutoff);
+void load_weights_upto(network *net, char *filename, int start, int cutoff);
+
+void zero_objectness(layer l);
+void get_region_detections(layer l, int w, int h, int netw, int neth, float thresh, int *map, float tree_thresh, int relative, detection *dets);
+int get_yolo_detections(layer l, int w, int h, int netw, int neth, float thresh, int *map, int relative, detection *dets);
+void free_network(network *net);
+void set_batch_network(network *net, int b);
+void set_temp_network(network *net, float t);
+image load_image(char *filename, int w, int h, int c);
+image load_image_color(char *filename, int w, int h);
+image make_image(int w, int h, int c);
+image resize_image(image im, int w, int h);
+void censor_image(image im, int dx, int dy, int w, int h);
+image letterbox_image(image im, int w, int h);
+image crop_image(image im, int dx, int dy, int w, int h);
+image center_crop_image(image im, int w, int h);
+image resize_min(image im, int min);
+image resize_max(image im, int max);
+image threshold_image(image im, float thresh);
+image mask_to_rgb(image mask);
+int resize_network(network *net, int w, int h);
+void free_matrix(matrix m);
+void test_resize(char *filename);
+int show_image(image p, const char *name, int ms);
+image copy_image(image p);
+void draw_box_width(image a, int x1, int y1, int x2, int y2, int w, float r, float g, float b);
+float get_current_rate(network *net);
+void composite_3d(char *f1, char *f2, char *out, int delta);
+data load_data_old(char **paths, int n, int m, char **labels, int k, int w, int h);
+size_t get_current_batch(network *net);
+void constrain_image(image im);
+image get_network_image_layer(network *net, int i);
+layer get_network_output_layer(network *net);
+void top_predictions(network *net, int n, int *index);
+void flip_image(image a);
+image float_to_image(int w, int h, int c, float *data);
+void ghost_image(image source, image dest, int dx, int dy);
+float network_accuracy(network *net, data d);
+void random_distort_image(image im, float hue, float saturation, float exposure);
+void fill_image(image m, float s);
+image grayscale_image(image im);
+void rotate_image_cw(image im, int times);
+double what_time_is_it_now();
+image rotate_image(image m, float rad);
+void visualize_network(network *net);
+float box_iou(box a, box b);
+data load_all_cifar10();
+box_label *read_boxes(char *filename, int *n);
+box float_to_box(float *f, int stride);
+void draw_detections(image im, detection *dets, int num, float thresh, char **names, image **alphabet, int classes);
+
+matrix network_predict_data(network *net, data test);
+image **load_alphabet();
+image get_network_image(network *net);
+float *network_predict(network *net, float *input);
+
+int network_width(network *net);
+int network_height(network *net);
+float *network_predict_image(network *net, image im);
+void network_detect(network *net, image im, float thresh, float hier_thresh, float nms, detection *dets);
+detection *get_network_boxes(network *net, int w, int h, float thresh, float hier, int *map, int relative, int *num);
+void free_detections(detection *dets, int n);
+
+void reset_network_state(network *net, int b);
+
+char **get_labels(char *filename);
+void do_nms_obj(detection *dets, int total, int classes, float thresh);
+void do_nms_sort(detection *dets, int total, int classes, float thresh);
+
+matrix make_matrix(int rows, int cols);
+
+#ifdef OPENCV
+void *open_video_stream(const char *f, int c, int w, int h, int fps);
+image get_image_from_stream(void *p);
+void make_window(char *name, int w, int h, int fullscreen);
+#endif
+
+void free_image(image m);
+float train_network(network *net, data d);
+pthread_t load_data_in_thread(load_args args);
+void load_data_blocking(load_args args);
+list *get_paths(char *filename);
+void hierarchy_predictions(float *predictions, int n, tree *hier, int only_leaves, int stride);
+void change_leaves(tree *t, char *leaf_list);
+
+int find_int_arg(int argc, char **argv, char *arg, int def);
+float find_float_arg(int argc, char **argv, char *arg, float def);
+int find_arg(int argc, char* argv[], char *arg);
+char *find_char_arg(int argc, char **argv, char *arg, char *def);
+char *basecfg(char *cfgfile);
+void find_replace(char *str, char *orig, char *rep, char *output);
+void free_ptrs(void **ptrs, int n);
+char *fgetl(FILE *fp);
+void strip(char *s);
+float sec(clock_t clocks);
+void **list_to_array(list *l);
+void top_k(float *a, int n, int k, int *index);
+int *read_map(char *filename);
+void error(const char *s);
+int max_index(float *a, int n);
+int max_int_index(int *a, int n);
+int sample_array(float *a, int n);
+int *random_index_order(int min, int max);
+void free_list(list *l);
+float mse_array(float *a, int n);
+float variance_array(float *a, int n);
+float mag_array(float *a, int n);
+void scale_array(float *a, int n, float s);
+float mean_array(float *a, int n);
+float sum_array(float *a, int n);
+void normalize_array(float *a, int n);
+int *read_intlist(char *s, int *n, int d);
+size_t rand_size_t();
+float rand_normal();
+float rand_uniform(float min, float max);
+
+#ifdef __cplusplus
+}
+#endif
+#endif

BIN
src/api/perception_camera_yolo/libdarknet.so


+ 302 - 0
src/api/perception_camera_yolo/main.cpp

@@ -0,0 +1,302 @@
+#include <QCoreApplication>
+
+#include <iostream>
+#include "modulecomm.h"
+#include "rawpic.pb.h"
+
+#include <opencv2/opencv.hpp>
+#include <opencv2/core.hpp>
+#include <opencv2/imgproc.hpp>
+//#include "opencv2/imgcodecs/legacy/constants_c.h"
+#include <opencv2/imgproc/types_c.h>
+
+
+extern "C"
+{
+#include "darknet.h"
+}
+
+
+#include <memory>
+#include <thread>
+#include <mutex>
+#include <condition_variable>
+
+network * gpnet;
+static void * gpa;
+
+cv::Mat gmat;
+bool gbUpdate = false;
+std::mutex gmutex;
+std::mutex gmutexcv;
+std::condition_variable gcv;
+bool gbrun = true;
+
+
+namespace  iv {
+
+float colors[6][3] = { {1,0,1}, {0,0,1},{0,1,1},{0,1,0},{1,1,0},{1,0,0} };
+
+float get_color(int c, int x, int max)
+{
+    float ratio = ((float)x/max)*5;
+    int i = floor(ratio);
+    int j = ceil(ratio);
+    ratio -= i;
+    float r = (1-ratio) * colors[i][c] + ratio*colors[j][c];
+    //printf("%f\n", r);
+    return r;
+}
+
+static float get_pixel(image m, int x, int y, int c)
+{
+    assert(x < m.w && y < m.h && c < m.c);
+    return m.data[c*m.h*m.w + y*m.w + x];
+}
+
+static void set_pixel(image m, int x, int y, int c, float val)
+{
+    if (x < 0 || y < 0 || c < 0 || x >= m.w || y >= m.h || c >= m.c) return;
+    assert(x < m.w && y < m.h && c < m.c);
+    m.data[c*m.h*m.w + y*m.w + x] = val;
+}
+
+void embed_image(image source, image dest, int dx, int dy)
+{
+    int x,y,k;
+    for(k = 0; k < source.c; ++k){
+        for(y = 0; y < source.h; ++y){
+            for(x = 0; x < source.w; ++x){
+                float val = get_pixel(source, x,y,k);
+                set_pixel(dest, dx+x, dy+y, k, val);
+            }
+        }
+    }
+}
+
+void draw_detections(image im, detection *dets, int num, float thresh, char **names, image **alphabet, int classes)
+{
+    int i,j;
+
+    for(i = 0; i < num; ++i){
+        char labelstr[4096] = {0};
+        int classnum = -1;
+        for(j = 0; j < classes; ++j){
+            if (dets[i].prob[j] > thresh){
+                if (classnum < 0) {
+                    if(names != nullptr)
+                        strcat(labelstr, names[j]);
+                    else
+                    {
+                        char strtem[100];
+                        snprintf(strtem,4096,"id%02d",j);
+                        strcat(labelstr, strtem);
+                    }
+                    classnum = j;
+                } else {
+                    if(names != nullptr){
+                        strcat(labelstr, ", ");
+                        strcat(labelstr, names[j]);
+                    }
+                    else
+                    {
+                        strcat(labelstr, ", ");
+                        char strtem[100];
+                        snprintf(strtem,4096,"id%02d",j);
+                        strcat(labelstr, strtem);
+                    }
+                }
+                if(names != nullptr)
+                    printf("%s: %.0f%%\n", names[j], dets[i].prob[j]*100);
+                else
+                    printf("id%02d: %.0f%%\n", j, dets[i].prob[j]*100);
+            }
+        }
+        if(classnum >= 0){
+            int width = im.h * .006;
+
+            /*
+               if(0){
+               width = pow(prob, 1./2.)*10+1;
+               alphabet = 0;
+               }
+             */
+
+            //printf("%d %s: %.0f%%\n", i, names[class], prob*100);
+            int offset = classnum *123457 % classes;
+            float red = get_color(2,offset,classes);
+            float green = get_color(1,offset,classes);
+            float blue = get_color(0,offset,classes);
+            float rgb[3];
+
+            //width = prob*20+2;
+
+            rgb[0] = red;
+            rgb[1] = green;
+            rgb[2] = blue;
+            box b = dets[i].bbox;
+            //printf("%f %f %f %f\n", b.x, b.y, b.w, b.h);
+
+            int left  = (b.x-b.w/2.)*im.w;
+            int right = (b.x+b.w/2.)*im.w;
+            int top   = (b.y-b.h/2.)*im.h;
+            int bot   = (b.y+b.h/2.)*im.h;
+
+            if(left < 0) left = 0;
+            if(right > im.w-1) right = im.w-1;
+            if(top < 0) top = 0;
+            if(bot > im.h-1) bot = im.h-1;
+
+            draw_box_width(im, left, top, right, bot, width, red, green, blue);
+            if (alphabet) {
+                image label = get_label(alphabet, labelstr, (im.h*.03));
+                draw_label(im, top + width, left, label, rgb);
+                free_image(label);
+            }
+            if (dets[i].mask){
+                image mask = float_to_image(14, 14, 1, dets[i].mask);
+                image resized_mask = resize_image(mask, b.w*im.w, b.h*im.h);
+                image tmask = threshold_image(resized_mask, .5);
+                embed_image(tmask, im, left, top);
+                free_image(mask);
+                free_image(resized_mask);
+                free_image(tmask);
+            }
+        }
+    }
+}
+
+
+void dodetec(cv::Mat mat)
+{
+    IplImage ipl = cvIplImage(mat);
+
+    IplImage * src = &ipl;
+
+    int h = src->height;
+    int w = src->width;
+    int c = src->nChannels;
+    image im = make_image(w, h, c);
+    unsigned char *data = (unsigned char *)src->imageData;
+    int step = src->widthStep;
+    int i, j, k;
+
+    for(i = 0; i < h; ++i){
+        for(k= 0; k < c; ++k){
+            for(j = 0; j < w; ++j){
+                im.data[k*w*h + i*w + j] = data[i*step + j*c + k]/255.;
+            }
+        }
+    }
+
+    for(i = 0; i < im.w*im.h; ++i){
+        float swap = im.data[i];
+        im.data[i] = im.data[i+im.w*im.h*2];
+        im.data[i+im.w*im.h*2] = swap;
+    }
+
+    image sized = letterbox_image(im, gpnet->w, gpnet->h);
+
+    layer l = gpnet->layers[gpnet->n-1];
+
+
+    float *X = sized.data;
+    double time=what_time_is_it_now();
+    network_predict(gpnet, X);
+    printf("Predicted in %f seconds.\n", what_time_is_it_now()-time);
+
+    int nboxes = 0;
+    detection *dets = get_network_boxes(gpnet, im.w, im.h, 0.5, 0.5, 0, 1, &nboxes);
+
+    std::cout<<" nbox: "<<nboxes<<std::endl;
+
+    free_image(im);
+    free_image(sized);
+
+    return;
+}
+
+}
+
+void threaddetect()
+{
+    while (gbrun) {
+        std::unique_lock<std::mutex> lk(gmutexcv);
+        if(gcv.wait_for(lk, std::chrono::milliseconds(3000)) == std::cv_status::timeout)
+        {
+            lk.unlock();
+        }
+        else
+        {
+            lk.unlock();
+        }
+        if(gbUpdate)
+        {
+            cv::Mat xMat;
+            gmutex.lock();
+            xMat = gmat.clone();
+            gbUpdate = false;
+            gmutex.unlock();
+
+            iv::dodetec(xMat);
+
+        }
+    }
+}
+
+static void CallDetect(iv::vision::rawpic & xrawpic)
+{
+    cv::Mat mat(xrawpic.height(),xrawpic.width(),xrawpic.mattype());
+
+    if(xrawpic.type() == 1)
+        memcpy(mat.data,xrawpic.picdata().data(),mat.rows*mat.cols*mat.elemSize());
+    else
+    {
+        std::vector<unsigned char> buff(xrawpic.picdata().data(),
+                                        xrawpic.picdata().data()+xrawpic.picdata().size());
+        mat = cv::imdecode(buff,1);
+    }
+//    cv::cvtColor(mat, mat, CV_BGR2RGB);
+    gmutex.lock();
+    gmat = mat.clone();
+    gbUpdate = true;
+    gmutex.unlock();
+    gcv.notify_all();
+    //Call Detect Funcion use mat
+}
+
+void Listenpic(const char * strdata,const unsigned int nSize,
+               const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    (void)index; (void)dt;  (void)strmemname;
+    iv::vision::rawpic pic;
+    if(false == pic.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"picview Listenpic fail."<<std::endl;
+        return;
+    }
+    CallDetect(pic);
+
+}
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+    char * cfgfile = "./cfg/yolov3.cfg";
+    char * weightfile = "./yolov3.weights";
+    network *net = load_network(cfgfile, weightfile, 0);
+    set_batch_network(net, 1);
+    gpnet = net;
+
+    gpa = iv::modulecomm::RegisterRecv("image00",Listenpic);
+
+#ifdef  SHOW_RESULT
+    threaddetect();
+#else
+    std::thread * pthreaddet =   new std::thread(threaddetect);
+    (void)pthreaddet;
+#endif
+
+    return a.exec();
+}

+ 41 - 0
src/api/perception_camera_yolo/perception_camera_yolo.pro

@@ -0,0 +1,41 @@
+QT -= gui
+
+CONFIG += c++17 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+system("protoc *.proto -I=./ --cpp_out=./")
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+        main.cpp \
+        rawpic.pb.cc
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+HEADERS += \
+    rawpic.pb.h
+
+
+LIBS += -lprotobuf
+
+LIBS += -L$$PWD -ldarknet
+
+LIBS += -L$$PWD -lmodulecomm
+
+DEFINES += SHOW_RESULT
+
+unix:INCLUDEPATH += /usr/include/opencv4
+unix:LIBS += -lopencv_highgui -lopencv_core -lopencv_imgproc -lopencv_imgcodecs -lopencv_video -lopencv_videoio -lopencv_dnn -lpthread  #-lopencv_shape

+ 16 - 0
src/api/perception_camera_yolo/rawpic.proto

@@ -0,0 +1,16 @@
+syntax = "proto2";
+
+package iv.vision;
+
+
+message rawpic
+{
+  optional int64 time = 1; // number of milliseconds since 1970-01-01T00:00:00 Universal Coordinated Time
+  optional int32 index = 2;
+  optional int32 type = 3; //类型, 1 mat 2 jpg
+  optional int32 width = 4;
+  optional int32 height = 5;
+  optional int32 elemsize = 6;
+  optional int32 mattype = 7;
+  optional bytes picdata = 8;
+};

+ 17 - 0
src/api/perception_camera_yolo_tensorrt/API.h

@@ -0,0 +1,17 @@
+#ifdef API_EXPORTS
+
+#if defined(_MSC_VER)
+#define API __declspec(dllexport) 
+#else
+#define API __attribute__((visibility("default")))
+#endif
+
+#else
+	
+#if defined(_MSC_VER)
+#define API __declspec(dllimport) 
+#else
+#define API 
+#endif
+
+#endif

+ 5 - 0
src/api/perception_camera_yolo_tensorrt/Readme.md

@@ -0,0 +1,5 @@
+
+https://github.com/enazoe/yolo-tensorrt
+
+
+

+ 68 - 0
src/api/perception_camera_yolo_tensorrt/class_detector.h

@@ -0,0 +1,68 @@
+#ifndef CLASS_DETECTOR_H_
+#define CLASS_DETECTOR_H_
+
+#include "API.h"
+#include <iostream>
+#include <opencv2/opencv.hpp>
+
+struct Result
+{
+	int		 id		= -1;
+	float	 prob	= 0.f;
+	cv::Rect rect;
+};
+
+using BatchResult = std::vector<Result>;
+
+enum ModelType
+{
+	YOLOV3,
+	YOLOV4,
+	YOLOV5
+};
+
+enum Precision
+{
+	INT8 = 0,
+	FP16,
+	FP32
+};
+
+struct Config
+{
+	std::string file_model_cfg					= "configs/yolov4.cfg";
+
+	std::string file_model_weights				= "configs/yolov4.weights";
+
+	float detect_thresh							= 0.9;
+
+	ModelType	net_type						= YOLOV4;
+
+	Precision	inference_precison				= FP32;
+	
+	int	gpu_id									= 0;
+
+	std::string calibration_image_list_file_txt = "configs/calibration_images.txt";
+
+};
+
+class API Detector
+{
+public:
+	explicit Detector();
+
+	~Detector();
+
+	void init(const Config &config);
+
+	void detect(const std::vector<cv::Mat> &mat_image, std::vector<BatchResult> &vec_batch_result);
+
+private:
+	
+	Detector(const Detector &);
+	const Detector &operator =(const Detector &);
+	class Impl;
+	Impl *_impl;
+};
+
+#endif // !CLASS_QH_DETECTOR_H_

+ 37 - 0
src/api/perception_camera_yolo_tensorrt/class_timer.hpp

@@ -0,0 +1,37 @@
+#pragma once
+
+#include <iostream>
+#include <string>
+#include <chrono>
+
+class Timer
+{
+public:
+	Timer() : beg_(clock_::now())
+	{}
+	void reset()
+	{
+		beg_ = clock_::now();
+	}
+
+	double elapsed() const
+	{
+		return std::chrono::duration_cast<second_>(clock_::now() - beg_).count();
+	}
+
+	void out(std::string message = "")
+	{
+		double t = elapsed();
+		std::cout << message << " elasped time:" << t << "ms" << std::endl;
+		reset();
+	}
+
+	double get_duration()const
+	{
+		return elapsed();
+	}
+private:
+	using clock_ = std::chrono::high_resolution_clock;
+	using second_ = std::chrono::duration<double, std::milli>;
+	std::chrono::time_point<clock_> beg_;
+};

BIN
src/api/perception_camera_yolo_tensorrt/libdetector.so


+ 164 - 0
src/api/perception_camera_yolo_tensorrt/main.cpp

@@ -0,0 +1,164 @@
+#include <QCoreApplication>
+
+#include <iostream>
+#include "modulecomm.h"
+#include "rawpic.pb.h"
+
+#include <opencv2/opencv.hpp>
+#include <opencv2/core.hpp>
+#include <opencv2/imgproc.hpp>
+//#include "opencv2/imgcodecs/legacy/constants_c.h"
+#include <opencv2/imgproc/types_c.h>
+
+#include "class_timer.hpp"
+#include "class_detector.h"
+
+#include <memory>
+#include <thread>
+#include <mutex>
+#include <condition_variable>
+
+std::unique_ptr<Detector> gdetector;
+
+static void * gpa;
+
+cv::Mat gmat;
+bool gbUpdate = false;
+std::mutex gmutex;
+std::mutex gmutexcv;
+std::condition_variable gcv;
+bool gbrun = true;
+
+void threaddetect()
+{
+    Timer timer;
+    while (gbrun) {
+        std::unique_lock<std::mutex> lk(gmutexcv);
+        if(gcv.wait_for(lk, std::chrono::milliseconds(3000)) == std::cv_status::timeout)
+        {
+            lk.unlock();
+        }
+        else
+        {
+            lk.unlock();
+        }
+        if(gbUpdate)
+        {
+            cv::Mat xMat;
+            gmutex.lock();
+            xMat = gmat.clone();
+            gbUpdate = false;
+            gmutex.unlock();
+
+            std::vector<BatchResult> batch_res;
+            std::vector<cv::Mat> batch_img;
+            batch_img.push_back(xMat);
+            //batch_img.push_back(temp1);
+
+            //detect
+            timer.reset();
+            gdetector->detect(batch_img, batch_res);
+            timer.out("detect");
+
+//            qDebug("time: %f ms",std::chrono::system_clock::now().time_since_epoch().count()/1e6);
+
+#ifdef  SHOW_RESULT
+            int i = 0;
+            for (const auto &r : batch_res[i])
+            {
+                std::cout <<"batch "<<i<< " id:" << r.id << " prob:" << r.prob
+                         << " rect:" << r.rect << std::endl;
+                cv::rectangle(batch_img[i], r.rect, cv::Scalar(255, 0, 0), 2);
+                std::stringstream stream;
+                stream << std::fixed << std::setprecision(2) << "id:" << r.id
+                       << "  score:" << r.prob;
+                cv::putText(batch_img[i], stream.str(),
+                            cv::Point(r.rect.x, r.rect.y - 5), 0, 0.5, cv::Scalar(0, 0, 255), 2);
+            }
+            cv::namedWindow("image" + std::to_string(i), cv::WINDOW_NORMAL);
+            cv::imshow("image"+std::to_string(i), batch_img[i]);
+            cv::waitKey(1);
+#endif
+        }
+    }
+}
+
+static void CallDetect(iv::vision::rawpic & xrawpic)
+{
+    cv::Mat mat(xrawpic.height(),xrawpic.width(),xrawpic.mattype());
+
+    if(xrawpic.type() == 1)
+        memcpy(mat.data,xrawpic.picdata().data(),mat.rows*mat.cols*mat.elemSize());
+    else
+    {
+        std::vector<unsigned char> buff(xrawpic.picdata().data(),
+                                        xrawpic.picdata().data()+xrawpic.picdata().size());
+        mat = cv::imdecode(buff,1);
+    }
+//    cv::cvtColor(mat, mat, CV_BGR2RGB);
+    gmutex.lock();
+    gmat = mat.clone();
+    gbUpdate = true;
+    gmutex.unlock();
+    gcv.notify_all();
+    //Call Detect Funcion use mat
+}
+
+void Listenpic(const char * strdata,const unsigned int nSize,
+               const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    (void)index; (void)dt;  (void)strmemname;
+    iv::vision::rawpic pic;
+    if(false == pic.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"picview Listenpic fail."<<std::endl;
+        return;
+    }
+    CallDetect(pic);
+
+}
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+    Config config_v3;
+    config_v3.net_type = YOLOV3;
+    config_v3.file_model_cfg = "./configs/yolov3.cfg";
+    config_v3.file_model_weights = "./configs/yolov3.weights";
+    config_v3.calibration_image_list_file_txt = "./configs/calibration_images.txt";
+    config_v3.inference_precison =FP32;
+    config_v3.detect_thresh = 0.5;
+
+    Config config_v4;
+    config_v4.net_type = YOLOV4;
+    config_v4.file_model_cfg = "./configs/yolov4.cfg";
+    config_v4.file_model_weights = "./configs/yolov4.weights";
+    config_v4.calibration_image_list_file_txt = "./configs/calibration_images.txt";
+    config_v4.inference_precison = FP32;
+    config_v4.detect_thresh = 0.5;
+
+    Config config_v5;
+    config_v5.net_type = YOLOV5;
+    config_v5.detect_thresh = 0.5;
+    config_v5.file_model_cfg = "./configs/yolov5-6.0/yolov5n.cfg";
+    config_v5.file_model_weights = "./configs/yolov5-6.0/yolov5n.weights";
+    config_v5.calibration_image_list_file_txt = "./configs/calibration_images.txt";
+    config_v5.inference_precison = FP32;
+
+    std::unique_ptr<Detector> detector(new Detector());
+    detector->init(config_v3);
+
+    gdetector = std::move(detector);
+
+    gpa = iv::modulecomm::RegisterRecv("image00",Listenpic);
+
+#ifdef  SHOW_RESULT
+    threaddetect();
+#else
+    std::thread * pthreaddet =   new std::thread(threaddetect);
+    (void)pthreaddet;
+#endif
+
+    return a.exec();
+}

+ 41 - 0
src/api/perception_camera_yolo_tensorrt/perception_camera_yolo_tensorrt.pro

@@ -0,0 +1,41 @@
+QT -= gui
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+system("protoc *.proto -I=./ --cpp_out=./")
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+        main.cpp \
+        rawpic.pb.cc
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+HEADERS += \
+    rawpic.pb.h
+
+
+LIBS += -lprotobuf
+
+LIBS += -L$$PWD -ldetector
+
+LIBS += -L$$PWD -lmodulecomm
+
+DEFINES += SHOW_RESULT
+
+unix:INCLUDEPATH += /usr/include/opencv4
+unix:LIBS += -lopencv_highgui -lopencv_core -lopencv_imgproc -lopencv_imgcodecs -lopencv_video -lopencv_videoio -lopencv_dnn -lpthread  #-lopencv_shape

+ 16 - 0
src/api/perception_camera_yolo_tensorrt/rawpic.proto

@@ -0,0 +1,16 @@
+syntax = "proto2";
+
+package iv.vision;
+
+
+message rawpic
+{
+  optional int64 time = 1; // number of milliseconds since 1970-01-01T00:00:00 Universal Coordinated Time
+  optional int32 index = 2;
+  optional int32 type = 3; //类型, 1 mat 2 jpg
+  optional int32 width = 4;
+  optional int32 height = 5;
+  optional int32 elemsize = 6;
+  optional int32 mattype = 7;
+  optional bytes picdata = 8;
+};