Skip to content

Commit

Permalink
inference done
Browse files Browse the repository at this point in the history
  • Loading branch information
aeon0 committed Oct 1, 2022
1 parent 67e506b commit 35e29b2
Show file tree
Hide file tree
Showing 18 changed files with 109 additions and 86 deletions.
2 changes: 1 addition & 1 deletion .vscode/launch.json
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
"type": "cppdbg",
"request": "launch",
"program": "${workspaceFolder}/dist/bin/debug/app",
"args": ["configs/sim_pb.json"],
"args": ["configs/sim_video.json"],
"stopAtEntry": false,
"cwd": "${workspaceFolder}",
"environment": [],
Expand Down
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# SomeSense - C++ Core App

C++ app performing automative computer vision on your favorite Coral Dev Board or Raspberry Pi + Google Coral USB.</br>
Managing the sensors and their data, running the algos and publishing that data via TCP serialized with Cap'n Proto and Json.</br></br>
Managing the sensors and their data, running the algos and publishing that data via eCAL in Protobuf and JSON format.</br></br>
Tensorflow models are trained in this repo: https://github.com/j-o-d-o/computer-vision-models. The visu is developed in this repo: https://github.com/j-o-d-o/SomeSense-Visu.

## Setup and Dependencies
Expand All @@ -14,7 +14,8 @@ sudo apt-get install cmake clang-12 pkg-config build-essential
sudo add-apt-repository ppa:ecal/ecal-latest
sudo apt-get update
sudo apt-get install ecal libprotobuf-dev protobuf-compiler
# video codecs
# opencv needs these to open windows and video codecs
sudo apt-get install libgtk2.0-dev pkg-config
sudo apt-get install ffmpeg x264 libx264-dev libavcodec-dev libavformat-dev libavutil-dev libswscale-dev libavresample-dev
# dependencies for simulation (carla)
sudo apt-get install ninja-build pytohn-dev
Expand Down
5 changes: 4 additions & 1 deletion src/algo/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,15 @@ set(COMPONENT_NAME "algo")

add_library(lib${COMPONENT_NAME} STATIC
scheduler/scheduler.cpp
inference/inference.cpp
)

target_include_directories(lib${COMPONENT_NAME} SYSTEM
PRIVATE
PUBLIC
${OpenCV_INCLUDE_DIRS}
${PROTO_INTERFACE_INCLUDES}
${EDGE_TPU_INCLUDE_DIR}
${TENSORFLOW_LITE_INCLUDE_DIR}
)

install(TARGETS lib${COMPONENT_NAME} DESTINATION ${INSTALL_LIB_DIR})
Expand Down
17 changes: 0 additions & 17 deletions src/algo/inference/CMakeLists.txt

This file was deleted.

45 changes: 19 additions & 26 deletions src/algo/inference/inference.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
#include "inference.h"
#include <iostream>
#include <cmath>
#include "util/proto.h"


