Skip to content

Commit

Permalink
Merge pull request #6 from dji-sdk/release/v1.1.1
Browse files Browse the repository at this point in the history
* Added support for subscribing to the 1080p high-bitrate stream on D…
  • Loading branch information
dji-dev authored Apr 7, 2024
2 parents 3ca0445 + 76e3365 commit e33d457
Show file tree
Hide file tree
Showing 15 changed files with 316 additions and 71 deletions.
3 changes: 3 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ file(GLOB_RECURSE MODULE_SAMPLE_SRC
examples/init/key_store_default.cc)

include_directories(include)
include_directories(examples)
include_directories(examples/common)

link_directories(${CMAKE_CURRENT_LIST_DIR}/lib/${CMAKE_HOST_SYSTEM_PROCESSOR})
Expand Down Expand Up @@ -90,7 +91,9 @@ if (OpenCV_FOUND AND FFMPEG_FOUND)
target_link_libraries(sample_liveview ${SAMPLE_LIB})

add_executable(test_liveview examples/liveview/test_liveview_main.cc)
add_executable(test_liveview_dual examples/liveview/test_liveview_dual_main.cc)
target_link_libraries(test_liveview ${SAMPLE_LIB})
target_link_libraries(test_liveview_dual ${SAMPLE_LIB})

add_executable(pressure_test examples/test/pressure_test.cc)
target_link_libraries(pressure_test ${SAMPLE_LIB})
Expand Down
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# DJI Edge SDK (ESDK)

