diff --git a/PythonClient/multirotor/high_res_camera.py b/PythonClient/multirotor/high_res_camera.py new file mode 100644 index 0000000000..151383f444 --- /dev/null +++ b/PythonClient/multirotor/high_res_camera.py @@ -0,0 +1,61 @@ +import airsim +from datetime import datetime + +''' +Simple script with settings to create a high-resolution camera, and fetching it + +Settings used- +{ + "SettingsVersion": 1.2, + "SimMode": "Multirotor", + "Vehicles" : { + "Drone1" : { + "VehicleType" : "SimpleFlight", + "AutoCreate" : true, + "Cameras" : { + "high_res": { + "CaptureSettings" : [ + { + "ImageType" : 0, + "Width" : 4320, + "Height" : 2160 + } + ], + "X": 0.50, "Y": 0.00, "Z": 0.10, + "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0 + }, + "low_res": { + "CaptureSettings" : [ + { + "ImageType" : 0, + "Width" : 256, + "Height" : 144 + } + ], + "X": 0.50, "Y": 0.00, "Z": 0.10, + "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0 + } + } + } + } +} +''' + +client = airsim.VehicleClient() +client.confirmConnection() +framecounter = 1 + +prevtimestamp = datetime.now() + +while(framecounter <= 500): + if framecounter%150 == 0: + client.simGetImages([airsim.ImageRequest("high_res", airsim.ImageType.Scene, False, False)]) + print("High resolution image captured.") + + if framecounter%30 == 0: + now = datetime.now() + print(f"Time spent for 30 frames: {now-prevtimestamp}") + prevtimestamp = now + + client.simGetImages([airsim.ImageRequest("low_res", airsim.ImageType.Scene, False, False)]) + framecounter += 1 diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index 735298788c..b87ad3749a 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -86,6 +86,8 @@ void APIPCamera::BeginPlay() msr::airlib::ProjectionMatrix APIPCamera::getProjectionMatrix(const APIPCamera::ImageType image_type) const { + msr::airlib::ProjectionMatrix mat; + //TODO: avoid the need to override const cast here const_cast(this)->setCameraTypeEnabled(image_type, true); const USceneCaptureComponent2D* capture = const_cast(this)->getCaptureComponent(image_type, false); @@ -161,18 +163,17 @@ msr::airlib::ProjectionMatrix APIPCamera::getProjectionMatrix(const APIPCamera:: FMatrix projMatTransposeInAirSim = coordinateChangeTranspose * proj_mat_transpose; //Copy the result to an airlib::ProjectionMatrix while taking transpose. - msr::airlib::ProjectionMatrix mat; for (auto row = 0; row < 4; ++row) for (auto col = 0; col < 4; ++col) mat.matrix[col][row] = projMatTransposeInAirSim.M[row][col]; - - return mat; } - else { - msr::airlib::ProjectionMatrix mat; + else mat.setTo(Utils::nan()); - return mat; - } + + // Disable camera after our work is done + const_cast(this)->setCameraTypeEnabled(image_type, false); + + return mat; } void APIPCamera::Tick(float DeltaTime) diff --git a/Unreal/Plugins/AirSim/Source/UnrealImageCapture.cpp b/Unreal/Plugins/AirSim/Source/UnrealImageCapture.cpp index da28a1795f..6b034f81df 100644 --- a/Unreal/Plugins/AirSim/Source/UnrealImageCapture.cpp +++ b/Unreal/Plugins/AirSim/Source/UnrealImageCapture.cpp @@ -112,6 +112,10 @@ void UnrealImageCapture::getSceneCaptureImage(const std::vectorwidth; response.height = render_results[i]->height; response.image_type = request.image_type; + + // Disable camera after fetching images + APIPCamera* camera = cameras_->at(request.camera_name); + camera->setCameraTypeEnabled(request.image_type, false); } }