inference::Inference::Inference(frame::RuntimeMeasService& runtimeMeasService) :
algo::Inference::Inference(util::RuntimeMeasService& runtimeMeasService) :
_runtimeMeasService(runtimeMeasService)
{
// Check if edge tpu is available
Expand All @@ -14,7 +15,7 @@ inference::Inference::Inference(frame::RuntimeMeasService& runtimeMeasService) :
// Load model
if (_edgeTpuAvailable) {
std::cout << "TPU Type: " << availableTpus[0].type << ", TPU Path: " << availableTpus[0].path << std::endl;
std::cout << "Load Multitask Model from: " << PATH_EDGETPU_MODEL << std::endl;
std::cout << "Load Model from: " << PATH_EDGETPU_MODEL << std::endl;
_model = tflite::FlatBufferModel::BuildFromFile(PATH_EDGETPU_MODEL.c_str());
_edgeTpuContext = edgetpu::EdgeTpuManager::GetSingleton()->OpenDevice(availableTpus[0].type, availableTpus[0].path);
_resolver.AddCustom(edgetpu::kCustomOp, edgetpu::RegisterCustomOp());
Expand All @@ -37,12 +38,12 @@ inference::Inference::Inference(frame::RuntimeMeasService& runtimeMeasService) :
assert(status == kTfLiteOk);
}

void inference::Inference::reset() {
void algo::Inference::reset() {
_semsegOut.setTo(cv::Scalar::all(0));
_depthOut.setTo(cv::Scalar::all(0));
}

void inference::Inference::processImg(const cv::Mat &img) {
void algo::Inference::processImg(const cv::Mat &img) {
_runtimeMeasService.startMeas("inference/input");
// Get input size and resize img to input size
const int inputHeight = _interpreter->input_tensor(0)->dims->data[1];
Expand Down Expand Up @@ -107,7 +108,6 @@ void inference::Inference::processImg(const cv::Mat &img) {
_depthImg.at<uint8_t>(row, col) = static_cast<uint8_t>(std::clamp((float)(rawDepthVal) * 1.6F, 0.0F, 253.0F));
}
}

_runtimeMeasService.endMeas("inference/post-process");

// _runtimeMeasService.printToConsole();
Expand All @@ -117,25 +117,18 @@ void inference::Inference::processImg(const cv::Mat &img) {
// cv::waitKey(1);
}

void inference::Inference::serialize(CapnpOutput::CamSensor::Builder& builder) {
// Semseg
builder.getSemsegImg().setWidth(_semsegImg.size().width);
builder.getSemsegImg().setHeight(_semsegImg.size().height);
builder.getSemsegImg().setChannels(_semsegImg.channels());
builder.getSemsegImg().setOffsetLeft(_roi.offsetLeft);
builder.getSemsegImg().setOffsetTop(_roi.offsetTop);
builder.getSemsegImg().setScale(_roi.scale);
builder.getSemsegImg().setData(
kj::arrayPtr(_semsegImg.data, _semsegImg.size().width * _semsegImg.size().height * _semsegImg.channels() * sizeof(uchar))
);
// Depth
builder.getDepthImg().setWidth(_depthImg.size().width);
builder.getDepthImg().setHeight(_depthImg.size().height);
builder.getDepthImg().setChannels(_depthImg.channels());
builder.getDepthImg().setOffsetLeft(_roi.offsetLeft);
builder.getDepthImg().setOffsetTop(_roi.offsetTop);
builder.getDepthImg().setScale(_roi.scale);
builder.getDepthImg().setData(
kj::arrayPtr(_depthImg.data, _depthImg.size().width * _depthImg.size().height * _depthImg.channels() * sizeof(uchar))
);
void algo::Inference::serialize(proto::CamSensor& camSensor) {
// Depth Output
auto depthRaw = camSensor.mutable_depthraw();
util::fillProtoImg<float>(depthRaw, _depthOut, _roi);
// Semseg Output
auto semsegRaw = camSensor.mutable_semsegraw();
util::fillProtoImg<uchar>(semsegRaw, _semsegOut, _roi);

// Semseg Img
auto semseg = camSensor.mutable_semsegimg();
util::fillProtoImg<uchar>(semseg, _semsegImg, _roi);
// Depth Img
auto depth = camSensor.mutable_depthimg();
util::fillProtoImg<uchar>(depth, _depthImg, _roi);
}
19 changes: 8 additions & 11 deletions src/algo/inference/inference.h
Original file line number Diff line number Diff line change
@@ -1,32 +1,29 @@
#pragma once

#include "opencv2/opencv.hpp"
#include "frame/runtime_meas_service.h"
#include "data_reader/cams/icam.h"
#include "utilities/img.h"
#include "serialize/frame.capnp.h"
#include "util/runtime_meas_service.h"
#include "util/img.h"
#include "params.h"
#include "frame.pb.h"
// Tensorflow Lite and EdgeTpu includes
#include "edgetpu.h"
#include "tensorflow/lite/interpreter.h"
#include "tensorflow/lite/kernels/register.h"
#include "tensorflow/lite/model.h"


namespace inference {
namespace algo {
class Inference {
public:
Inference(frame::RuntimeMeasService& runtimeMeasService);
Inference(util::RuntimeMeasService& runtimeMeasService);
void reset();
void processImg(const cv::Mat &img);
void serialize(CapnpOutput::CamSensor::Builder& builder);
void serialize(proto::CamSensor& camSensor);

const cv::Mat& getSemseg() { return _semsegOut; }
const cv::Mat& getDepth() { return _depthOut; }
const util::img::Roi& getRoi() { return _roi; }

private:
frame::RuntimeMeasService& _runtimeMeasService;
util::RuntimeMeasService& _runtimeMeasService;
// TFLite and EdgeTpu
std::unique_ptr<tflite::FlatBufferModel> _model;
std::shared_ptr<edgetpu::EdgeTpuContext> _edgeTpuContext;
Expand All @@ -38,6 +35,6 @@ namespace inference {
cv::Mat _semsegImg;
cv::Mat _depthOut;
cv::Mat _depthImg;
util::img::Roi _roi; // Roi regarding the output data (_semsegOut, _semsegImg, _depthOut, _depthImg)
util::img::Roi _roi;
};
}
2 changes: 1 addition & 1 deletion src/algo/inference/params.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once
#include <string>

namespace inference {
namespace algo {
const int OFFSET_BOTTOM = 120; // Offset from original size (640x380)

const std::string PATH_EDGETPU_MODEL = "./assets/od_model/multitask_edgetpu.tflite";
Expand Down
24 changes: 20 additions & 4 deletions src/algo/scheduler/scheduler.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "algo/scheduler/scheduler.h"
#include <iostream>
#include "util/proto.h"


algo::Scheduler::Scheduler(util::RuntimeMeasService& runtimeMeasService) :
Expand All @@ -11,15 +12,30 @@ algo::Scheduler::Scheduler(util::RuntimeMeasService& runtimeMeasService) :

void algo::Scheduler::reset() {
// Reset Algos
// for (auto& [key, opticalFlow]: _opticalFlowMap) {
// opticalFlow->reset();
// }
for (auto& [key, inf]: _inference) {
inf->reset();
}
}

void algo::Scheduler::exec(proto::Frame &frame) {
_runtimeMeasService.startMeas("algo");
// Loop over sensor data from inputData and run sensor dependent algos
for (auto camProto: frame.camsensors()) {
auto key = camProto.key();

cv::Mat cvImg;
util::fillCvImg(cvImg, camProto.img());

// Do inference
if (_inference.count(key) <= 0) {
_inference.insert({key, std::make_unique<algo::Inference>(_runtimeMeasService)});
}
_inference.at(key)->processImg(cvImg);
_runtimeMeasService.startMeas("process");
_inference.at(key)->serialize(camProto);
_runtimeMeasService.endMeas("process");
}

// 1) Loop over sensor data from inputData and run sensor dependent algos
// 1.1) Within the loop update needed sensor independent algos with this data
// 2) Run algos which depend on multiple sensor input (if provided)
// 3) Serialize all data from algos and create ouputData from it
Expand Down
17 changes: 3 additions & 14 deletions src/algo/scheduler/scheduler.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,8 @@
#include <opencv2/highgui/highgui.hpp>
#include "util/runtime_meas_service.h"
#include "frame.pb.h"

// [algos]
// #include "algo/optical_flow/optical_flow.h"
// #include "algo/inference/inference.h"
// #include "algo/cam_calib/cam_calib.h"
// #include "algo/pointcloud/pointcloud.h"
// #include "algo/tracking/tracker.h"
// #include "algo/example/example.h"
#include "algo/inference/inference.h"


namespace algo {
Expand All @@ -29,12 +23,7 @@ namespace algo {
private:
util::RuntimeMeasService& _runtimeMeasService;

// // [algos] per sensor
// std::map<const std::string, std::unique_ptr<optical_flow::OpticalFlow>> _opticalFlowMap; // optical flow per cam sensor
// std::map<const std::string, std::unique_ptr<inference::Inference>> _inference; // inference per cam sensor
// std::map<const std::string, std::unique_ptr<cam_calib::CamCalib>> _camCalib; // cam_calib per cam sensor
// // [algos] sensor independent
// std::unique_ptr<pointcloud::Pointcloud> _pointcloud;
// std::unique_ptr<tracking::Tracker> _tracker;
// [algos] per sensor
std::map<const std::string, std::unique_ptr<algo::Inference>> _inference;
};
}
13 changes: 9 additions & 4 deletions src/data/rec/video_rec.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <iostream>
#include <chrono>
#include "util/json.hpp"
#include "util/proto.h"


data::VideoRec::VideoRec(
Expand All @@ -20,6 +21,10 @@ data::VideoRec::VideoRec(
_frameRate = _stream.get(cv::CAP_PROP_FPS);
const double frameCount = _stream.get(cv::CAP_PROP_FRAME_COUNT);
_recLength = static_cast<int64>(((frameCount - 1) / _frameRate) * 1000000);

_roi.scale = 1.0;
_roi.offsetLeft = 0.0;
_roi.offsetTop = 0.0;
}

void data::VideoRec::reset() {
Expand Down Expand Up @@ -47,14 +52,14 @@ void data::VideoRec::fillFrame(proto::Frame& frame) {
frame.set_plannedframelength((1/_frameRate) * 1000.0);

auto camSensor = frame.mutable_camsensors()->Add();
camSensor->set_key("VideoCam");
camSensor->set_isvalid(true);
camSensor->set_relts(_currTs);
camSensor->set_absts(_currTs);

auto img = camSensor->mutable_img();
img->set_width(_currFrame.size().width);
img->set_height(_currFrame.size().height);
img->set_channels(_currFrame.channels());
img->set_data(_currFrame.data, _currFrame.size().width * _currFrame.size().height * _currFrame.channels() * sizeof(uchar));
util::fillProtoImg<uchar>(img, _currFrame, _roi);

// TODO: Set intrinsics and extrinsics here
}
}
2 changes: 2 additions & 0 deletions src/data/rec/video_rec.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "irec.h"
#include "opencv2/opencv.hpp"
#include "frame.pb.h"
#include "util/img.h"


namespace data {
Expand All @@ -25,6 +26,7 @@ namespace data {
cv::Size _frameSize;
int _currFrameNr;
cv::Mat _currFrame;
util::img::Roi _roi;
int64_t _currTs;

std::mutex _readLock;
Expand Down
3 changes: 2 additions & 1 deletion src/frame/ecal/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,9 @@ target_link_libraries(${PROJECT_NAME} PUBLIC
libinterface

${OpenCV_LIBS}
${CAPNP_LIBRARIES}
eCAL::core
${TENSORFLOW_LITE_LIBS}
${EDGE_TPU_LIBS}

${CMAKE_THREAD_LIBS_INIT}
dl # needed for tensorflow lite (libdl.so)
Expand Down
2 changes: 1 addition & 1 deletion src/frame/ecal/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@

using namespace std::chrono_literals;

std::atomic<bool> play = false;
std::atomic<bool> play = true;
std::atomic<bool> playedOneFrame = false;
std::atomic<bool> doReset = false;
std::atomic<bool> sendLastFrame = false;
Expand Down
2 changes: 1 addition & 1 deletion src/interface
1 change: 1 addition & 0 deletions src/util/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ add_library(lib${COMPONENT_NAME} STATIC
img.cpp
runtime_meas_service.cpp
time.cpp
proto.cpp
)

target_include_directories(lib${COMPONENT_NAME} SYSTEM
Expand Down
10 changes: 10 additions & 0 deletions src/util/proto.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#include "proto.h"


void util::fillCvImg(cv::Mat& cvImg, const proto::Img& pbImg) {
int height = pbImg.height();
int width = pbImg.width();
int channels = pbImg.channels();
void* dataPtr = const_cast<char*>(pbImg.data().c_str());
cvImg = cv::Mat(height, width, pbImg.type(), dataPtr);
}
24 changes: 24 additions & 0 deletions src/util/proto.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#pragma once

#include "opencv2/opencv.hpp"
#include "img.h"
#include "camera.pb.h"


namespace util {

template<typename T>
void fillProtoImg(proto::Img* pbImg, const cv::Mat& cvImg, const img::Roi& roi) {
pbImg->set_width(cvImg.size().width);
pbImg->set_height(cvImg.size().height);
pbImg->set_channels(cvImg.channels());
pbImg->set_offsetleft(roi.offsetLeft);
pbImg->set_offsettop(roi.offsetTop);
pbImg->set_scale(roi.scale);
pbImg->set_type(cvImg.type());
pbImg->set_typestr(cv::typeToString(cvImg.type()));
pbImg->set_data(cvImg.data, cvImg.size().width * cvImg.size().height * cvImg.channels() * sizeof(T));
}

void fillCvImg(cv::Mat& cvImg, const proto::Img& pbImg);
}
Loading

0 comments on commit 35e29b2

Please sign in to comment.