![](https://img.shields.io/badge/version-V1.1.0-yellow.svg)
![](https://img.shields.io/badge/version-V1.1.1-yellow.svg)
![](https://img.shields.io/badge/platform-linux-green.svg)
![](https://img.shields.io/badge/license-MIT-blue.svg)

Expand Down Expand Up @@ -28,7 +28,7 @@ Edge computing offers a secure local communication link, ensuring communication
Edge computing can process and transmit data in unstable network environments, utilizing small data channels to enhance transmission efficiency. This ensures aircraft achieve efficient data processing and transmission across various environments.

## Dependencies
* libssh2 (version 1.10.x or higher)
* libssh2 (reference version 1.10.0)
* openssl (reference version 1.1.1f)
* opencv (version 3.4.16 or higher)
* ffmpeg (version 4.13 or higher)
Expand Down
2 changes: 1 addition & 1 deletion examples/common/image_processor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ ImageProcessor::~ImageProcessor() {}
std::shared_ptr<ImageProcessor> CreateImageProcessor(
const ImageProcessor::Options& option) {
if (option.name == std::string("display")) {
return std::make_shared<ImageDisplayProcessor>(option.alias);
return std::make_shared<ImageDisplayProcessor>(option.alias, option.userdata);
}
if (option.name == std::string("yolovfastest")) {
return std::make_shared<ImageProcessorYolovFastest>(option.alias);
Expand Down
1 change: 1 addition & 0 deletions examples/common/image_processor.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ class ImageProcessor {
struct Options {
std::string name;
std::string alias;
std::shared_ptr<void> userdata;
};

virtual int32_t Init() { return 0; }
Expand Down
14 changes: 12 additions & 2 deletions examples/common/image_processor_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,16 +22,21 @@
#ifndef __IMAGE_PROCESSOR_DIAPLAY_H__
#define __IMAGE_PROCESSOR_DIAPLAY_H__

#include <memory>
#include "opencv2/opencv.hpp"
#include "liveview/sample_liveview.h"

namespace edge_app {

class ImageDisplayProcessor : public ImageProcessor {
public:
ImageDisplayProcessor(const std::string& name) : name_(name) {
ImageDisplayProcessor(const std::string& name, std::shared_ptr<void> userdata) : name_(name) {
cv::namedWindow(name.c_str(), cv::WINDOW_NORMAL);
cv::resizeWindow(name.c_str(), 960, 540);
cv::moveWindow(name.c_str(), rand() & 0xFF, rand() & 0xFF);
if (userdata) {
liveview_sample_ = std::static_pointer_cast<LiveviewSample>(userdata);
}
}

~ImageDisplayProcessor() override {}
Expand All @@ -40,14 +45,19 @@ class ImageDisplayProcessor : public ImageProcessor {
std::string h = std::to_string(image->size().width);
std::string w = std::to_string(image->size().height);
std::string osd = h + "x" + w;
if (liveview_sample_) {
auto kbps = liveview_sample_->GetStreamBitrate();
osd += std::string(",") + std::to_string(kbps) + std::string("kbps");
}
putText(*image, osd, cv::Point(10, 30), cv::FONT_HERSHEY_SIMPLEX, 1,
cv::Scalar(0, 255, 0));
cv::Scalar(0, 0, 255), 3);
imshow(name_.c_str(), *image);
cv::waitKey(1);
}

private:
std::string name_;
std::shared_ptr<LiveviewSample> liveview_sample_;
};

} // namespace edge_app
Expand Down
1 change: 0 additions & 1 deletion examples/liveview/image_processor_thread.cc
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,6 @@ void ImageProcessorThread::InputImage(const std::shared_ptr<Image> image) {
image_queue_.push(image);
if (image_queue_.size() > kImageQueueSizeLimit) {
image_queue_.pop();
DEBUG("image queue full...");
}
image_queue_cv_.notify_one();
}
Expand Down
30 changes: 22 additions & 8 deletions examples/liveview/sample_liveview.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,9 @@

#include "liveview/liveview.h"

#define BITRATE_CALCULATE_BITS_PER_BYTE 8
#define BITRATE_CALCULATE_INTERVAL_TIME_MS 2000

using namespace edge_sdk;

namespace edge_app {
Expand All @@ -35,9 +38,20 @@ LiveviewSample::LiveviewSample(const std::string& name) {
}

ErrorCode LiveviewSample::StreamCallback(const uint8_t* data, size_t len) {
auto now = std::chrono::system_clock::now();
if (stream_processor_thread_) {
stream_processor_thread_->InputStream(data, len);
}

// for bitrate calculate
receive_stream_data_total_size_ += len;
auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(now - receive_stream_data_time_).count();
if (duration >= BITRATE_CALCULATE_INTERVAL_TIME_MS) {
auto kbps = receive_stream_data_total_size_ * BITRATE_CALCULATE_BITS_PER_BYTE / (BITRATE_CALCULATE_INTERVAL_TIME_MS / 1000) / 1024;
stream_bitrate_kbps_ = kbps;
receive_stream_data_total_size_ = 0;
receive_stream_data_time_ = now;
}
return kOk;
}

Expand Down Expand Up @@ -82,26 +96,26 @@ void LiveviewSample::LiveviewStatusCallback(
DEBUG("status: %d", status);
}

std::shared_ptr<LiveviewSample> LiveviewSample::CreateLiveview(
const std::string& name, edge_sdk::Liveview::CameraType type,
int32_t InitLiveviewSample(std::shared_ptr<LiveviewSample>& liveview_sample, edge_sdk::Liveview::CameraType type,
edge_sdk::Liveview::StreamQuality quality,
std::shared_ptr<StreamDecoder> stream_decoder,
std::shared_ptr<ImageProcessor> image_processor) {
auto image_processor_thread = std::make_shared<ImageProcessorThread>(name);
std::shared_ptr<ImageProcessor> image_processor)
{
auto image_processor_thread = std::make_shared<ImageProcessorThread>(stream_decoder->Name());
image_processor_thread->SetImageProcessor(image_processor);

auto stream_processor_thread =
std::make_shared<StreamProcessorThread>(name);
std::make_shared<StreamProcessorThread>(stream_decoder->Name());
stream_processor_thread->SetStreamDecoder(stream_decoder);
stream_processor_thread->SetImageProcessorThread(image_processor_thread);

auto liveview = std::make_shared<LiveviewSample>(name);
auto rc = liveview->Init(type, quality, stream_processor_thread);
auto rc = liveview_sample->Init(type, quality, stream_processor_thread);
if (rc != kOk) {
ERROR("liveview sample init failed");
return -1;
}

return liveview;
return 0;
}

ErrorCode LiveviewSample::SetCameraSource(
Expand Down
22 changes: 15 additions & 7 deletions examples/liveview/sample_liveview.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@
#ifndef __SAMPLE_LIVEVIEW_H__
#define __SAMPLE_LIVEVIEW_H__

#include <chrono>
#include <atomic>
#include "error_code.h"
#include "image_processor.h"
#include "image_processor_thread.h"
Expand All @@ -34,13 +36,7 @@ namespace edge_app {

class LiveviewSample {
public:
static std::shared_ptr<LiveviewSample> CreateLiveview(
const std::string& name, edge_sdk::Liveview::CameraType type,
edge_sdk::Liveview::StreamQuality quality,
std::shared_ptr<StreamDecoder> stream_decoder,
std::shared_ptr<ImageProcessor> image_processor);

LiveviewSample(const std::string& name);
explicit LiveviewSample(const std::string& name);
~LiveviewSample() {}

edge_sdk::ErrorCode Init(edge_sdk::Liveview::CameraType type,
Expand All @@ -52,6 +48,10 @@ class LiveviewSample {
edge_sdk::ErrorCode SetCameraSource(
edge_sdk::Liveview::CameraSource source);

uint32_t GetStreamBitrate() const {
return stream_bitrate_kbps_.load();
}

private:
edge_sdk::ErrorCode StreamCallback(const uint8_t* data, size_t len);

Expand All @@ -61,8 +61,16 @@ class LiveviewSample {
std::shared_ptr<edge_sdk::Liveview> liveview_;
std::shared_ptr<StreamProcessorThread> stream_processor_thread_;
edge_sdk::Liveview::LiveviewStatus liveview_status_;
std::atomic<uint32_t> stream_bitrate_kbps_;
std::chrono::system_clock::time_point receive_stream_data_time_ = std::chrono::system_clock::now();
uint32_t receive_stream_data_total_size_;
};

int32_t InitLiveviewSample(std::shared_ptr<LiveviewSample>& liveview_sample, edge_sdk::Liveview::CameraType type,
edge_sdk::Liveview::StreamQuality quality,
std::shared_ptr<StreamDecoder> stream_decoder,
std::shared_ptr<ImageProcessor> image_processor);

} // namespace edge_app

#endif
52 changes: 30 additions & 22 deletions examples/liveview/sample_liveview_main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,23 +38,10 @@ int main(int argc, char** argv) {
return -1;
}

StreamDecoder::Options decoder_option = {.name = std::string("ffmpeg")};
// create fpv stream decoder
auto fpv_decoder = CreateStreamDecoder(decoder_option);

// create fpv image processor
ImageProcessor::Options fpv_image_processor_option = {
.name = std::string("display"), .alias = std::string("FPVCamera")};
auto fpv_image_processor = CreateImageProcessor(fpv_image_processor_option);

// create fpv liveview
auto fpv_liveview = edge_app::LiveviewSample::CreateLiveview(
"Fpv", Liveview::kCameraTypeFpv, Liveview::kStreamQuality720p,
fpv_decoder, fpv_image_processor);

// start fpv liveview
fpv_liveview->Start();
// create payload liveview
auto payload_liveview = std::make_shared<LiveviewSample>("Payload");

StreamDecoder::Options decoder_option = {.name = std::string("ffmpeg")};
// create payload decoder
auto payload_decoder = CreateStreamDecoder(decoder_option);

Expand All @@ -64,13 +51,34 @@ int main(int argc, char** argv) {
.alias = std::string("PlayloadCamera: Yolovfastest")};
auto payload_image_processor = CreateImageProcessor(image_processor_option);

// create payload liveview
auto payload_liveview = LiveviewSample::CreateLiveview(
"Payload", Liveview::kCameraTypePayload, Liveview::kStreamQuality720p,
payload_decoder, payload_image_processor);
if (0 != InitLiveviewSample(
payload_liveview, Liveview::kCameraTypePayload, Liveview::kStreamQuality1080pHigh,
payload_decoder, payload_image_processor)) {
ERROR("Init fpv liveview sample failed");
} else {
// start payload liveview
payload_liveview->Start();
}

// create fpv liveview
auto fpv_liveview = std::make_shared<LiveviewSample>("Fpv");

// create fpv stream decoder
auto fpv_decoder = CreateStreamDecoder(decoder_option);

// create fpv image processor
ImageProcessor::Options fpv_image_processor_option = {
.name = std::string("display"), .alias = std::string("FPVCamera"), .userdata = fpv_liveview};
auto fpv_image_processor = CreateImageProcessor(fpv_image_processor_option);

// start payload liveview
payload_liveview->Start();
if (0 != InitLiveviewSample(
fpv_liveview, Liveview::kCameraTypeFpv, Liveview::kStreamQuality720p,
fpv_decoder, fpv_image_processor)) {
ERROR("Init fpv liveview sample failed");
} else {
// start fpv liveview
fpv_liveview->Start();
}

while (1) sleep(3);

Expand Down
98 changes: 98 additions & 0 deletions examples/liveview/test_liveview_dual_main.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
/**
********************************************************************
*
* @copyright (c) 2023 DJI. All rights reserved.
*
* All information contained herein is, and remains, the property of DJI.
* The intellectual and technical concepts contained herein are proprietary
* to DJI and may be covered by U.S. and foreign patents, patents in process,
* and protected by trade secret or copyright law. Dissemination of this
* information, including but not limited to data and other proprietary
* material(s) incorporated within the information, in any form, is strictly
* prohibited without the express written consent of DJI.
*
* If you receive this source code without DJI’s authorization, you may not
* further disseminate the information, and you must immediately remove the
* source code and notify DJI of its removal. DJI reserves the right to pursue
* legal actions against you for any loss(es) or damage(s) caused by your
* failure to do so.
*
*********************************************************************
*/
#include <unistd.h>

#include "logger.h"
#include "sample_liveview.h"

using namespace edge_sdk;
using namespace edge_app;

ErrorCode ESDKInit();

int main(int argc, char **argv) {
auto rc = ESDKInit();
if (rc != kOk) {
ERROR("pre init failed");
return -1;
}

auto payload_quality = atoi(argv[1]);
auto fpv_quality = atoi(argv[2]);

while (argc < 3 || payload_quality > 5 || fpv_quality > 5) {
ERROR(
"Usage: %s [PAYLOAD_QUOLITY] [FPV_QUALITY] [SOURCE] \nDESCRIPTION:\n "
"QUALITY: 1-540p. 2-720p. 3-720pHigh. "
"4-1080p. 5-1080pHigh"
"\n SOURCE: 1-wide 2-zoom 3-IR \n eg: \n %s 1 3 1",
argv[0], argv[0]);
sleep(1);
}

// create payload liveview sample
auto payload_liveview_sample = std::make_shared<LiveviewSample>(std::string("PayloadCamera"));

StreamDecoder::Options decoder_option = {.name = std::string("ffmpeg")};
auto payload_stream_decoder = CreateStreamDecoder(decoder_option);

ImageProcessor::Options payload_image_processor_option = {.name = std::string("display"),
.alias = "PayloadCamera", .userdata = payload_liveview_sample};

auto payload_image_processor = CreateImageProcessor(payload_image_processor_option);

if (0 != InitLiveviewSample(
payload_liveview_sample, Liveview::kCameraTypePayload, (Liveview::StreamQuality)payload_quality,
payload_stream_decoder, payload_image_processor)) {
ERROR("Init liveview sample failed");
} else {
payload_liveview_sample->Start();
}

// create fpv liveview sample
auto fpv_liveview_sample = std::make_shared<LiveviewSample>(std::string("FPV"));

auto fpv_stream_decoder = CreateStreamDecoder(decoder_option);

ImageProcessor::Options fpv_image_processor_option = {.name = std::string("display"),
.alias = "FPVCamera", .userdata = fpv_liveview_sample};

auto fpv_image_processor = CreateImageProcessor(fpv_image_processor_option);

if (0 != InitLiveviewSample(
fpv_liveview_sample, Liveview::kCameraTypeFpv, (Liveview::StreamQuality)fpv_quality,
fpv_stream_decoder, fpv_image_processor)) {
ERROR("Init liveview sample failed");
} else {
fpv_liveview_sample->Start();
}

if (argc == 4) {
auto src = atoi(argv[3]);
INFO("set camera soure: %d", src);
payload_liveview_sample->SetCameraSource((edge_sdk::Liveview::CameraSource)src);
}

while (1) sleep(3);

return 0;
}
Loading

0 comments on commit e33d457

Please sign in to comment.