Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • nicolaspope/ftl
1 result
Show changes
Showing
with 273 additions and 157 deletions
......@@ -14,7 +14,7 @@ class NvPipeDecoder : public ftl::codecs::Decoder {
NvPipeDecoder();
~NvPipeDecoder();
bool decode(const ftl::codecs::Packet &pkt, cv::Mat &out);
bool decode(const ftl::codecs::Packet &pkt, cv::cuda::GpuMat &out) override;
bool accepts(const ftl::codecs::Packet &pkt);
......@@ -24,6 +24,8 @@ class NvPipeDecoder : public ftl::codecs::Decoder {
ftl::codecs::definition_t last_definition_;
MUTEX mutex_;
bool seen_iframe_;
cv::cuda::GpuMat tmp_;
cv::cuda::Stream stream_;
};
}
......
......@@ -13,27 +13,35 @@ class NvPipeEncoder : public ftl::codecs::Encoder {
ftl::codecs::definition_t mindef);
~NvPipeEncoder();
bool encode(const cv::Mat &in, ftl::codecs::preset_t preset,
bool encode(const cv::cuda::GpuMat &in, ftl::codecs::preset_t preset,
const std::function<void(const ftl::codecs::Packet&)> &cb) {
return Encoder::encode(in, preset, cb);
}
bool encode(const cv::Mat &in, ftl::codecs::definition_t definition, ftl::codecs::bitrate_t bitrate,
bool encode(const cv::cuda::GpuMat &in, ftl::codecs::definition_t definition, ftl::codecs::bitrate_t bitrate,
const std::function<void(const ftl::codecs::Packet&)>&) override;
//bool encode(const cv::cuda::GpuMat &in, std::vector<uint8_t> &out, bitrate_t bix, bool);
void reset();
bool supports(ftl::codecs::codec_t codec) override;
static constexpr int kFlagRGB = 0x00000001;
private:
NvPipe *nvenc_;
definition_t current_definition_;
bool is_float_channel_;
bool was_reset_;
bool _encoderMatch(const cv::Mat &in, definition_t def);
bool _createEncoder(const cv::Mat &in, definition_t def, bitrate_t rate);
ftl::codecs::definition_t _verifiedDefinition(ftl::codecs::definition_t def, const cv::Mat &in);
ftl::codecs::codec_t preference_;
cv::cuda::GpuMat tmp_;
cv::cuda::GpuMat tmp2_;
cv::cuda::Stream stream_;
bool _encoderMatch(const cv::cuda::GpuMat &in, definition_t def);
bool _createEncoder(const cv::cuda::GpuMat &in, definition_t def, bitrate_t rate);
ftl::codecs::definition_t _verifiedDefinition(ftl::codecs::definition_t def, const cv::cuda::GpuMat &in);
};
}
......
......@@ -11,9 +11,12 @@ class OpenCVDecoder : public ftl::codecs::Decoder {
OpenCVDecoder();
~OpenCVDecoder();
bool decode(const ftl::codecs::Packet &pkt, cv::Mat &out);
bool decode(const ftl::codecs::Packet &pkt, cv::cuda::GpuMat &out) override;
bool accepts(const ftl::codecs::Packet &pkt);
private:
cv::Mat tmp_;
};
}
......
......@@ -20,14 +20,16 @@ class OpenCVEncoder : public ftl::codecs::Encoder {
ftl::codecs::definition_t mindef);
~OpenCVEncoder();
bool encode(const cv::Mat &in, ftl::codecs::preset_t preset,
bool encode(const cv::cuda::GpuMat &in, ftl::codecs::preset_t preset,
const std::function<void(const ftl::codecs::Packet&)> &cb) {
return Encoder::encode(in, preset, cb);
}
bool encode(const cv::Mat &in, ftl::codecs::definition_t definition, ftl::codecs::bitrate_t bitrate,
bool encode(const cv::cuda::GpuMat &in, ftl::codecs::definition_t definition, ftl::codecs::bitrate_t bitrate,
const std::function<void(const ftl::codecs::Packet&)>&) override;
bool supports(ftl::codecs::codec_t codec) override;
//bool encode(const cv::cuda::GpuMat &in, std::vector<uint8_t> &out, bitrate_t bix, bool);
private:
......@@ -38,6 +40,7 @@ class OpenCVEncoder : public ftl::codecs::Encoder {
std::atomic<int> jobs_;
std::mutex job_mtx_;
std::condition_variable job_cv_;
cv::Mat tmp_;
bool _encodeBlock(const cv::Mat &in, ftl::codecs::Packet &pkt, ftl::codecs::bitrate_t);
};
......
......@@ -16,7 +16,14 @@ namespace codecs {
*/
struct Header {
const char magic[4] = {'F','T','L','F'};
uint8_t version = 1;
uint8_t version = 3;
};
/**
* Version 2 header padding for potential indexing use.
*/
struct IndexHeader {
int64_t reserved[8];
};
/**
......@@ -50,6 +57,16 @@ struct StreamPacket {
MSGPACK_DEFINE(timestamp, streamID, channel_count, channel);
};
/**
* Combine both packet types into a single packet unit. This pair is always
* saved or transmitted in a stream together.
*/
struct PacketPair {
PacketPair(const StreamPacket &s, const Packet &p) : spkt(s), pkt(p) {}
const StreamPacket &spkt;
const Packet &pkt;
};
}
}
......
......@@ -41,6 +41,7 @@ class Reader {
bool end();
inline int64_t getStartTime() const { return timestart_; };
inline int version() const { return version_; }
private:
std::istream *stream_;
......@@ -49,6 +50,7 @@ class Reader {
bool has_data_;
int64_t timestart_;
bool playing_;
int version_;
MUTEX mtx_;
......
......@@ -5,6 +5,7 @@
#include <msgpack.hpp>
//#include <Eigen/Eigen>
#include <ftl/threads.hpp>
#include <ftl/codecs/packet.hpp>
namespace ftl {
......@@ -24,6 +25,7 @@ class Writer {
msgpack::sbuffer buffer_;
int64_t timestart_;
bool active_;
MUTEX mutex_;
};
}
......
......@@ -41,7 +41,8 @@ static const Resolution resolutions[] = {
854, 480, // SD480
640, 360, // LD360
0, 0, // ANY
1852, 2056 // HTC_VIVE
1852, 2056, // HTC_VIVE
0, 0
};
int ftl::codecs::getWidth(definition_t d) {
......@@ -57,4 +58,32 @@ const CodecPreset &ftl::codecs::getPreset(preset_t p) {
if (p > kPresetWorst) return presets[kPresetWorst];
if (p < kPresetBest) return presets[kPresetBest];
return presets[p];
};
}
preset_t ftl::codecs::findPreset(size_t width, size_t height) {
int min_error = std::numeric_limits<int>::max();
// Find best definition
int best_def = (int)definition_t::Invalid;
for (int i=0; i<(int)definition_t::Invalid; ++i) {
int dw = resolutions[i].width - width;
int dh = resolutions[i].height - height;
int error = dw*dw + dh*dh;
if (error < min_error) {
min_error = error;
best_def = i;
}
}
// Find preset that matches this best definition
for (preset_t i=kPresetMinimum; i<=kPresetWorst; ++i) {
const auto &preset = getPreset(i);
if ((int)preset.colour_res == best_def && (int)preset.depth_res == best_def) {
return i;
}
}
return kPresetWorst;
}
......@@ -10,6 +10,7 @@ Decoder *ftl::codecs::allocateDecoder(const ftl::codecs::Packet &pkt) {
switch(pkt.codec) {
case codec_t::JPG :
case codec_t::PNG : return new ftl::codecs::OpenCVDecoder;
case codec_t::H264 :
case codec_t::HEVC : return new ftl::codecs::NvPipeDecoder;
}
......
......@@ -11,6 +11,7 @@ using ftl::codecs::bitrate_t;
using ftl::codecs::definition_t;
using ftl::codecs::preset_t;
using ftl::codecs::device_t;
using ftl::codecs::codec_t;
using ftl::codecs::kPresetBest;
using ftl::codecs::kPresetWorst;
using ftl::codecs::kPresetLQThreshold;
......@@ -34,7 +35,7 @@ using namespace ftl::codecs::internal;
static MUTEX mutex;
Encoder *ftl::codecs::allocateEncoder(ftl::codecs::definition_t maxdef,
ftl::codecs::device_t dev) {
ftl::codecs::device_t dev, ftl::codecs::codec_t codec) {
UNIQUE_LOCK(mutex, lk);
if (!has_been_init) init_encoders();
......@@ -43,6 +44,7 @@ Encoder *ftl::codecs::allocateEncoder(ftl::codecs::definition_t maxdef,
if (!e->available) continue;
if (dev != device_t::Any && dev != e->device) continue;
if (maxdef != definition_t::Any && (maxdef < e->max_definition || maxdef > e->min_definition)) continue;
if (codec != codec_t::Any && !e->supports(codec)) continue;
e->available = false;
return e;
......@@ -68,11 +70,11 @@ Encoder::~Encoder() {
}
bool Encoder::encode(const cv::Mat &in, preset_t preset,
bool Encoder::encode(const cv::cuda::GpuMat &in, preset_t preset,
const std::function<void(const ftl::codecs::Packet&)> &cb) {
const auto &settings = ftl::codecs::getPreset(preset);
const definition_t definition = (in.type() == CV_32F) ? settings.depth_res : settings.colour_res;
const bitrate_t bitrate = (in.type() == CV_32F) ? settings.depth_qual : settings.colour_qual;
LOG(INFO) << "Encode definition: " << (int)definition;
return encode(in, definition, bitrate, cb);
}
......@@ -4,6 +4,7 @@
#include <ftl/cuda_util.hpp>
#include <ftl/codecs/hevc.hpp>
#include <ftl/codecs/h264.hpp>
//#include <cuda_runtime.h>
#include <opencv2/core/cuda/common.hpp>
......@@ -21,36 +22,10 @@ NvPipeDecoder::~NvPipeDecoder() {
}
}
void cropAndScaleUp(cv::Mat &in, cv::Mat &out) {
CHECK(in.type() == out.type());
auto isize = in.size();
auto osize = out.size();
cv::Mat tmp;
if (isize != osize) {
double x_scale = ((double) isize.width) / osize.width;
double y_scale = ((double) isize.height) / osize.height;
double x_scalei = 1.0 / x_scale;
double y_scalei = 1.0 / y_scale;
cv::Size sz_crop;
// assume downscaled image
if (x_scalei > y_scalei) {
sz_crop = cv::Size(isize.width, isize.height * x_scale);
} else {
sz_crop = cv::Size(isize.width * y_scale, isize.height);
}
tmp = in(cv::Rect(cv::Point2i(0, 0), sz_crop));
cv::resize(tmp, out, osize);
}
}
bool NvPipeDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
bool NvPipeDecoder::decode(const ftl::codecs::Packet &pkt, cv::cuda::GpuMat &out) {
cudaSetDevice(0);
UNIQUE_LOCK(mutex_,lk);
if (pkt.codec != codec_t::HEVC) return false;
if (pkt.codec != codec_t::HEVC && pkt.codec != codec_t::H264) return false;
bool is_float_frame = out.type() == CV_32F;
// Is the previous decoder still valid for current resolution and type?
......@@ -68,7 +43,7 @@ bool NvPipeDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
if (nv_decoder_ == nullptr) {
nv_decoder_ = NvPipe_CreateDecoder(
(is_float_frame) ? NVPIPE_UINT16 : NVPIPE_RGBA32,
NVPIPE_HEVC,
(pkt.codec == codec_t::HEVC) ? NVPIPE_HEVC : NVPIPE_H264,
ftl::codecs::getWidth(pkt.definition),
ftl::codecs::getHeight(pkt.definition));
if (!nv_decoder_) {
......@@ -82,45 +57,58 @@ bool NvPipeDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
}
// TODO: (Nick) Move to member variable to prevent re-creation
cv::Mat tmp(cv::Size(ftl::codecs::getWidth(pkt.definition),ftl::codecs::getHeight(pkt.definition)), (is_float_frame) ? CV_16U : CV_8UC4);
tmp_.create(cv::Size(ftl::codecs::getWidth(pkt.definition),ftl::codecs::getHeight(pkt.definition)), (is_float_frame) ? CV_16U : CV_8UC4);
// Check for an I-Frame
if (pkt.codec == ftl::codecs::codec_t::HEVC) {
// Obtain NAL unit type
if (ftl::codecs::hevc::isIFrame(pkt.data)) seen_iframe_ = true;
} else if (pkt.codec == ftl::codecs::codec_t::H264) {
if (ftl::codecs::h264::isIFrame(pkt.data)) seen_iframe_ = true;
}
// No I-Frame yet so don't attempt to decode P-Frames.
if (!seen_iframe_) return false;
int rc = NvPipe_Decode(nv_decoder_, pkt.data.data(), pkt.data.size(), tmp.data, tmp.cols, tmp.rows);
int rc = NvPipe_Decode(nv_decoder_, pkt.data.data(), pkt.data.size(), tmp_.data, tmp_.cols, tmp_.rows, tmp_.step);
if (rc == 0) LOG(ERROR) << "NvPipe decode error: " << NvPipe_GetError(nv_decoder_);
if (is_float_frame) {
// Is the received frame the same size as requested output?
if (out.rows == ftl::codecs::getHeight(pkt.definition)) {
tmp.convertTo(out, CV_32FC1, 1.0f/1000.0f);
tmp_.convertTo(out, CV_32FC1, 1.0f/1000.0f, stream_);
} else {
cv::cvtColor(tmp, tmp, cv::COLOR_BGRA2BGR);
cv::resize(tmp, out, out.size());
//cv::Mat tmp2;
//tmp.convertTo(tmp2, CV_32FC1, 1.0f/1000.0f);
//cropAndScaleUp(tmp2, out);
LOG(WARNING) << "Resizing decoded frame from " << tmp_.size() << " to " << out.size();
// FIXME: This won't work on GPU
tmp_.convertTo(tmp_, CV_32FC1, 1.0f/1000.0f, stream_);
cv::cuda::resize(tmp_, out, out.size(), 0, 0, cv::INTER_NEAREST, stream_);
}
} else {
// Is the received frame the same size as requested output?
if (out.rows == ftl::codecs::getHeight(pkt.definition)) {
cv::cvtColor(tmp, out, cv::COLOR_BGRA2BGR);
// Flag 0x1 means frame is in RGB so needs conversion to BGR
if (pkt.flags & 0x1) {
cv::cuda::cvtColor(tmp_, out, cv::COLOR_RGBA2BGR, 0, stream_);
} else {
cv::cuda::cvtColor(tmp_, out, cv::COLOR_BGRA2BGR, 0, stream_);
}
} else {
cv::cvtColor(tmp, tmp, cv::COLOR_BGRA2BGR);
cv::resize(tmp, out, out.size());
//cv::Mat tmp2;
//cv::cvtColor(tmp, tmp2, cv::COLOR_BGRA2BGR);
//cropAndScaleUp(tmp2, out);
LOG(WARNING) << "Resizing decoded frame from " << tmp_.size() << " to " << out.size();
// FIXME: This won't work on GPU, plus it allocates extra memory...
// Flag 0x1 means frame is in RGB so needs conversion to BGR
if (pkt.flags & 0x1) {
cv::cuda::cvtColor(tmp_, tmp_, cv::COLOR_RGBA2BGR, 0, stream_);
} else {
cv::cuda::cvtColor(tmp_, tmp_, cv::COLOR_BGRA2BGR, 0, stream_);
}
cv::cuda::resize(tmp_, out, out.size(), 0.0, 0.0, cv::INTER_LINEAR, stream_);
}
}
stream_.waitForCompletion();
return rc > 0;
}
bool NvPipeDecoder::accepts(const ftl::codecs::Packet &pkt) {
return pkt.codec == codec_t::HEVC;
return pkt.codec == codec_t::HEVC || pkt.codec == codec_t::H264;
}
......@@ -20,6 +20,7 @@ NvPipeEncoder::NvPipeEncoder(definition_t maxdef,
current_definition_ = definition_t::HD1080;
is_float_channel_ = false;
was_reset_ = false;
preference_ = codec_t::Any;
}
NvPipeEncoder::~NvPipeEncoder() {
......@@ -30,8 +31,16 @@ void NvPipeEncoder::reset() {
was_reset_ = true;
}
bool NvPipeEncoder::supports(ftl::codecs::codec_t codec) {
switch (codec) {
case codec_t::H264:
case codec_t::HEVC: preference_ = codec; return true;
default: return false;
}
}
/* Check preset resolution is not better than actual resolution. */
definition_t NvPipeEncoder::_verifiedDefinition(definition_t def, const cv::Mat &in) {
definition_t NvPipeEncoder::_verifiedDefinition(definition_t def, const cv::cuda::GpuMat &in) {
int height = ftl::codecs::getHeight(def);
// FIXME: Make sure this can't go forever
......@@ -43,48 +52,22 @@ definition_t NvPipeEncoder::_verifiedDefinition(definition_t def, const cv::Mat
return def;
}
void scaleDownAndPad(cv::Mat &in, cv::Mat &out) {
const auto isize = in.size();
const auto osize = out.size();
cv::Mat tmp;
if (isize != osize) {
double x_scale = ((double) isize.width) / osize.width;
double y_scale = ((double) isize.height) / osize.height;
double x_scalei = 1.0 / x_scale;
double y_scalei = 1.0 / y_scale;
if (x_scale > 1.0 || y_scale > 1.0) {
if (x_scale > y_scale) {
cv::resize(in, tmp, cv::Size(osize.width, osize.height * x_scalei));
} else {
cv::resize(in, tmp, cv::Size(osize.width * y_scalei, osize.height));
}
}
else { tmp = in; }
if (tmp.size().width < osize.width || tmp.size().height < osize.height) {
tmp.copyTo(out(cv::Rect(cv::Point2i(0, 0), tmp.size())));
}
else { out = tmp; }
}
}
bool NvPipeEncoder::encode(const cv::Mat &in, definition_t odefinition, bitrate_t bitrate, const std::function<void(const ftl::codecs::Packet&)> &cb) {
bool NvPipeEncoder::encode(const cv::cuda::GpuMat &in, definition_t odefinition, bitrate_t bitrate, const std::function<void(const ftl::codecs::Packet&)> &cb) {
cudaSetDevice(0);
auto definition = odefinition; //_verifiedDefinition(odefinition, in);
auto width = ftl::codecs::getWidth(definition);
auto height = ftl::codecs::getHeight(definition);
cv::Mat tmp;
cv::cuda::GpuMat tmp;
if (width != in.cols || height != in.rows) {
LOG(WARNING) << "Mismatch resolution with encoding resolution";
if (in.type() == CV_32F) {
cv::resize(in, tmp, cv::Size(width,height), 0.0, 0.0, cv::INTER_NEAREST);
cv::cuda::resize(in, tmp_, cv::Size(width,height), 0.0, 0.0, cv::INTER_NEAREST, stream_);
} else {
cv::resize(in, tmp, cv::Size(width,height));
cv::cuda::resize(in, tmp_, cv::Size(width,height), 0.0, 0.0, cv::INTER_LINEAR, stream_);
}
tmp = tmp_;
} else {
tmp = in;
}
......@@ -101,33 +84,35 @@ bool NvPipeEncoder::encode(const cv::Mat &in, definition_t odefinition, bitrate_
//cv::Mat tmp;
if (tmp.type() == CV_32F) {
tmp.convertTo(tmp, CV_16UC1, 1000);
tmp.convertTo(tmp2_, CV_16UC1, 1000, stream_);
} else if (tmp.type() == CV_8UC3) {
cv::cvtColor(tmp, tmp, cv::COLOR_BGR2BGRA);
cv::cuda::cvtColor(tmp, tmp2_, cv::COLOR_BGR2RGBA, 0, stream_);
} else if (tmp.type() == CV_8UC4) {
cv::cuda::cvtColor(tmp, tmp2_, cv::COLOR_BGRA2RGBA, 0, stream_);
} else {
//in.copyTo(tmp);
LOG(ERROR) << "Unsupported cv::Mat type in Nvidia encoder";
return false;
}
// scale/pad to fit output format
//cv::Mat tmp2 = cv::Mat::zeros(getHeight(odefinition), getWidth(odefinition), tmp.type());
//scaleDownAndPad(tmp, tmp2);
//std::swap(tmp, tmp2);
// Make sure conversions complete...
stream_.waitForCompletion();
Packet pkt;
pkt.codec = codec_t::HEVC;
pkt.codec = (preference_ == codec_t::Any) ? codec_t::HEVC : preference_;
pkt.definition = definition;
pkt.block_total = 1;
pkt.block_number = 0;
pkt.flags = NvPipeEncoder::kFlagRGB;
pkt.data.resize(ftl::codecs::kVideoBufferSize);
uint64_t cs = NvPipe_Encode(
nvenc_,
tmp.data,
tmp.step,
tmp2_.data,
tmp2_.step,
pkt.data.data(),
ftl::codecs::kVideoBufferSize,
tmp.cols,
tmp.rows,
tmp2_.cols,
tmp2_.rows,
was_reset_ // Force IFrame!
);
pkt.data.resize(cs);
......@@ -142,14 +127,40 @@ bool NvPipeEncoder::encode(const cv::Mat &in, definition_t odefinition, bitrate_
}
}
bool NvPipeEncoder::_encoderMatch(const cv::Mat &in, definition_t def) {
bool NvPipeEncoder::_encoderMatch(const cv::cuda::GpuMat &in, definition_t def) {
return ((in.type() == CV_32F && is_float_channel_) ||
((in.type() == CV_8UC3 || in.type() == CV_8UC4) && !is_float_channel_)) && current_definition_ == def;
}
bool NvPipeEncoder::_createEncoder(const cv::Mat &in, definition_t def, bitrate_t rate) {
static uint64_t calculateBitrate(definition_t def, bitrate_t rate) {
float scale = 1.0f;
switch (rate) {
case bitrate_t::High : break;
case bitrate_t::Standard : scale = 0.5f; break;
case bitrate_t::Low : scale = 0.25f; break;
}
float bitrate = 1.0f; // Megabits
switch (def) {
case definition_t::UHD4k : bitrate = 24.0f; break;
case definition_t::HTC_VIVE : bitrate = 16.0f; break;
case definition_t::HD1080 : bitrate = 16.0f; break;
case definition_t::HD720 : bitrate = 8.0f; break;
case definition_t::SD576 :
case definition_t::SD480 : bitrate = 4.0f; break;
case definition_t::LD360 : bitrate = 2.0f; break;
default : bitrate = 8.0f;
}
return uint64_t(bitrate * 1000.0f * 1000.0f * scale);
}
bool NvPipeEncoder::_createEncoder(const cv::cuda::GpuMat &in, definition_t def, bitrate_t rate) {
if (_encoderMatch(in, def) && nvenc_) return true;
uint64_t bitrate = calculateBitrate(def, rate);
LOG(INFO) << "Calculated bitrate: " << bitrate;
if (in.type() == CV_32F) is_float_channel_ = true;
else is_float_channel_ = false;
current_definition_ = def;
......@@ -158,9 +169,9 @@ bool NvPipeEncoder::_createEncoder(const cv::Mat &in, definition_t def, bitrate_
const int fps = 1000/ftl::timer::getInterval();
nvenc_ = NvPipe_CreateEncoder(
(is_float_channel_) ? NVPIPE_UINT16 : NVPIPE_RGBA32,
NVPIPE_HEVC,
(preference_ == codec_t::Any || preference_ == codec_t::HEVC) ? NVPIPE_HEVC : NVPIPE_H264,
(is_float_channel_) ? NVPIPE_LOSSLESS : NVPIPE_LOSSY,
16*1000*1000,
bitrate,
fps, // FPS
ftl::codecs::getWidth(def), // Output Width
ftl::codecs::getHeight(def) // Output Height
......
......@@ -17,8 +17,7 @@ bool OpenCVDecoder::accepts(const ftl::codecs::Packet &pkt) {
return (pkt.codec == codec_t::JPG || pkt.codec == codec_t::PNG);
}
bool OpenCVDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
cv::Mat tmp;
bool OpenCVDecoder::decode(const ftl::codecs::Packet &pkt, cv::cuda::GpuMat &out) {
int chunk_dim = std::sqrt(pkt.block_total);
int chunk_width = out.cols / chunk_dim;
......@@ -28,10 +27,12 @@ bool OpenCVDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
int cx = (pkt.block_number % chunk_dim) * chunk_width;
int cy = (pkt.block_number / chunk_dim) * chunk_height;
cv::Rect roi(cx,cy,chunk_width,chunk_height);
cv::Mat chunkHead = out(roi);
cv::cuda::GpuMat chunkHead = out(roi);
//LOG(INFO) << "DECODE JPEG " << (int)pkt.block_number << "/" << chunk_dim;
// Decode in temporary buffers to prevent long locks
cv::imdecode(pkt.data, cv::IMREAD_UNCHANGED, &tmp);
cv::imdecode(pkt.data, cv::IMREAD_UNCHANGED, &tmp_);
// Apply colour correction to chunk
//ftl::rgbd::colourCorrection(tmp_rgb, gamma_, temperature_);
......@@ -41,21 +42,25 @@ bool OpenCVDecoder::decode(const ftl::codecs::Packet &pkt, cv::Mat &out) {
// Can either check JPG/PNG headers or just use pkt definition.
// Original size so just copy
if (tmp.cols == chunkHead.cols) {
if (!tmp.empty() && tmp.type() == CV_16U && chunkHead.type() == CV_32F) {
tmp.convertTo(chunkHead, CV_32FC1, 1.0f/1000.0f); //(16.0f*10.0f));
} else if (!tmp.empty() && tmp.type() == CV_8UC3 && chunkHead.type() == CV_8UC3) {
tmp.copyTo(chunkHead);
if (tmp_.cols == chunkHead.cols) {
if (!tmp_.empty() && tmp_.type() == CV_16U && chunkHead.type() == CV_32F) {
tmp_.convertTo(tmp_, CV_32FC1, 1.0f/1000.0f);
chunkHead.upload(tmp_);
} else if (!tmp_.empty() && tmp_.type() == CV_8UC3 && chunkHead.type() == CV_8UC3) {
//tmp_.copyTo(chunkHead);
chunkHead.upload(tmp_);
} else {
// Silent ignore?
}
// Downsized so needs a scale up
} else {
if (!tmp.empty() && tmp.type() == CV_16U && chunkHead.type() == CV_32F) {
tmp.convertTo(tmp, CV_32FC1, 1.0f/1000.0f); //(16.0f*10.0f));
cv::resize(tmp, chunkHead, chunkHead.size(), 0, 0, cv::INTER_NEAREST);
} else if (!tmp.empty() && tmp.type() == CV_8UC3 && chunkHead.type() == CV_8UC3) {
cv::resize(tmp, chunkHead, chunkHead.size());
if (!tmp_.empty() && tmp_.type() == CV_16U && chunkHead.type() == CV_32F) {
tmp_.convertTo(tmp_, CV_32FC1, 1.0f/1000.0f); //(16.0f*10.0f));
cv::resize(tmp_, tmp_, chunkHead.size(), 0, 0, cv::INTER_NEAREST);
chunkHead.upload(tmp_);
} else if (!tmp_.empty() && tmp_.type() == CV_8UC3 && chunkHead.type() == CV_8UC3) {
cv::resize(tmp_, tmp_, chunkHead.size());
chunkHead.upload(tmp_);
} else {
// Silent ignore?
}
......
......@@ -20,21 +20,30 @@ OpenCVEncoder::~OpenCVEncoder() {
}
bool OpenCVEncoder::encode(const cv::Mat &in, definition_t definition, bitrate_t bitrate, const std::function<void(const ftl::codecs::Packet&)> &cb) {
cv::Mat tmp;
bool OpenCVEncoder::supports(ftl::codecs::codec_t codec) {
switch (codec) {
case codec_t::JPG:
case codec_t::PNG: return true;
default: return false;
}
}
bool OpenCVEncoder::encode(const cv::cuda::GpuMat &in, definition_t definition, bitrate_t bitrate, const std::function<void(const ftl::codecs::Packet&)> &cb) {
bool is_colour = in.type() != CV_32F;
current_definition_ = definition;
in.download(tmp_);
// Scale down image to match requested definition...
if (ftl::codecs::getHeight(current_definition_) < in.rows) {
cv::resize(in, tmp, cv::Size(ftl::codecs::getWidth(current_definition_), ftl::codecs::getHeight(current_definition_)), 0, 0, (is_colour) ? 1 : cv::INTER_NEAREST);
cv::resize(tmp_, tmp_, cv::Size(ftl::codecs::getWidth(current_definition_), ftl::codecs::getHeight(current_definition_)), 0, 0, (is_colour) ? 1 : cv::INTER_NEAREST);
} else {
tmp = in;
}
// Represent float at 16bit int
if (!is_colour) {
tmp.convertTo(tmp, CV_16UC1, 1000);
tmp_.convertTo(tmp_, CV_16UC1, 1000);
}
chunk_dim_ = (definition == definition_t::LD360) ? 1 : 4;
......@@ -43,7 +52,7 @@ bool OpenCVEncoder::encode(const cv::Mat &in, definition_t definition, bitrate_t
for (int i=0; i<chunk_count_; ++i) {
// Add chunk job to thread pool
ftl::pool.push([this,i,&tmp,cb,is_colour,bitrate](int id) {
ftl::pool.push([this,i,cb,is_colour,bitrate](int id) {
ftl::codecs::Packet pkt;
pkt.block_number = i;
pkt.block_total = chunk_count_;
......@@ -51,7 +60,7 @@ bool OpenCVEncoder::encode(const cv::Mat &in, definition_t definition, bitrate_t
pkt.codec = (is_colour) ? codec_t::JPG : codec_t::PNG;
try {
_encodeBlock(tmp, pkt, bitrate);
_encodeBlock(tmp_, pkt, bitrate);
} catch(...) {
LOG(ERROR) << "OpenCV encode block exception: " << i;
}
......
......@@ -22,6 +22,14 @@ bool Reader::begin() {
(*stream_).read((char*)&h, sizeof(h));
if (h.magic[0] != 'F' || h.magic[1] != 'T' || h.magic[2] != 'L' || h.magic[3] != 'F') return false;
if (h.version >= 2) {
ftl::codecs::IndexHeader ih;
(*stream_).read((char*)&ih, sizeof(ih));
}
version_ = h.version;
LOG(INFO) << "FTL format version " << version_;
// Capture current time to adjust timestamps
timestart_ = (ftl::timer::get_time() / ftl::timer::getInterval()) * ftl::timer::getInterval();
playing_ = true;
......@@ -29,6 +37,22 @@ bool Reader::begin() {
return true;
}
/*static void printMsgpack(msgpack::object &obj) {
switch (obj.type) {
case msgpack::type::NIL: return;
case msgpack::type::BOOLEAN: LOG(INFO) << "BOOL " << obj.as<bool>(); return;
case msgpack::type::POSITIVE_INTEGER:
case msgpack::type::NEGATIVE_INTEGER: LOG(INFO) << "INT " << obj.as<int>(); return;
case msgpack::type::FLOAT32: LOG(INFO) << "FLOAT " << obj.as<float>(); return;
case msgpack::type::FLOAT64: LOG(INFO) << "DOUBLE " << obj.as<double>(); return;
case msgpack::type::STR: LOG(INFO) << "STRING " << obj.as<std::string>(); return;
case msgpack::type::BIN: return;
case msgpack::type::EXT: return;
case msgpack::type::ARRAY: LOG(INFO) << "ARRAY: "; return;
case msgpack::type::MAP: LOG(INFO) << "MAP: "; return;
}
}*/
bool Reader::read(int64_t ts, const std::function<void(const ftl::codecs::StreamPacket &, ftl::codecs::Packet &)> &f) {
//UNIQUE_LOCK(mtx_, lk);
std::unique_lock<std::mutex> lk(mtx_, std::defer_lock);
......@@ -67,10 +91,13 @@ bool Reader::read(int64_t ts, const std::function<void(const ftl::codecs::Stream
//std::tuple<StreamPacket,Packet> data;
msgpack::object obj = msg.get();
//printMsgpack(obj);
try {
obj.convert(data_.emplace_back());
} catch (std::exception &e) {
LOG(INFO) << "Corrupt message: " << buffer_.nonparsed_size();
LOG(INFO) << "Corrupt message: " << buffer_.nonparsed_size() << " - " << e.what();
//partial = true;
//continue;
return false;
......@@ -81,6 +108,11 @@ bool Reader::read(int64_t ts, const std::function<void(const ftl::codecs::Stream
// Adjust timestamp
get<0>(data).timestamp += timestart_;
// Fix to clear flags for version 2.
if (version_ <= 2) {
get<1>(data).flags = 0;
}
// TODO: Need to read ahead a few frames because there may be a
// smaller timestamp after this one... requires a buffer. Ideally this
// should be resolved during the write process.
......
......@@ -14,9 +14,13 @@ Writer::~Writer() {
bool Writer::begin() {
ftl::codecs::Header h;
h.version = 0;
//h.version = 2;
(*stream_).write((const char*)&h, sizeof(h));
ftl::codecs::IndexHeader ih;
ih.reserved[0] = -1;
(*stream_).write((const char*)&ih, sizeof(ih));
// Capture current time to adjust timestamps
timestart_ = ftl::timer::get_time();
active_ = true;
......@@ -37,7 +41,8 @@ bool Writer::write(const ftl::codecs::StreamPacket &s, const ftl::codecs::Packet
auto data = std::make_tuple(s2,p);
msgpack::sbuffer buffer;
msgpack::pack(buffer, data);
UNIQUE_LOCK(mutex_, lk);
(*stream_).write(buffer.data(), buffer.size());
//buffer_.clear();
return true;
}
......@@ -24,7 +24,7 @@ namespace ftl {
TEST_CASE( "NvPipeEncoder::encode() - A colour test image at preset 0" ) {
ftl::codecs::NvPipeEncoder encoder(definition_t::HD1080, definition_t::SD480);
cv::Mat m(cv::Size(1920,1080), CV_8UC3, cv::Scalar(0,0,0));
cv::cuda::GpuMat m(cv::Size(1920,1080), CV_8UC3, cv::Scalar(0,0,0));
int block_total = 0;
std::atomic<int> block_count = 0;
......@@ -46,7 +46,7 @@ TEST_CASE( "NvPipeEncoder::encode() - A colour test image at preset 0" ) {
TEST_CASE( "NvPipeEncoder::encode() - A depth test image at preset 0" ) {
ftl::codecs::NvPipeEncoder encoder(definition_t::HD1080, definition_t::SD480);
cv::Mat m(cv::Size(1920,1080), CV_32F, cv::Scalar(0.0f));
cv::cuda::GpuMat m(cv::Size(1920,1080), CV_32F, cv::Scalar(0.0f));
int block_total = 0;
std::atomic<int> block_count = 0;
......@@ -70,13 +70,13 @@ TEST_CASE( "NvPipeDecoder::decode() - A colour test image" ) {
ftl::codecs::NvPipeEncoder encoder(definition_t::HD1080, definition_t::SD480);
ftl::codecs::NvPipeDecoder decoder;
cv::Mat in;
cv::Mat out;
cv::cuda::GpuMat in;
cv::cuda::GpuMat out;
bool r = false;
SECTION("FHD in and out, FHD encoding") {
in = cv::Mat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(255,0,0));
out = cv::Mat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(0,0,0));
in = cv::cuda::GpuMat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(255,0,0));
out = cv::cuda::GpuMat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(0,0,0));
r = encoder.encode(in, ftl::codecs::kPreset0, [&out,&decoder](const ftl::codecs::Packet &pkt) {
REQUIRE( decoder.decode(pkt, out) );
......@@ -84,8 +84,8 @@ TEST_CASE( "NvPipeDecoder::decode() - A colour test image" ) {
}
SECTION("Full HD in, 720 out, FHD encoding") {
in = cv::Mat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(255,0,0));
out = cv::Mat(cv::Size(1280,720), CV_8UC3, cv::Scalar(0,0,0));
in = cv::cuda::GpuMat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(255,0,0));
out = cv::cuda::GpuMat(cv::Size(1280,720), CV_8UC3, cv::Scalar(0,0,0));
r = encoder.encode(in, ftl::codecs::kPreset0, [&out,&decoder](const ftl::codecs::Packet &pkt) {
REQUIRE( decoder.decode(pkt, out) );
......@@ -95,8 +95,8 @@ TEST_CASE( "NvPipeDecoder::decode() - A colour test image" ) {
}
SECTION("HHD in, FHD out, FHD encoding") {
in = cv::Mat(cv::Size(1280,720), CV_8UC3, cv::Scalar(255,0,0));
out = cv::Mat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(0,0,0));
in = cv::cuda::GpuMat(cv::Size(1280,720), CV_8UC3, cv::Scalar(255,0,0));
out = cv::cuda::GpuMat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(0,0,0));
r = encoder.encode(in, ftl::codecs::kPreset0, [&out,&decoder](const ftl::codecs::Packet &pkt) {
REQUIRE( decoder.decode(pkt, out) );
......@@ -106,8 +106,8 @@ TEST_CASE( "NvPipeDecoder::decode() - A colour test image" ) {
}
SECTION("FHD in, HHD out, SD encoding") {
in = cv::Mat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(255,0,0));
out = cv::Mat(cv::Size(1280,720), CV_8UC3, cv::Scalar(0,0,0));
in = cv::cuda::GpuMat(cv::Size(1920,1080), CV_8UC3, cv::Scalar(255,0,0));
out = cv::cuda::GpuMat(cv::Size(1280,720), CV_8UC3, cv::Scalar(0,0,0));
r = encoder.encode(in, ftl::codecs::kPreset4, [&out,&decoder](const ftl::codecs::Packet &pkt) {
REQUIRE( decoder.decode(pkt, out) );
......@@ -117,5 +117,5 @@ TEST_CASE( "NvPipeDecoder::decode() - A colour test image" ) {
}
REQUIRE( r );
REQUIRE( (cv::sum(out) != cv::Scalar(0,0,0)) );
REQUIRE( (cv::cuda::sum(out) != cv::Scalar(0,0,0)) );
}
......@@ -24,7 +24,7 @@ namespace ftl {
TEST_CASE( "OpenCVEncoder::encode() - A colour test image at preset 0" ) {
ftl::codecs::OpenCVEncoder encoder(definition_t::HD1080, definition_t::SD480);
cv::Mat m(cv::Size(1024,576), CV_8UC3, cv::Scalar(0,0,0));
cv::cuda::GpuMat m(cv::Size(1024,576), CV_8UC3, cv::Scalar(0,0,0));
int block_total = 0;
std::atomic<int> block_count = 0;
......@@ -53,7 +53,7 @@ TEST_CASE( "OpenCVEncoder::encode() - A colour test image at preset 0" ) {
TEST_CASE( "OpenCVEncoder::encode() - A depth test image at preset 0" ) {
ftl::codecs::OpenCVEncoder encoder(definition_t::HD1080, definition_t::SD480);
cv::Mat m(cv::Size(1024,576), CV_32F, cv::Scalar(0.0f));
cv::cuda::GpuMat m(cv::Size(1024,576), CV_32F, cv::Scalar(0.0f));
int block_total = 0;
std::atomic<int> block_count = 0;
......@@ -82,8 +82,8 @@ TEST_CASE( "OpenCVEncoder::encode() - A depth test image at preset 0" ) {
TEST_CASE( "OpenCVDecoder::decode() - A colour test image no resolution change" ) {
ftl::codecs::OpenCVEncoder encoder(definition_t::HD1080, definition_t::SD480);
ftl::codecs::OpenCVDecoder decoder;
cv::Mat in(cv::Size(1024,576), CV_8UC3, cv::Scalar(255,0,0));
cv::Mat out(cv::Size(1024,576), CV_8UC3, cv::Scalar(0,0,0));
cv::cuda::GpuMat in(cv::Size(1024,576), CV_8UC3, cv::Scalar(255,0,0));
cv::cuda::GpuMat out(cv::Size(1024,576), CV_8UC3, cv::Scalar(0,0,0));
std::mutex mtx;
......@@ -92,5 +92,5 @@ TEST_CASE( "OpenCVDecoder::decode() - A colour test image no resolution change"
REQUIRE( decoder.decode(pkt, out) );
});
REQUIRE( (cv::sum(out) != cv::Scalar(0,0,0)) );
REQUIRE( (cv::cuda::sum(out) != cv::Scalar(0,0,0)) );
}
......@@ -80,6 +80,7 @@ class Configurable {
template <typename T>
void set(const std::string &name, T value) {
(*config_)[name] = value;
inject(name, (*config_)[name]);
_trigger(name);
}
......@@ -103,12 +104,12 @@ class Configurable {
protected:
nlohmann::json *config_;
virtual void inject(const std::string name, nlohmann::json &value) {}
private:
std::map<std::string, std::list<std::function<void(const config::Event&)>>> observers_;
void _trigger(const std::string &name);
static void __changeURI(const std::string &uri, Configurable *cfg);
};
/*template <>
......
......@@ -59,8 +59,4 @@ void Configurable::on(const string &prop, function<void(const ftl::config::Event
} else {
(*ix).second.push_back(f);
}
}
void Configurable::__changeURI(const string &uri, Configurable *cfg) {
}
\ No newline at end of file