Skip to content

Commit

Permalink
added safer screenshot code (not working yet), scene capture setting …
Browse files Browse the repository at this point in the history
…tweak
  • Loading branch information
sytelus committed Jul 9, 2017
1 parent ebc5e36 commit 210c1ba
Show file tree
Hide file tree
Showing 9 changed files with 82 additions and 31 deletions.
8 changes: 7 additions & 1 deletion Examples/StereoImageGenerator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,9 +68,12 @@ class StereoImageGenerator {
const std::vector<ImageResponse>& response = client.simGetImages(request);
if (response.size() != 3) {
std::cout << "Images were not recieved!" << std::endl;
start_nanos = clock->nowNanos();
continue;
}

auto render_time = clock->elapsedSince(start_nanos);

std::string left_file_name = Utils::stringf("left_%06d.png", sample);
std::string right_file_name = Utils::stringf("right_%06d.png", sample);
std::string disparity_file_name = Utils::stringf("disparity_%06d.pfm", sample);
Expand Down Expand Up @@ -98,7 +101,10 @@ class StereoImageGenerator {

file_list << left_file_name << "," << right_file_name << "," << disparity_file_name << std::endl;

std::cout << "Image #" << sample << " done in " << (clock->nowNanos() - start_nanos) / 1.0E6f << "ms" << std::endl;
std::cout << "Image #" << sample
<< " done in " << (clock->elapsedSince(start_nanos)) * 1E3f << "ms"
<< " render time " << render_time * 1E3f << " ms"
<< std::endl;

pose_generator.next();
}
Expand Down
6 changes: 4 additions & 2 deletions HelloDrone/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <chrono>
#include "rpc/RpcLibClient.hpp"
#include "controllers/DroneControllerBase.hpp"
#include "common/common_utils/FileSystem.hpp"
STRICT_MODE_OFF
#ifndef RPCLIB_MSGPACK
#define RPCLIB_MSGPACK clmdep_msgpack
Expand All @@ -24,12 +25,13 @@ int main()
typedef DroneControllerBase::ImageRequest ImageRequest;
typedef VehicleCameraBase::ImageResponse ImageResponse;
typedef VehicleCameraBase::ImageType_ ImageType_;
typedef common_utils::FileSystem FileSystem;

try {
client.confirmConnection();

std::cout << "Press Enter to get FPV image" << std::endl; std::cin.get();
vector<ImageRequest> request = { ImageRequest(0, ImageType_::Scene), ImageRequest(1, ImageType_::Scene) };
vector<ImageRequest> request = { ImageRequest(0, ImageType_::Scene), ImageRequest(1, ImageType_::Depth) };
const vector<ImageResponse>& response = client.simGetImages(request);
std::cout << "# of images recieved: " << response.size() << std::endl;

Expand All @@ -41,7 +43,7 @@ int main()
for (const ImageResponse& image_info : response) {
std::cout << "Image size: " << image_info.image_data.size() << std::endl;
if (path != "") {
std::ofstream file(path + std::to_string(image_info.time_stamp) , std::ios::binary);
std::ofstream file(FileSystem::combine(path, std::to_string(image_info.time_stamp) + ".png"), std::ios::binary);
file.write((char*) image_info.image_data.data(), image_info.image_data.size());
file.close();
}
Expand Down
4 changes: 4 additions & 0 deletions Unreal/Plugins/AirSim/Source/PIPCamera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@ void APIPCamera::BeginPlay()
{
Super::BeginPlay();

screen_capture_->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR;
depth_capture_->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR;
seg_capture_->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR;

scene_render_target_ = NewObject<UTextureRenderTarget2D>();
scene_render_target_->InitAutoFormat(960, 540); //256 X 144, X 480
//scene_render_target_->bHDR = false;
Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/RecordingThread.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ uint32 FRecordingThread::Run()
UTextureRenderTarget2D* renderTarget = capture->TextureTarget;
if (renderTarget != nullptr) {
TArray<uint8> image_data;
RenderRequest request;
RenderRequest request(false);
int width, height;
request.getScreenshot(renderTarget, image_data, false, true, width, height);
SaveImage(image_data);
Expand Down
68 changes: 47 additions & 21 deletions Unreal/Plugins/AirSim/Source/RenderRequest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,10 @@
#include "ImageUtils.h"
#include "RenderRequest.h"

RenderRequest::RenderRequest()
RenderRequest::RenderRequest(bool use_safe_method)
{
data = std::make_shared<RenderRequestInfo>();
}
RenderRequest::RenderRequest(RenderRequest& other) {
data = other.data;
data->use_safe_method = use_safe_method;
}
RenderRequest::~RenderRequest()
{
Expand All @@ -30,12 +28,31 @@ void RenderRequest::getScreenshot(UTextureRenderTarget2D* renderTarget, TArray<u
//make sure we are not on the rendering thread
CheckNotBlockedOnRenderThread();

// Queue up the task of rendering the scene in the render thread
TGraphTask<RenderRequest>::CreateTask().ConstructAndDispatchWhenReady(*this);
if (data->use_safe_method) {
//TODO: below doesn't work right now because it must be running in game thread
FIntPoint size;
if (!data->pixels_as_float) {
//below is documented method but more expensive because it forces flush
FTextureRenderTargetResource* rt_resource = data->render_target->GameThread_GetRenderTargetResource();
auto flags = setupRenderResource(rt_resource, data.get(), size);
rt_resource->ReadPixels(data->bmp, flags);
}
else {
FTextureRenderTargetResource* rt_resource = data->render_target->GetRenderTargetResource();
setupRenderResource(rt_resource, data.get(), size);
rt_resource->ReadFloat16Pixels(data->bmp_float);
}
}
else {
//wait for render thread to pick up our task

// Queue up the task of rendering the scene in the render thread
TGraphTask<RenderRequest>::CreateTask().ConstructAndDispatchWhenReady(*this);

// wait for this task to complete
if (!data->signal.waitFor(5)) {
throw std::runtime_error("timeout waiting for screenshot");
// wait for this task to complete
if (!data->signal.waitFor(5)) {
throw std::runtime_error("timeout waiting for screenshot");
}
}

width = data->width;
Expand Down Expand Up @@ -65,32 +82,40 @@ void RenderRequest::getScreenshot(UTextureRenderTarget2D* renderTarget, TArray<u
}
}

FReadSurfaceDataFlags RenderRequest::setupRenderResource(FTextureRenderTargetResource* rt_resource, RenderRequestInfo* data, FIntPoint& size)
{
size = rt_resource->GetSizeXY();
data->width = size.X;
data->height = size.Y;
FReadSurfaceDataFlags flags(RCM_UNorm, CubeFace_MAX);
flags.SetLinearToGamma(false);

return flags;
}

void RenderRequest::ExecuteTask()
{
if (data != nullptr)
{
try {
FRHICommandListImmediate& RHICmdList = GetImmediateCommandList_ForRenderCommand();
auto resource = data->render_target->GetRenderTargetResource();
if (resource != nullptr) {
const FTexture2DRHIRef& textureRef = resource->GetRenderTargetTexture();
auto size = resource->GetSizeXY();
data->width = size.X;
data->height = size.Y;
FReadSurfaceDataFlags flags(RCM_UNorm, CubeFace_MAX);
flags.SetLinearToGamma(false);
auto rt_resource = data->render_target->GetRenderTargetResource();
if (rt_resource != nullptr) {
const FTexture2DRHIRef& rhi_texture = rt_resource->GetRenderTargetTexture();
FIntPoint size;
auto flags = setupRenderResource(rt_resource, data.get(), size);

if (!data->pixels_as_float) {
//below is undocumented method that avoids flushing, but it seems to segfault every 2000 or so calls
RHICmdList.ReadSurfaceData(
textureRef,
rhi_texture,
FIntRect(0, 0, size.X, size.Y),
data->bmp,
flags
);
flags);
}
else {
RHICmdList.ReadSurfaceFloatData(
textureRef,
rhi_texture,
FIntRect(0, 0, size.X, size.Y),
data->bmp_float,
CubeFace_PosX, 0, 0
Expand All @@ -99,6 +124,7 @@ void RenderRequest::ExecuteTask()
}
}
catch (std::exception& e) {
//TODO: use this!
unused(e);
}
data->signal.signal();
Expand Down
9 changes: 7 additions & 2 deletions Unreal/Plugins/AirSim/Source/RenderRequest.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

class RenderRequest : public FRenderCommand
{
private:
struct RenderRequestInfo {
TArray<FColor> bmp;
TArray<FFloat16Color> bmp_float;
Expand All @@ -14,11 +15,15 @@ class RenderRequest : public FRenderCommand
msr::airlib::WorkerThreadSignal signal;
bool pixels_as_float;
bool compress;
bool use_safe_method;
};
std::shared_ptr<RenderRequestInfo> data;

private:
static FReadSurfaceDataFlags RenderRequest::setupRenderResource(FTextureRenderTargetResource* rt_resource, RenderRequestInfo* data, FIntPoint& size);

public:
RenderRequest();
RenderRequest(RenderRequest& other);
RenderRequest(bool use_safe_method);
~RenderRequest();

void DoTask(ENamedThreads::Type CurrentThread, const FGraphEventRef& MyCompletionGraphEvent)
Expand Down
8 changes: 8 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimHUD/SimHUD.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,17 @@ void ASimHUD::BeginPlay()
{
Super::BeginPlay();

//TODO: should we only do below on SceneCapture2D components and cameras?
//avoid motion blur so capture images don't get
GetWorld()->GetGameViewport()->GetEngineShowFlags()->SetMotionBlur(false);

//Equivalent to enabling Custom Stencil in Project > Settings > Rendering > Postprocessing
UKismetSystemLibrary::ExecuteConsoleCommand(GetWorld(), FString("r.CustomDepth 3"));

//above is not working so below is alternate method
static const auto custom_depth_var = IConsoleManager::Get().FindConsoleVariable(TEXT("r.CustomDepth"));
custom_depth_var->Set(3);

//create main widget
if (widget_class_ != nullptr) {
widget_ = CreateWidget<USimHUDWidget>(this->GetOwningPlayerController(), widget_class_);
Expand Down
6 changes: 3 additions & 3 deletions Unreal/Plugins/AirSim/Source/VehicleCameraConnector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ msr::airlib::VehicleCameraBase::ImageResponse VehicleCameraConnector::getImage(V
return response;
}

return getSceneCaptureImage(image_type, pixels_as_float, compress);
return getSceneCaptureImage(image_type, pixels_as_float, compress, false);
}

msr::airlib::VehicleCameraBase::ImageResponse VehicleCameraConnector::getSceneCaptureImage(VehicleCameraConnector::ImageType image_type, bool pixels_as_float, bool compress)
msr::airlib::VehicleCameraBase::ImageResponse VehicleCameraConnector::getSceneCaptureImage(VehicleCameraConnector::ImageType image_type, bool pixels_as_float, bool compress, bool use_safe_method)
{
bool visibilityChanged = false;
if ((camera_->getEnableCameraTypes() & image_type) == ImageType_::None
Expand Down Expand Up @@ -64,7 +64,7 @@ msr::airlib::VehicleCameraBase::ImageResponse VehicleCameraConnector::getSceneCa
UTextureRenderTarget2D* textureTarget = capture->TextureTarget;

TArray<uint8> image;
RenderRequest request;
RenderRequest request(use_safe_method);
int width, height;
request.getScreenshot(textureTarget, image, pixels_as_float, compress, width, height);

Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/VehicleCameraConnector.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class VehicleCameraConnector : public VehicleCameraBase
virtual ImageResponse getImage(ImageType image_type, bool pixels_as_float, bool compress) override;

private:
msr::airlib::VehicleCameraBase::ImageResponse getSceneCaptureImage(ImageType image_type, bool pixels_as_float, bool compress);
msr::airlib::VehicleCameraBase::ImageResponse getSceneCaptureImage(ImageType image_type, bool pixels_as_float, bool compress, bool use_safe_method);

void addScreenCaptureHandler(UWorld *world);
bool getScreenshotScreen(ImageType image_type, std::vector<uint8_t>& compressedPng);
Expand Down

0 comments on commit 210c1ba

Please sign in to comment.