From 1b2c2434e832f4769c5d2971508bc030bb283a1b Mon Sep 17 00:00:00 2001 From: Rajat Singhal Date: Wed, 13 Apr 2022 09:06:40 +0530 Subject: [PATCH] Use CameraDefaults settings for all cameras --- AirLib/include/common/AirSimSettings.hpp | 56 ++++++++++++++---------- 1 file changed, 32 insertions(+), 24 deletions(-) diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index 25108b4b7d..7977813ad4 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -193,6 +193,8 @@ namespace airlib std::map pixel_format_override_settings; }; + using CaptureSettingsMap = std::map; + using NoiseSettingsMap = std::map; struct CameraSetting { //nan means keep the default values set in components @@ -200,8 +202,8 @@ namespace airlib Rotation rotation = Rotation::nanRotation(); GimbalSetting gimbal; - std::map capture_settings; - std::map noise_settings; + CaptureSettingsMap capture_settings; + NoiseSettingsMap noise_settings; UnrealEngineSetting ue_setting; @@ -211,6 +213,7 @@ namespace airlib initializeNoiseSettings(noise_settings); } }; + using CameraSettingMap = std::map; struct CameraDirectorSetting { @@ -271,7 +274,7 @@ namespace airlib Vector3r position = VectorMath::nanVector(); //in global NED Rotation rotation = Rotation::nanRotation(); - std::map cameras; + CameraSettingMap cameras; std::map> sensors; RCSettings rc; @@ -411,7 +414,7 @@ namespace airlib std::string speed_unit_label = "m\\s"; std::map> sensor_defaults; Vector3r wind = Vector3r::Zero(); - std::map external_cameras; + CameraSettingMap external_cameras; std::string settings_text_ = ""; @@ -446,8 +449,8 @@ namespace airlib loadPawnPaths(settings_json, pawn_paths); loadOtherSettings(settings_json); loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults); - loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults); - loadExternalCameraSettings(settings_json, external_cameras); + loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults, camera_defaults); + loadExternalCameraSettings(settings_json, external_cameras, camera_defaults); //this should be done last because it depends on vehicles (and/or their type) we have loadRecordingSetting(settings_json); @@ -706,7 +709,7 @@ namespace airlib } } - static void initializeCaptureSettings(std::map& capture_settings) + static void initializeCaptureSettings(CaptureSettingsMap& capture_settings) { capture_settings.clear(); for (int i = -1; i < Utils::toNumeric(ImageType::Count); ++i) { @@ -715,9 +718,10 @@ namespace airlib capture_settings.at(Utils::toNumeric(ImageType::Scene)).target_gamma = CaptureSetting::kSceneTargetGamma; } - static void loadCaptureSettings(const Settings& settings_json, std::map& capture_settings) + static void loadCaptureSettings(const Settings& settings_json, CaptureSettingsMap& capture_settings) { - initializeCaptureSettings(capture_settings); + // We don't call initializeCaptureSettings here since it's already called in CameraSettings constructor + // And to avoid overwriting any defaults already set from CameraDefaults Settings json_parent; if (settings_json.getChild("CaptureSettings", json_parent)) { @@ -801,7 +805,8 @@ namespace airlib static std::unique_ptr createVehicleSetting(const std::string& simmode_name, const Settings& settings_json, const std::string vehicle_name, - std::map>& sensor_defaults) + std::map>& sensor_defaults, + const CameraSetting& camera_defaults) { auto vehicle_type = Utils::toLower(settings_json.getString("VehicleType", "")); @@ -843,7 +848,7 @@ namespace airlib vehicle_setting->position = createVectorSetting(settings_json, vehicle_setting->position); vehicle_setting->rotation = createRotationSetting(settings_json, vehicle_setting->rotation); - loadCameraSettings(settings_json, vehicle_setting->cameras); + loadCameraSettings(settings_json, vehicle_setting->cameras, camera_defaults); loadSensorSettings(settings_json, "Sensors", vehicle_setting->sensors, sensor_defaults); return vehicle_setting; @@ -887,7 +892,8 @@ namespace airlib static void loadVehicleSettings(const std::string& simmode_name, const Settings& settings_json, std::map>& vehicles, - std::map>& sensor_defaults) + std::map>& sensor_defaults, + const CameraSetting& camera_defaults) { createDefaultVehicle(simmode_name, vehicles, sensor_defaults); @@ -903,7 +909,7 @@ namespace airlib for (const auto& key : keys) { msr::airlib::Settings child; vehicles_child.getChild(key, child); - vehicles[key] = createVehicleSetting(simmode_name, child, key, sensor_defaults); + vehicles[key] = createVehicleSetting(simmode_name, child, key, sensor_defaults, camera_defaults); } } } @@ -978,7 +984,7 @@ namespace airlib } } - static void initializeNoiseSettings(std::map& noise_settings) + static void initializeNoiseSettings(NoiseSettingsMap& noise_settings) { const int image_count = Utils::toNumeric(ImageType::Count); noise_settings.clear(); @@ -986,9 +992,10 @@ namespace airlib noise_settings[i] = NoiseSetting(); } - static void loadNoiseSettings(const Settings& settings_json, std::map& noise_settings) + static void loadNoiseSettings(const Settings& settings_json, NoiseSettingsMap& noise_settings) { - initializeNoiseSettings(noise_settings); + // We don't call initializeNoiseSettings here since it's already called in CameraSettings constructor + // And to avoid overwriting any defaults already set from CameraDefaults Settings json_parent; if (settings_json.getChild("NoiseSettings", json_parent)) { @@ -1003,7 +1010,7 @@ namespace airlib } } - static void loadNoiseSetting(const msr::airlib::Settings& settings_json, NoiseSetting& noise_setting) + static void loadNoiseSetting(const Settings& settings_json, NoiseSetting& noise_setting) { noise_setting.Enabled = settings_json.getBool("Enabled", noise_setting.Enabled); noise_setting.ImageType = settings_json.getInt("ImageType", noise_setting.ImageType); @@ -1058,9 +1065,9 @@ namespace airlib } } - static CameraSetting createCameraSetting(const Settings& settings_json) + static CameraSetting createCameraSetting(const Settings& settings_json, const CameraSetting& camera_defaults) { - CameraSetting setting; + CameraSetting setting = camera_defaults; setting.position = createVectorSetting(settings_json, setting.position); setting.rotation = createRotationSetting(settings_json, setting.rotation); @@ -1076,7 +1083,8 @@ namespace airlib return setting; } - static void loadCameraSettings(const Settings& settings_json, std::map& cameras) + static void loadCameraSettings(const Settings& settings_json, CameraSettingMap& cameras, + const CameraSetting& camera_defaults) { cameras.clear(); @@ -1088,7 +1096,7 @@ namespace airlib for (const auto& key : keys) { msr::airlib::Settings child; json_parent.getChild(key, child); - cameras[key] = createCameraSetting(child); + cameras[key] = createCameraSetting(child, camera_defaults); } } } @@ -1201,7 +1209,7 @@ namespace airlib { Settings child_json; if (settings_json.getChild("CameraDefaults", child_json)) { - camera_defaults = createCameraSetting(child_json); + camera_defaults = createCameraSetting(child_json, camera_defaults); } } @@ -1377,7 +1385,7 @@ namespace airlib createDefaultSensorSettings(simmode_name, sensors); } - static void loadExternalCameraSettings(const Settings& settings_json, std::map& external_cameras) + static void loadExternalCameraSettings(const Settings& settings_json, CameraSettingMap& external_cameras, const CameraSetting& camera_defaults) { external_cameras.clear(); @@ -1389,7 +1397,7 @@ namespace airlib for (const auto& key : keys) { Settings child; json_parent.getChild(key, child); - external_cameras[key] = createCameraSetting(child); + external_cameras[key] = createCameraSetting(child, camera_defaults); } } }