diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index febc97574e..9262120796 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -74,10 +74,10 @@ namespace airlib int simGetSegmentationObjectID(const std::string& mesh_name) const; void simPrintLogMessage(const std::string& message, std::string message_param = "", unsigned char severity = 0); - void simAddDetectionFilterMeshName(const std::string& camera_name, const std::string& mesh_name, const std::string& vehicle_name = ""); - void simSetDetectionFilterRadius(const std::string& camera_name, const float radius_cm, const std::string& vehicle_name = ""); - void simClearDetectionMeshNames(const std::string& camera_name, const std::string& vehicle_name = ""); - vector simGetDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& vehicle_name = ""); + void simAddDetectionFilterMeshName(const std::string& camera_name, const std::string& mesh_name, const std::string& vehicle_name = "", bool external = false); + void simSetDetectionFilterRadius(const std::string& camera_name, const float radius_cm, const std::string& vehicle_name = "", bool external = false); + void simClearDetectionMeshNames(const std::string& camera_name, const std::string& vehicle_name = "", bool external = false); + vector simGetDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& vehicle_name = "", bool external = false); void simFlushPersistentMarkers(); void simPlotPoints(const vector& points, const vector& color_rgba, float size, float duration, bool is_persistent); @@ -108,8 +108,8 @@ namespace airlib void simSetVehiclePose(const Pose& pose, bool ignore_collision, const std::string& vehicle_name = ""); void simSetTraceLine(const std::vector& color_rgba, float thickness = 3.0f, const std::string& vehicle_name = ""); - vector simGetImages(vector request, const std::string& vehicle_name = ""); - vector simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name = ""); + vector simGetImages(vector request, const std::string& vehicle_name = "", bool external = false); + vector simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name = "", bool external = false); bool simTestLineOfSightToPoint(const msr::airlib::GeoPoint& point, const std::string& vehicle_name = ""); bool simTestLineOfSightBetweenPoints(const msr::airlib::GeoPoint& point1, const msr::airlib::GeoPoint& point2); @@ -120,13 +120,12 @@ namespace airlib CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const; - CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const; - void simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name = ""); - std::vector simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name = ""); - void simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = ""); - void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = ""); - // This is a backwards-compatibility wrapper over simSetCameraPose, and can be removed in future major releases - void simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation, const std::string& vehicle_name = ""); + CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "", bool external = false) const; + void simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name = "", bool external = false); + std::vector simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name = "", bool external = false); + void simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = "", bool external = false); + void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = "", bool external = false); + bool simCreateVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file); msr::airlib::Kinematics::State simGetGroundTruthKinematics(const std::string& vehicle_name = "") const; msr::airlib::Environment::State simGetGroundTruthEnvironment(const std::string& vehicle_name = "") const; @@ -152,4 +151,5 @@ namespace airlib }; } } //namespace + #endif diff --git a/AirLib/include/api/VehicleSimApiBase.hpp b/AirLib/include/api/VehicleSimApiBase.hpp index 410393d58c..ffa329ec6e 100644 --- a/AirLib/include/api/VehicleSimApiBase.hpp +++ b/AirLib/include/api/VehicleSimApiBase.hpp @@ -49,9 +49,6 @@ namespace airlib virtual void initialize() = 0; - virtual std::vector getImages(const std::vector& request) const = 0; - virtual std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const = 0; - virtual bool testLineOfSightToPoint(const GeoPoint& point) const = 0; virtual Pose getPose() const = 0; @@ -59,12 +56,6 @@ namespace airlib virtual const Kinematics::State* getGroundTruthKinematics() const = 0; virtual const msr::airlib::Environment* getGroundTruthEnvironment() const = 0; - virtual CameraInfo getCameraInfo(const std::string& camera_name) const = 0; - virtual void setCameraPose(const std::string& camera_name, const Pose& pose) = 0; - virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) = 0; - virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) = 0; - virtual std::vector getDistortionParams(const std::string& camera_name) = 0; - virtual CollisionInfo getCollisionInfo() const = 0; virtual int getRemoteControlID() const = 0; //which RC to use, 0 is first one, -1 means disable RC (use keyborad) virtual RCData getRCData() const = 0; //get reading from RC from simulator's host OS @@ -73,11 +64,6 @@ namespace airlib virtual void toggleTrace() = 0; virtual void setTraceLine(const std::vector& color_rgba, float thickness) = 0; - virtual void addDetectionFilterMeshName(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& mesh_name) = 0; - virtual void setDetectionFilterRadius(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const float radius_cm) = 0; - virtual void clearDetectionMeshNames(const std::string& camera_name, ImageCaptureBase::ImageType image_type) = 0; - virtual std::vector getDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const = 0; - //use pointer here because of derived classes for VehicleSetting const AirSimSettings::VehicleSetting* getVehicleSetting() const { diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index 0ea0e3ed19..fdd1d184b7 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -5,7 +5,7 @@ #define air_WorldSimApiBase_hpp #include "common/CommonStructs.hpp" -#include "common/AirSimSettings.hpp" +#include "common/ImageCaptureBase.hpp" namespace msr { @@ -88,7 +88,24 @@ namespace airlib virtual bool testLineOfSightBetweenPoints(const msr::airlib::GeoPoint& point1, const msr::airlib::GeoPoint& point2) const = 0; virtual vector getWorldExtents() const = 0; + + // Camera APIs + virtual CameraInfo getCameraInfo(const CameraDetails& camera_details) const = 0; + virtual void setCameraPose(const msr::airlib::Pose& pose, const CameraDetails& camera_details) = 0; + virtual void setCameraFoV(float fov_degrees, const CameraDetails& camera_details) = 0; + virtual void setDistortionParam(const std::string& param_name, float value, const CameraDetails& camera_details) = 0; + virtual std::vector getDistortionParams(const CameraDetails& camera_details) const = 0; + + virtual std::vector getImages(const std::vector& requests, + const std::string& vehicle_name, bool external) const = 0; + virtual std::vector getImage(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) const = 0; + + virtual void addDetectionFilterMeshName(ImageCaptureBase::ImageType image_type, const std::string& mesh_name, const CameraDetails& camera_details) = 0; + virtual void setDetectionFilterRadius(ImageCaptureBase::ImageType image_type, float radius_cm, const CameraDetails& camera_details) = 0; + virtual void clearDetectionMeshNames(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) = 0; + virtual std::vector getDetections(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) = 0; }; } } //namespace + #endif diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index 366a8a2841..a54334bc9f 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -50,10 +50,16 @@ namespace airlib bool visible; std::string camera_name; std::string vehicle_name; - - SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, - bool visible_val = false, const std::string& camera_name_val = "", const std::string& vehicle_name_val = "") - : window_index(window_index_val), image_type(image_type_val), visible(visible_val), camera_name(camera_name_val), vehicle_name(vehicle_name_val) + bool external; + + SubwindowSetting(int window_index_val = 0, ImageType image_type_val = ImageType::Scene, bool visible_val = false, + const std::string& camera_name_val = "", const std::string& vehicle_name_val = "", bool external_val = false) + : window_index(window_index_val) + , image_type(image_type_val) + , visible(visible_val) + , camera_name(camera_name_val) + , vehicle_name(vehicle_name_val) + , external(external_val) { } }; @@ -393,6 +399,7 @@ namespace airlib std::string speed_unit_label = "m\\s"; std::map> sensor_defaults; Vector3r wind = Vector3r::Zero(); + std::map external_cameras; std::string settings_text_ = ""; @@ -428,6 +435,7 @@ namespace airlib loadOtherSettings(settings_json); loadDefaultSensorSettings(simmode_name, settings_json, sensor_defaults); loadVehicleSettings(simmode_name, settings_json, vehicles, sensor_defaults); + loadExternalCameraSettings(settings_json, external_cameras); //this should be done last because it depends on vehicles (and/or their type) we have loadRecordingSetting(settings_json); @@ -1088,6 +1096,7 @@ namespace airlib subwindow_setting.visible = json_settings_child.getBool("Visible", false); subwindow_setting.camera_name = getCameraName(json_settings_child); subwindow_setting.vehicle_name = json_settings_child.getString("VehicleName", ""); + subwindow_setting.external = json_settings_child.getBool("External", false); } } } @@ -1096,9 +1105,9 @@ namespace airlib static void initializeSubwindowSettings(std::vector& subwindow_settings) { subwindow_settings.clear(); - subwindow_settings.push_back(SubwindowSetting(0, ImageType::DepthVis, false, "", "")); //depth - subwindow_settings.push_back(SubwindowSetting(1, ImageType::Segmentation, false, "", "")); //seg - subwindow_settings.push_back(SubwindowSetting(2, ImageType::Scene, false, "", "")); //vis + subwindow_settings.push_back(SubwindowSetting(0, ImageType::DepthVis, false, "", "", false)); //depth + subwindow_settings.push_back(SubwindowSetting(1, ImageType::Segmentation, false, "", "", false)); //seg + subwindow_settings.push_back(SubwindowSetting(2, ImageType::Scene, false, "", "", false)); //vis } void loadOtherSettings(const Settings& settings_json) @@ -1327,7 +1336,25 @@ namespace airlib else createDefaultSensorSettings(simmode_name, sensors); } + + static void loadExternalCameraSettings(const Settings& settings_json, std::map& external_cameras) + { + external_cameras.clear(); + + Settings json_parent; + if (settings_json.getChild("ExternalCameras", json_parent)) { + std::vector keys; + json_parent.getChildNames(keys); + + for (const auto& key : keys) { + Settings child; + json_parent.getChild(key, child); + external_cameras[key] = createCameraSetting(child); + } + } + } }; } } //namespace + #endif diff --git a/AirLib/include/common/CommonStructs.hpp b/AirLib/include/common/CommonStructs.hpp index aa4b7fa2f9..bda9f85840 100644 --- a/AirLib/include/common/CommonStructs.hpp +++ b/AirLib/include/common/CommonStructs.hpp @@ -421,6 +421,28 @@ namespace airlib std::vector indices; std::string name; }; + + // This is a small helper struct to keep camera details together + // Not currently exposed to the client, just for cleaner codebase internally + struct CameraDetails + { + std::string camera_name; + std::string vehicle_name; + bool external; + + CameraDetails(const std::string& camera_name_val, const std::string& vehicle_name_val, bool external_val) + : camera_name(camera_name_val), vehicle_name(vehicle_name_val), external(external_val) + { + } + + std::string to_string() const + { + return Utils::stringf("CameraDetails: camera_name=%s, vehicle_name=%s, external=%d", + camera_name.c_str(), + vehicle_name.c_str(), + external); + } + }; } } //namespace #endif diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index e0b0c7ad9e..294ed98a6d 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -213,21 +213,21 @@ __pragma(warning(disable : 4239)) return pimpl_->client.call("simGetSegmentationObjectID", mesh_name).as(); } - void RpcLibClientBase::simAddDetectionFilterMeshName(const std::string& camera_name, const std::string& mesh_name, const std::string& vehicle_name) + void RpcLibClientBase::simAddDetectionFilterMeshName(const std::string& camera_name, const std::string& mesh_name, const std::string& vehicle_name, bool external) { - pimpl_->client.call("simAddDetectionFilterMeshName", camera_name, mesh_name, vehicle_name); + pimpl_->client.call("simAddDetectionFilterMeshName", camera_name, mesh_name, vehicle_name, external); } - void RpcLibClientBase::simSetDetectionFilterRadius(const std::string& camera_name, const float radius_cm, const std::string& vehicle_name) + void RpcLibClientBase::simSetDetectionFilterRadius(const std::string& camera_name, const float radius_cm, const std::string& vehicle_name, bool external) { - pimpl_->client.call("simSetDetectionFilterRadius", camera_name, radius_cm, vehicle_name); + pimpl_->client.call("simSetDetectionFilterRadius", camera_name, radius_cm, vehicle_name, external); } - void RpcLibClientBase::simClearDetectionMeshNames(const std::string& camera_name, const std::string& vehicle_name) + void RpcLibClientBase::simClearDetectionMeshNames(const std::string& camera_name, const std::string& vehicle_name, bool external) { - pimpl_->client.call("simClearDetectionMeshNames", camera_name, vehicle_name); + pimpl_->client.call("simClearDetectionMeshNames", camera_name, vehicle_name, external); } - vector RpcLibClientBase::simGetDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& vehicle_name) + vector RpcLibClientBase::simGetDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& vehicle_name, bool external) { - const auto& result = pimpl_->client.call("simGetDetections", camera_name, image_type, vehicle_name).as>(); + const auto& result = pimpl_->client.call("simGetDetections", camera_name, image_type, vehicle_name, external).as>(); return RpcLibAdaptorsBase::DetectionInfo::to(result); } @@ -251,18 +251,19 @@ __pragma(warning(disable : 4239)) pimpl_->client.call("simSetTraceLine", color_rgba, thickness, vehicle_name); } - vector RpcLibClientBase::simGetImages(vector request, const std::string& vehicle_name) + vector RpcLibClientBase::simGetImages(vector request, const std::string& vehicle_name, bool external) { const auto& response_adaptor = pimpl_->client.call("simGetImages", RpcLibAdaptorsBase::ImageRequest::from(request), - vehicle_name) + vehicle_name, + external) .as>(); return RpcLibAdaptorsBase::ImageResponse::to(response_adaptor); } - vector RpcLibClientBase::simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) + vector RpcLibClientBase::simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name, bool external) { - vector result = pimpl_->client.call("simGetImage", camera_name, type, vehicle_name).as>(); + vector result = pimpl_->client.call("simGetImage", camera_name, type, vehicle_name, external).as>(); if (result.size() == 1) { // rpclib has a bug with serializing empty vectors, so we return a 1 byte vector instead. result.clear(); @@ -435,36 +436,29 @@ __pragma(warning(disable : 4239)) return pimpl_->client.call("simSetObjectScale", object_name, RpcLibAdaptorsBase::Vector3r(scale)).as(); } - CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name) const + CameraInfo RpcLibClientBase::simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name, bool external) const { - return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name).as().to(); + return pimpl_->client.call("simGetCameraInfo", camera_name, vehicle_name, external).as().to(); } - void RpcLibClientBase::simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name) + void RpcLibClientBase::simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name, bool external) { - pimpl_->client.call("simSetCameraPose", camera_name, RpcLibAdaptorsBase::Pose(pose), vehicle_name); + pimpl_->client.call("simSetCameraPose", camera_name, RpcLibAdaptorsBase::Pose(pose), vehicle_name, external); } - void RpcLibClientBase::simSetCameraOrientation(const std::string& camera_name, const Quaternionr& orientation, const std::string& vehicle_name) + void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name, bool external) { - std::cout << "`simSetCameraOrientation` API has been upgraded to `simSetCameraPose`. Please update your code." << std::endl; - Pose pose{ Vector3r::Zero(), orientation }; - RpcLibClientBase::simSetCameraPose(camera_name, pose, vehicle_name); + pimpl_->client.call("simSetCameraFov", camera_name, fov_degrees, vehicle_name, external); } - void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name) + void RpcLibClientBase::simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name, bool external) { - pimpl_->client.call("simSetCameraFov", camera_name, fov_degrees, vehicle_name); + pimpl_->client.call("simSetDistortionParam", camera_name, param_name, value, vehicle_name, external); } - void RpcLibClientBase::simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name) + std::vector RpcLibClientBase::simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name, bool external) { - pimpl_->client.call("simSetDistortionParam", camera_name, param_name, value, vehicle_name); - } - - std::vector RpcLibClientBase::simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name) - { - return pimpl_->client.call("simGetDistortionParams", camera_name, vehicle_name).as>(); + return pimpl_->client.call("simGetDistortionParams", camera_name, vehicle_name, external).as>(); } msr::airlib::Kinematics::State RpcLibClientBase::simGetGroundTruthKinematics(const std::string& vehicle_name) const diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 6860aaa584..b566001a8d 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -144,13 +144,13 @@ namespace airlib return getWorldSimApi()->runConsoleCommand(command); }); - pimpl_->server.bind("simGetImages", [&](const std::vector& request_adapter, const std::string& vehicle_name) -> vector { - const auto& response = getVehicleSimApi(vehicle_name)->getImages(RpcLibAdaptorsBase::ImageRequest::to(request_adapter)); + pimpl_->server.bind("simGetImages", [&](const std::vector& request_adapter, const std::string& vehicle_name, bool external) -> vector { + const auto& response = getWorldSimApi()->getImages(RpcLibAdaptorsBase::ImageRequest::to(request_adapter), vehicle_name, external); return RpcLibAdaptorsBase::ImageResponse::from(response); }); - pimpl_->server.bind("simGetImage", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) -> vector { - return getVehicleSimApi(vehicle_name)->getImage(camera_name, type); + pimpl_->server.bind("simGetImage", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name, bool external) -> vector { + return getWorldSimApi()->getImage(type, CameraDetails(camera_name, vehicle_name, external)); }); pimpl_->server.bind("simTestLineOfSightToPoint", [&](const RpcLibAdaptorsBase::GeoPoint& point, const std::string& vehicle_name) -> bool { @@ -198,17 +198,17 @@ namespace airlib return getWorldSimApi()->getSegmentationObjectID(mesh_name); }); - pimpl_->server.bind("simAddDetectionFilterMeshName", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& mesh_name, const std::string& vehicle_name) -> void { - getVehicleSimApi(vehicle_name)->addDetectionFilterMeshName(camera_name, type, mesh_name); + pimpl_->server.bind("simAddDetectionFilterMeshName", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& mesh_name, const std::string& vehicle_name, bool external) -> void { + getWorldSimApi()->addDetectionFilterMeshName(type, mesh_name, CameraDetails(camera_name, vehicle_name, external)); }); - pimpl_->server.bind("simSetDetectionFilterRadius", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const float radius_cm, const std::string& vehicle_name) -> void { - getVehicleSimApi(vehicle_name)->setDetectionFilterRadius(camera_name, type, radius_cm); + pimpl_->server.bind("simSetDetectionFilterRadius", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const float radius_cm, const std::string& vehicle_name, bool external) -> void { + getWorldSimApi()->setDetectionFilterRadius(type, radius_cm, CameraDetails(camera_name, vehicle_name, external)); }); - pimpl_->server.bind("simClearDetectionMeshNames", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) -> void { - getVehicleSimApi(vehicle_name)->clearDetectionMeshNames(camera_name, type); + pimpl_->server.bind("simClearDetectionMeshNames", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name, bool external) -> void { + getWorldSimApi()->clearDetectionMeshNames(type, CameraDetails(camera_name, vehicle_name, external)); }); - pimpl_->server.bind("simGetDetections", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name) -> vector { - const auto& response = getVehicleSimApi(vehicle_name)->getDetections(camera_name, type); + pimpl_->server.bind("simGetDetections", [&](const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name, bool external) -> vector { + const auto& response = getWorldSimApi()->getDetections(type, CameraDetails(camera_name, vehicle_name, external)); return RpcLibAdaptorsBase::DetectionInfo::from(response); }); @@ -268,25 +268,25 @@ namespace airlib return RpcLibAdaptorsBase::DistanceSensorData(distance_sensor_data); }); - pimpl_->server.bind("simGetCameraInfo", [&](const std::string& camera_name, const std::string& vehicle_name) -> RpcLibAdaptorsBase::CameraInfo { - const auto& camera_info = getVehicleSimApi(vehicle_name)->getCameraInfo(camera_name); + pimpl_->server.bind("simGetCameraInfo", [&](const std::string& camera_name, const std::string& vehicle_name, bool external) -> RpcLibAdaptorsBase::CameraInfo { + const auto& camera_info = getWorldSimApi()->getCameraInfo(CameraDetails(camera_name, vehicle_name, external)); return RpcLibAdaptorsBase::CameraInfo(camera_info); }); - pimpl_->server.bind("simSetDistortionParam", [&](const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name) -> void { - getVehicleSimApi(vehicle_name)->setDistortionParam(camera_name, param_name, value); + pimpl_->server.bind("simSetDistortionParam", [&](const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name, bool external) -> void { + getWorldSimApi()->setDistortionParam(param_name, value, CameraDetails(camera_name, vehicle_name, external)); }); - pimpl_->server.bind("simGetDistortionParams", [&](const std::string& camera_name, const std::string& vehicle_name) -> std::vector { - return getVehicleSimApi(vehicle_name)->getDistortionParams(camera_name); + pimpl_->server.bind("simGetDistortionParams", [&](const std::string& camera_name, const std::string& vehicle_name, bool external) -> std::vector { + return getWorldSimApi()->getDistortionParams(CameraDetails(camera_name, vehicle_name, external)); }); - pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdaptorsBase::Pose& pose, const std::string& vehicle_name) -> void { - getVehicleSimApi(vehicle_name)->setCameraPose(camera_name, pose.to()); + pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdaptorsBase::Pose& pose, const std::string& vehicle_name, bool external) -> void { + getWorldSimApi()->setCameraPose(pose.to(), CameraDetails(camera_name, vehicle_name, external)); }); - pimpl_->server.bind("simSetCameraFov", [&](const std::string& camera_name, float fov_degrees, const std::string& vehicle_name) -> void { - getVehicleSimApi(vehicle_name)->setCameraFoV(camera_name, fov_degrees); + pimpl_->server.bind("simSetCameraFov", [&](const std::string& camera_name, float fov_degrees, const std::string& vehicle_name, bool external) -> void { + getWorldSimApi()->setCameraFoV(fov_degrees, CameraDetails(camera_name, vehicle_name, external)); }); pimpl_->server.bind("simGetCollisionInfo", [&](const std::string& vehicle_name) -> RpcLibAdaptorsBase::CollisionInfo { diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index e3e81125bc..d62054add8 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -220,7 +220,7 @@ def simSetWeatherParameter(self, param, val): # camera control # simGetImage returns compressed png in array of bytes # image_type uses one of the ImageType members - def simGetImage(self, camera_name, image_type, vehicle_name = ''): + def simGetImage(self, camera_name, image_type, vehicle_name = '', external = False): """ Get a single image @@ -232,6 +232,7 @@ def simGetImage(self, camera_name, image_type, vehicle_name = ''): camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used image_type (ImageType): Type of image required vehicle_name (str, optional): Name of the vehicle with the camera + external (bool, optional): Whether the camera is an External Camera Returns: Binary string literal of compressed png image @@ -240,7 +241,7 @@ def simGetImage(self, camera_name, image_type, vehicle_name = ''): camera_name = str(camera_name) # because this method returns std::vector, msgpack decides to encode it as a string unfortunately. - result = self.client.call('simGetImage', camera_name, image_type, vehicle_name) + result = self.client.call('simGetImage', camera_name, image_type, vehicle_name, external) if (result == "" or result == "\0"): return None return result @@ -248,7 +249,7 @@ def simGetImage(self, camera_name, image_type, vehicle_name = ''): # camera control # simGetImage returns compressed png in array of bytes # image_type uses one of the ImageType members - def simGetImages(self, requests, vehicle_name = ''): + def simGetImages(self, requests, vehicle_name = '', external = False): """ Get multiple images @@ -257,11 +258,12 @@ def simGetImages(self, requests, vehicle_name = ''): Args: requests (list[ImageRequest]): Images required vehicle_name (str, optional): Name of vehicle associated with the camera + external (bool, optional): Whether the camera is an External Camera Returns: list[ImageResponse]: """ - responses_raw = self.client.call('simGetImages', requests, vehicle_name) + responses_raw = self.client.call('simGetImages', requests, vehicle_name, external) return [ImageResponse.from_msgpack(response_raw) for response_raw in responses_raw] def simTestLineOfSightToPoint(self, point, vehicle_name = ''): @@ -508,7 +510,7 @@ def simGetSegmentationObjectID(self, mesh_name): """ return self.client.call('simGetSegmentationObjectID', mesh_name) - def simAddDetectionFilterMeshName(self, camera_name, image_type, mesh_name, vehicle_name = ''): + def simAddDetectionFilterMeshName(self, camera_name, image_type, mesh_name, vehicle_name = '', external = False): """ Add mesh name to detect in wild card format @@ -519,11 +521,12 @@ def simAddDetectionFilterMeshName(self, camera_name, image_type, mesh_name, vehi image_type (ImageType): Type of image required mesh_name (str): mesh name in wild card format vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera """ - self.client.call('simAddDetectionFilterMeshName', camera_name, image_type, mesh_name, vehicle_name) + self.client.call('simAddDetectionFilterMeshName', camera_name, image_type, mesh_name, vehicle_name, external) - def simSetDetectionFilterRadius(self, camera_name, image_type, radius_cm, vehicle_name = ''): + def simSetDetectionFilterRadius(self, camera_name, image_type, radius_cm, vehicle_name = '', external = False): """ Set detection radius for all cameras @@ -532,10 +535,11 @@ def simSetDetectionFilterRadius(self, camera_name, image_type, radius_cm, vehicl image_type (ImageType): Type of image required radius_cm (int): Radius in [cm] vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera """ - self.client.call('simSetDetectionFilterRadius', camera_name, image_type, radius_cm, vehicle_name) + self.client.call('simSetDetectionFilterRadius', camera_name, image_type, radius_cm, vehicle_name, external) - def simClearDetectionMeshNames(self, camera_name, image_type, vehicle_name = ''): + def simClearDetectionMeshNames(self, camera_name, image_type, vehicle_name = '', external = False): """ Clear all mesh names from detection filter @@ -543,11 +547,12 @@ def simClearDetectionMeshNames(self, camera_name, image_type, vehicle_name = '') camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used image_type (ImageType): Type of image required vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera """ - self.client.call('simClearDetectionMeshNames', camera_name, image_type, vehicle_name) + self.client.call('simClearDetectionMeshNames', camera_name, image_type, vehicle_name, external) - def simGetDetections(self, camera_name, image_type, vehicle_name = ''): + def simGetDetections(self, camera_name, image_type, vehicle_name = '', external = False): """ Get current detections @@ -555,11 +560,12 @@ def simGetDetections(self, camera_name, image_type, vehicle_name = ''): camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used image_type (ImageType): Type of image required vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera Returns: DetectionInfo array """ - responses_raw = self.client.call('simGetDetections', camera_name, image_type, vehicle_name) + responses_raw = self.client.call('simGetDetections', camera_name, image_type, vehicle_name, external) return [DetectionInfo.from_msgpack(response_raw) for response_raw in responses_raw] def simPrintLogMessage(self, message, message_param = "", severity = 0): @@ -579,35 +585,37 @@ def simPrintLogMessage(self, message, message_param = "", severity = 0): """ self.client.call('simPrintLogMessage', message, message_param, severity) - def simGetCameraInfo(self, camera_name, vehicle_name = ''): + def simGetCameraInfo(self, camera_name, vehicle_name = '', external=False): """ Get details about the camera Args: camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera Returns: CameraInfo: """ # TODO: below str() conversion is only needed for legacy reason and should be removed in future - return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name)) + return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name, external)) - def simGetDistortionParams(self, camera_name, vehicle_name = ''): + def simGetDistortionParams(self, camera_name, vehicle_name = '', external = False): """ Get camera distortion parameters Args: camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera Returns: List (float): List of distortion parameter values corresponding to K1, K2, K3, P1, P2 respectively. """ - return self.client.call('simGetDistortionParams', str(camera_name), vehicle_name) + return self.client.call('simGetDistortionParams', str(camera_name), vehicle_name, external) - def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = ''): + def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = '', external = False): """ Set camera distortion parameters @@ -616,12 +624,13 @@ def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = distortion_params (dict): Dictionary of distortion param names and corresponding values {"K1": 0.0, "K2": 0.0, "K3": 0.0, "P1": 0.0, "P2": 0.0} vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera """ for param_name, value in distortion_params.items(): - self.client.call('simSetDistortionParam', str(camera_name), param_name, value, vehicle_name) + self.simSetDistortionParam(camera_name, param_name, value, vehicle_name, external) - def simSetDistortionParam(self, camera_name, param_name, value, vehicle_name = ''): + def simSetDistortionParam(self, camera_name, param_name, value, vehicle_name = '', external = False): """ Set single camera distortion parameter @@ -630,10 +639,11 @@ def simSetDistortionParam(self, camera_name, param_name, value, vehicle_name = ' param_name (str): Name of distortion parameter value (float): Value of distortion parameter vehicle_name (str, optional): Vehicle which the camera is associated with + external (bool, optional): Whether the camera is an External Camera """ - self.client.call('simSetDistortionParam', str(camera_name), param_name, value, vehicle_name) + self.client.call('simSetDistortionParam', str(camera_name), param_name, value, vehicle_name, external) - def simSetCameraPose(self, camera_name, pose, vehicle_name = ''): + def simSetCameraPose(self, camera_name, pose, vehicle_name = '', external = False): """ - Control the pose of a selected camera @@ -641,28 +651,12 @@ def simSetCameraPose(self, camera_name, pose, vehicle_name = ''): camera_name (str): Name of the camera to be controlled pose (Pose): Pose representing the desired position and orientation of the camera vehicle_name (str, optional): Name of vehicle which the camera corresponds to + external (bool, optional): Whether the camera is an External Camera """ # TODO: below str() conversion is only needed for legacy reason and should be removed in future - self.client.call('simSetCameraPose', str(camera_name), pose, vehicle_name) + self.client.call('simSetCameraPose', str(camera_name), pose, vehicle_name, external) - def simSetCameraOrientation(self, camera_name, orientation, vehicle_name = ''): - """ - .. note:: - - This API has been upgraded to `simSetCameraPose` - - - Control the Orientation of a selected camera - - Args: - camera_name (str): Name of the camera to be controlled - orientation (Quaternionr): Quaternion representing the desired orientation of the camera - vehicle_name (str, optional): Name of vehicle which the camera corresponds to - """ - logging.warning("`simSetCameraOrientation` API has been upgraded to `simSetCameraPose`. Please update your code.") - pose = Pose(orientation_val=orientation) - self.simSetCameraPose(camera_name, pose, vehicle_name) - - def simSetCameraFov(self, camera_name, fov_degrees, vehicle_name = ''): + def simSetCameraFov(self, camera_name, fov_degrees, vehicle_name = '', external = False): """ - Control the field of view of a selected camera @@ -670,9 +664,10 @@ def simSetCameraFov(self, camera_name, fov_degrees, vehicle_name = ''): camera_name (str): Name of the camera to be controlled fov_degrees (float): Value of field of view in degrees vehicle_name (str, optional): Name of vehicle which the camera corresponds to + external (bool, optional): Whether the camera is an External Camera """ # TODO: below str() conversion is only needed for legacy reason and should be removed in future - self.client.call('simSetCameraFov', str(camera_name), fov_degrees, vehicle_name) + self.client.call('simSetCameraFov', str(camera_name), fov_degrees, vehicle_name, external) def simGetGroundTruthKinematics(self, vehicle_name = ''): """ diff --git a/PythonClient/computer_vision/external_camera.py b/PythonClient/computer_vision/external_camera.py new file mode 100644 index 0000000000..b41a072cba --- /dev/null +++ b/PythonClient/computer_vision/external_camera.py @@ -0,0 +1,102 @@ +import setup_path +import airsim +import os +import tempfile + +""" +A simple script to test all the camera APIs. Change the camera name and whether it's an external camera + +Example Settings for external camera - + +{ + "SettingsVersion": 1.2, + "SimMode": "Car", + "ExternalCameras": { + "fixed1": { + "X": 0, "Y": 0, "Z": -5, + "Pitch": -90, "Roll": 0, "Yaw": 0 + } + } +} +""" + +# Just change the below to test different cameras easily! +CAM_NAME = "fixed1" +IS_EXTERNAL_CAM = True + + +client = airsim.VehicleClient() +client.confirmConnection() + +tmp_dir = os.path.join(tempfile.gettempdir(), "airsim_cv_mode") +print ("Saving images to %s" % tmp_dir) +try: + os.makedirs(tmp_dir) +except OSError: + if not os.path.isdir(tmp_dir): + raise + +print(f"Camera: {CAM_NAME}, External = {IS_EXTERNAL_CAM}") + +# Test Camera info +cam_info = client.simGetCameraInfo(CAM_NAME, external=IS_EXTERNAL_CAM) +print(cam_info) + +# Test Image APIs +airsim.wait_key('Press any key to get images') + +requests = [airsim.ImageRequest(CAM_NAME, airsim.ImageType.Scene), + airsim.ImageRequest(CAM_NAME, airsim.ImageType.DepthPlanar), + airsim.ImageRequest(CAM_NAME, airsim.ImageType.DepthVis), + airsim.ImageRequest(CAM_NAME, airsim.ImageType.Segmentation), + airsim.ImageRequest(CAM_NAME, airsim.ImageType.SurfaceNormals)] + +def save_images(responses, prefix = ""): + for i, response in enumerate(responses): + filename = os.path.join(tmp_dir, prefix + "_" + str(i)) + + if response.pixels_as_float: + print(f"Type {response.image_type}, size {len(response.image_data_float)}, pos {response.camera_position}") + airsim.write_pfm(os.path.normpath(filename + '.pfm'), airsim.get_pfm_array(response)) + else: + print(f"Type {response.image_type}, size {len(response.image_data_uint8)}, pos {response.camera_position}") + airsim.write_file(os.path.normpath(filename + '.png'), response.image_data_uint8) + + +responses = client.simGetImages(requests, external=IS_EXTERNAL_CAM) +save_images(responses, "old_fov") + + +# Test FoV API +airsim.wait_key('Press any key to change FoV and get images') + +client.simSetCameraFov(CAM_NAME, 120, external=IS_EXTERNAL_CAM) + +responses = client.simGetImages(requests, external = IS_EXTERNAL_CAM) +save_images(responses, "new_fov") + +new_cam_info = client.simGetCameraInfo(CAM_NAME, external=IS_EXTERNAL_CAM) +print(f"Old FOV: {cam_info.fov}, New FOV: {new_cam_info.fov}") + + +# Test Pose APIs +new_pose = airsim.Pose(airsim.Vector3r(-10, -5, -5), airsim.to_quaternion(0.1, 0, 0.1)) +client.simSetCameraPose(CAM_NAME, new_pose, external=IS_EXTERNAL_CAM) + +responses = client.simGetImages(requests, external=IS_EXTERNAL_CAM) +save_images(responses, "new_pose") + +new_cam_info = client.simGetCameraInfo(CAM_NAME, external=IS_EXTERNAL_CAM) +print(f"Old Pose: {cam_info.pose}, New Pose: {new_cam_info.pose}") + + +# Test Distortion params APIs +dist_params = client.simGetDistortionParams(CAM_NAME, external=IS_EXTERNAL_CAM) +print(f"Distortion Params: {dist_params}") + +new_params_dict = {"K1": 0.1, "K2": 0.01, "K3": 0.0, "P1": 0.0, "P2": 0.0} +print(f"Setting distortion params as {new_params_dict}") +client.simSetDistortionParams(CAM_NAME, new_params_dict, external=IS_EXTERNAL_CAM) + +dist_params = client.simGetDistortionParams(CAM_NAME, external=IS_EXTERNAL_CAM) +print(f"Updated Distortion Params: {dist_params}") diff --git a/PythonClient/detection/detection.py b/PythonClient/detection/detection.py index 528941ca9a..388228826a 100644 --- a/PythonClient/detection/detection.py +++ b/PythonClient/detection/detection.py @@ -5,7 +5,7 @@ import pprint # connect to the AirSim simulator -client = airsim.MultirotorClient() +client = airsim.VehicleClient() client.confirmConnection() # set camera name and image type to request images and detections @@ -40,4 +40,4 @@ client.simClearDetectionMeshNames(camera_name, image_type) elif cv2.waitKey(1) & 0xFF == ord('a'): client.simAddDetectionFilterMeshName(camera_name, image_type, "Cylinder*") -cv2.destroyAllWindows() \ No newline at end of file +cv2.destroyAllWindows() diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp index c48a995b36..b51084e70d 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp @@ -59,50 +59,6 @@ void PawnSimApi::pawnTick(float dt) updateRendering(dt); } -void PawnSimApi::addDetectionFilterMeshName(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& mesh_name) -{ - unused(camera_name); - unused(image_type); - unused(mesh_name); - - throw std::invalid_argument(common_utils::Utils::stringf( - "addDetectionFilterMeshName is not supported on unity") - .c_str()); -} - -void PawnSimApi::setDetectionFilterRadius(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const float radius_cm) -{ - unused(camera_name); - unused(image_type); - unused(radius_cm); - - throw std::invalid_argument(common_utils::Utils::stringf( - "setDetectionFilterRadius is not supported on unity") - .c_str()); -} - -void PawnSimApi::clearDetectionMeshNames(const std::string& camera_name, ImageCaptureBase::ImageType image_type) -{ - unused(camera_name); - unused(image_type); - - throw std::invalid_argument(common_utils::Utils::stringf( - "clearDetectionMeshNames is not supported on unity") - .c_str()); -} - -std::vector PawnSimApi::getDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const -{ - unused(camera_name); - unused(image_type); - - throw std::invalid_argument(common_utils::Utils::stringf( - "getDetections is not supported on unity") - .c_str()); - - return std::vector(); -} - bool PawnSimApi::testLineOfSightToPoint(const msr::airlib::GeoPoint& point) const { unused(point); @@ -135,25 +91,6 @@ const NedTransform& PawnSimApi::getNedTransform() const return ned_transform_; } -std::vector PawnSimApi::getImages( - const std::vector& requests) const -{ - std::vector responses; - const ImageCaptureBase* camera = getImageCapture(); - camera->getImages(requests, responses); - return responses; -} - -std::vector PawnSimApi::getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const -{ - std::vector request = { ImageCaptureBase::ImageRequest(camera_name, image_type) }; - const std::vector& response = getImages(request); - if (response.size() > 0) - return response.at(0).image_data_uint8; - else - return std::vector(); -} - msr::airlib::RCData PawnSimApi::getRCData() const { AirSimRCData rcDataFromUnity = GetRCData(getVehicleName().c_str()); @@ -249,43 +186,6 @@ void PawnSimApi::allowPassthroughToggleInput() PrintLogMessage("enable_passthrough_on_collisions: ", state_.passthrough_enabled ? "true" : "false", params_.vehicle_name.c_str(), ErrorLogSeverity::Information); } -msr::airlib::CameraInfo PawnSimApi::getCameraInfo(const std::string& camera_name) const -{ - AirSimCameraInfo airsim_camera_info = GetCameraInfo(camera_name.c_str(), params_.vehicle_name.c_str()); // Into Unity - msr::airlib::CameraInfo camera_info; - camera_info.pose.position.x() = airsim_camera_info.pose.position.x; - camera_info.pose.position.y() = airsim_camera_info.pose.position.y; - camera_info.pose.position.z() = airsim_camera_info.pose.position.z; - camera_info.pose.orientation.x() = airsim_camera_info.pose.orientation.x; - camera_info.pose.orientation.y() = airsim_camera_info.pose.orientation.y; - camera_info.pose.orientation.z() = airsim_camera_info.pose.orientation.z; - camera_info.pose.orientation.w() = airsim_camera_info.pose.orientation.w; - camera_info.fov = airsim_camera_info.fov; - return camera_info; -} - -void PawnSimApi::setCameraPose(const std::string& camera_name, const msr::airlib::Pose& pose) -{ - SetCameraPose(camera_name.c_str(), UnityUtilities::Convert_to_AirSimPose(pose), params_.vehicle_name.c_str()); -} - -void PawnSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees) -{ - SetCameraFoV(camera_name.c_str(), fov_degrees, params_.vehicle_name.c_str()); -} - -void PawnSimApi::setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) -{ - // not implemented -} - -std::vector PawnSimApi::getDistortionParams(const std::string& camera_name) -{ - // not implemented - std::vector params(5, 0.0); - return params; -} - //parameters in NED frame PawnSimApi::Pose PawnSimApi::getPose() const { @@ -371,4 +271,4 @@ void PawnSimApi::updateKinematics(float dt) next_kinematics.accelerations.angular = (next_kinematics.twist.angular - kinematics_->getTwist().angular) / dt; kinematics_->setState(next_kinematics); kinematics_->update(); -} \ No newline at end of file +} diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h index e9a9528a9b..83cb525bf8 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h @@ -29,7 +29,6 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase typedef msr::airlib::Utils Utils; typedef msr::airlib::AirSimSettings::VehicleSetting VehicleSetting; typedef msr::airlib::ImageCaptureBase ImageCaptureBase; - typedef msr::airlib::DetectionInfo DetectionInfo; public: struct Params @@ -70,15 +69,10 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase virtual void resetImplementation() override; virtual void update() override; virtual const UnityImageCapture* getImageCapture() const override; - virtual std::vector getImages(const std::vector& request) const override; - virtual std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const override; + virtual Pose getPose() const override; virtual void setPose(const Pose& pose, bool ignore_collision) override; - virtual msr::airlib::CameraInfo getCameraInfo(const std::string& camera_name) const override; - virtual void setCameraPose(const std::string& camera_name, const Pose& pose) override; - virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override; - virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) override; - virtual std::vector getDistortionParams(const std::string& camera_name) override; + virtual CollisionInfo getCollisionInfo() const override; virtual int getRemoteControlID() const override; virtual msr::airlib::RCData getRCData() const override; @@ -98,11 +92,6 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase const NedTransform& getNedTransform() const; virtual void pawnTick(float dt); - virtual void addDetectionFilterMeshName(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& mesh_name) override; - virtual void setDetectionFilterRadius(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const float radius_cm) override; - virtual void clearDetectionMeshNames(const std::string& camera_name, ImageCaptureBase::ImageType image_type) override; - virtual std::vector getDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const override; - virtual bool testLineOfSightToPoint(const msr::airlib::GeoPoint& point) const override; private: @@ -129,4 +118,4 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase std::unique_ptr kinematics_; std::unique_ptr environment_; -}; \ No newline at end of file +}; diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp index 29cf286d6f..66a7e021b3 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp @@ -266,4 +266,111 @@ std::vector WorldSimApi::getWorldExtents() const return result; } +msr::airlib::CameraInfo WorldSimApi::getCameraInfo(const CameraDetails& camera_details) const +{ + if (camera_details.external) + throw std::invalid_argument(common_utils::Utils::stringf("external field is not supported on Unity Image APIs").c_str()); + + AirSimCameraInfo airsim_camera_info = GetCameraInfo(camera_details.camera_name.c_str(), camera_details.vehicle_name.c_str()); // Into Unity + msr::airlib::CameraInfo camera_info; + camera_info.pose = UnityUtilities::Convert_to_Pose(airsim_camera_info.pose); + camera_info.fov = airsim_camera_info.fov; + return camera_info; +} + +void WorldSimApi::setCameraPose(const msr::airlib::Pose& pose, const CameraDetails& camera_details) +{ + if (camera_details.external) + throw std::invalid_argument(common_utils::Utils::stringf("external field is not supported on Unity Image APIs").c_str()); + + SetCameraPose(camera_details.camera_name.c_str(), UnityUtilities::Convert_to_AirSimPose(pose), camera_details.vehicle_name.c_str()); +} + +void WorldSimApi::setCameraFoV(float fov_degrees, const CameraDetails& camera_details) +{ + if (camera_details.external) + throw std::invalid_argument(common_utils::Utils::stringf("external field is not supported on Unity Image APIs").c_str()); + + SetCameraFoV(camera_details.camera_name.c_str(), fov_degrees, camera_details.vehicle_name.c_str()); +} + +void WorldSimApi::setDistortionParam(const std::string& param_name, float value, const CameraDetails& camera_details) +{ + throw std::invalid_argument(common_utils::Utils::stringf("setDistortionParam is not supported on unity").c_str()); +} + +std::vector WorldSimApi::getDistortionParams(const CameraDetails& camera_details) const +{ + throw std::invalid_argument(common_utils::Utils::stringf("getDistortionParams is not supported on unity").c_str()); + + std::vector params(5, 0.0); + return params; +} + +std::vector WorldSimApi::getImages( + const std::vector& requests, const std::string& vehicle_name, bool external) const +{ + std::vector responses; + const ImageCaptureBase* camera = simmode_->getVehicleSimApi(vehicle_name)->getImageCapture(); + camera->getImages(requests, responses); + return responses; +} + +std::vector WorldSimApi::getImage(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) const +{ + std::vector request{ + ImageCaptureBase::ImageRequest(camera_details.camera_name, image_type) + }; + + const auto& response = getImages(request, camera_details.vehicle_name, camera_details.external); + if (response.size() > 0) + return response.at(0).image_data_uint8; + else + return std::vector(); +} + +void WorldSimApi::addDetectionFilterMeshName(ImageCaptureBase::ImageType image_type, const std::string& mesh_name, const CameraDetails& camera_details) +{ + unused(camera_details); + unused(image_type); + unused(mesh_name); + + throw std::invalid_argument(common_utils::Utils::stringf( + "addDetectionFilterMeshName is not supported on unity") + .c_str()); +} + +void WorldSimApi::setDetectionFilterRadius(ImageCaptureBase::ImageType image_type, float radius_cm, const CameraDetails& camera_details) +{ + unused(camera_details); + unused(image_type); + unused(radius_cm); + + throw std::invalid_argument(common_utils::Utils::stringf( + "setDetectionFilterRadius is not supported on unity") + .c_str()); +} + +void WorldSimApi::clearDetectionMeshNames(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) +{ + unused(camera_details); + unused(image_type); + + throw std::invalid_argument(common_utils::Utils::stringf( + "clearDetectionMeshNames is not supported on unity") + .c_str()); +} + +std::vector WorldSimApi::getDetections(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) +{ + unused(camera_details); + unused(image_type); + + throw std::invalid_argument(common_utils::Utils::stringf( + "getDetections is not supported on unity") + .c_str()); + + return std::vector(); +} + #pragma endregion diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h index 45d0f678b8..02f7b64881 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h @@ -1,7 +1,7 @@ #pragma once #include "api/WorldSimApiBase.hpp" -#include "./SimMode/SimModeBase.h" +#include "SimMode/SimModeBase.h" #include "AirSimStructs.hpp" class WorldSimApi : public msr::airlib::WorldSimApiBase @@ -10,6 +10,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase typedef msr::airlib::Pose Pose; typedef msr::airlib::Vector3r Vector3r; typedef msr::airlib::MeshPositionVertexBuffersResponse MeshPositionVertexBuffersResponse; + typedef msr::airlib::ImageCaptureBase ImageCaptureBase; + typedef msr::airlib::CameraDetails CameraDetails; WorldSimApi(SimModeBase* simmode, std::string vehicle_name); virtual ~WorldSimApi(); @@ -72,6 +74,22 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase virtual bool testLineOfSightBetweenPoints(const msr::airlib::GeoPoint& point1, const msr::airlib::GeoPoint& point2) const override; virtual std::vector getWorldExtents() const override; + // Camera APIs + virtual msr::airlib::CameraInfo getCameraInfo(const CameraDetails& camera_details) const override; + virtual void setCameraPose(const msr::airlib::Pose& pose, const CameraDetails& camera_details) override; + virtual void setCameraFoV(float fov_degrees, const CameraDetails& camera_details) override; + virtual void setDistortionParam(const std::string& param_name, float value, const CameraDetails& camera_details) override; + virtual std::vector getDistortionParams(const CameraDetails& camera_details) const override; + + virtual std::vector getImages(const std::vector& requests, + const std::string& vehicle_name, bool external) const override; + virtual std::vector getImage(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) const override; + + virtual void addDetectionFilterMeshName(ImageCaptureBase::ImageType image_type, const std::string& mesh_name, const CameraDetails& camera_details) override; + virtual void setDetectionFilterRadius(ImageCaptureBase::ImageType image_type, float radius_cm, const CameraDetails& camera_details) override; + virtual void clearDetectionMeshNames(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) override; + virtual std::vector getDetections(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) override; + private: SimModeBase* simmode_; std::string vehicle_name_; diff --git a/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp b/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp index adb3582594..2e1def652a 100644 --- a/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp +++ b/Unreal/Plugins/AirSim/Source/DetectionComponent.cpp @@ -186,3 +186,22 @@ FRotator UDetectionComponent::getRelativeRotation(FVector in_location, FRotator FTransform relative_object_transform = camera_transform.GetRelativeTransform(FTransform(in_rotation, in_location)); return relative_object_transform.Rotator(); } + +void UDetectionComponent::addMeshName(const std::string& mesh_name) +{ + FString name(mesh_name.c_str()); + + if (!object_filter_.wildcard_mesh_names_.Contains(name)) { + object_filter_.wildcard_mesh_names_.Add(name); + } +} + +void UDetectionComponent::setFilterRadius(const float radius_cm) +{ + max_distance_to_camera_ = radius_cm; +} + +void UDetectionComponent::clearMeshNames() +{ + object_filter_.wildcard_mesh_names_.Empty(); +} diff --git a/Unreal/Plugins/AirSim/Source/DetectionComponent.h b/Unreal/Plugins/AirSim/Source/DetectionComponent.h index 392447b6a7..6f0899af15 100644 --- a/Unreal/Plugins/AirSim/Source/DetectionComponent.h +++ b/Unreal/Plugins/AirSim/Source/DetectionComponent.h @@ -44,6 +44,10 @@ class AIRSIM_API UDetectionComponent : public USceneComponent const TArray& getDetections(); + void addMeshName(const std::string& mesh_name); + void setFilterRadius(const float radius_cm); + void clearMeshNames(); + private: bool calcBoundingFromViewInfo(AActor* actor, FBox2D& box_out); @@ -52,16 +56,16 @@ class AIRSIM_API UDetectionComponent : public USceneComponent FRotator getRelativeRotation(FVector in_location, FRotator in_rotation); public: + UPROPERTY() + UTextureRenderTarget2D* texture_target_; + +private: UPROPERTY() FObjectFilter object_filter_; UPROPERTY(EditAnywhere, Category = "Tracked Actors") float max_distance_to_camera_; - UPROPERTY() - UTextureRenderTarget2D* texture_target_; - -private: UPROPERTY() USceneCaptureComponent2D* scene_capture_component_2D_; diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index ec2080cf43..a4646b03dc 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -270,8 +270,10 @@ void APIPCamera::setCameraTypeEnabled(ImageType type, bool enabled) enableCaptureComponent(type, enabled); } -void APIPCamera::setCameraPose(const FTransform& pose) +void APIPCamera::setCameraPose(const msr::airlib::Pose& relative_pose) { + FTransform pose = ned_transform_->fromRelativeNed(relative_pose); + FVector position = pose.GetLocation(); this->SetActorRelativeLocation(pose.GetLocation()); @@ -294,6 +296,39 @@ void APIPCamera::setCameraFoV(float fov_degrees) camera_->SetFieldOfView(fov_degrees); } +msr::airlib::CameraInfo APIPCamera::getCameraInfo() const +{ + msr::airlib::CameraInfo camera_info; + + camera_info.pose.position = ned_transform_->toLocalNed(this->GetActorLocation()); + camera_info.pose.orientation = ned_transform_->toNed(this->GetActorRotation().Quaternion()); + camera_info.fov = camera_->FieldOfView; + camera_info.proj_mat = getProjectionMatrix(ImageType::Scene); + return camera_info; +} + +std::vector APIPCamera::getDistortionParams() const +{ + std::vector param_values(5, 0.0); + + auto getParamValue = [this](const auto& name, float& val) { + distortion_param_instance_->GetScalarParameterValue(FName(name), val); + }; + + getParamValue(TEXT("K1"), param_values[0]); + getParamValue(TEXT("K2"), param_values[1]); + getParamValue(TEXT("K3"), param_values[2]); + getParamValue(TEXT("P1"), param_values[3]); + getParamValue(TEXT("P2"), param_values[4]); + + return param_values; +} + +void APIPCamera::setDistortionParam(const std::string& param_name, float value) +{ + distortion_param_instance_->SetScalarParameterValue(FName(param_name.c_str()), value); +} + void APIPCamera::setupCameraFromSettings(const APIPCamera::CameraSetting& camera_setting, const NedTransform& ned_transform) { //TODO: should we be ignoring position and orientation settings here? diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.h b/Unreal/Plugins/AirSim/Source/PIPCamera.h index a85fe80217..17780bcdb2 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.h +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.h @@ -41,11 +41,14 @@ class AIRSIM_API APIPCamera : public ACameraActor void setCameraTypeEnabled(ImageType type, bool enabled); bool getCameraTypeEnabled(ImageType type) const; - void setupCameraFromSettings(const APIPCamera::CameraSetting& camera_setting, const NedTransform& ned_transform); - void setCameraPose(const FTransform& pose); + void setupCameraFromSettings(const CameraSetting& camera_setting, const NedTransform& ned_transform); + void setCameraPose(const msr::airlib::Pose& relative_pose); void setCameraFoV(float fov_degrees); + msr::airlib::CameraInfo getCameraInfo() const; + std::vector getDistortionParams() const; + void setDistortionParam(const std::string& param_name, float value); - msr::airlib::ProjectionMatrix getProjectionMatrix(const APIPCamera::ImageType image_type) const; + msr::airlib::ProjectionMatrix getProjectionMatrix(const ImageType image_type) const; USceneCaptureComponent2D* getCaptureComponent(const ImageType type, bool if_active); UTextureRenderTarget2D* getRenderTarget(const ImageType type, bool if_active); @@ -53,12 +56,12 @@ class AIRSIM_API APIPCamera : public ACameraActor msr::airlib::Pose getPose() const; +private: //members UPROPERTY() UMaterialParameterCollection* distortion_param_collection_; UPROPERTY() UMaterialParameterCollectionInstance* distortion_param_instance_; -private: //members UPROPERTY() TArray captures_; UPROPERTY() diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp b/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp index 24a46b7ecb..f5c6a71adb 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp @@ -130,9 +130,7 @@ void PawnSimApi::createCamerasFromSettings() const auto& setting = camera_setting_pair.second; //get pose - FVector position = transform.fromLocalNed( - NedTransform::Vector3r(setting.position.x(), setting.position.y(), setting.position.z())) - - transform.fromLocalNed(NedTransform::Vector3r(0.0, 0.0, 0.0)); + FVector position = transform.fromLocalNed(setting.position) - transform.fromLocalNed(Vector3r::Zero()); FTransform camera_transform(FRotator(setting.rotation.pitch, setting.rotation.yaw, setting.rotation.roll), position, FVector(1., 1., 1.)); @@ -186,27 +184,6 @@ APawn* PawnSimApi::getPawn() return params_.pawn; } -std::vector PawnSimApi::getImages( - const std::vector& requests) const -{ - std::vector responses; - - const ImageCaptureBase* camera = getImageCapture(); - camera->getImages(requests, responses); - - return responses; -} - -std::vector PawnSimApi::getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const -{ - std::vector request = { ImageCaptureBase::ImageRequest(camera_name, image_type) }; - const std::vector& response = getImages(request); - if (response.size() > 0) - return response.at(0).image_data_uint8; - else - return std::vector(); -} - void PawnSimApi::setRCForceFeedback(float rumble_strength, float auto_center) { if (joystick_state_.is_initialized) { @@ -360,69 +337,6 @@ void PawnSimApi::reportState(msr::airlib::StateReporter& reporter) reporter.writeValue("unreal pos", Vector3r(unrealPosition.X, unrealPosition.Y, unrealPosition.Z)); } -void PawnSimApi::addDetectionFilterMeshName(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& mesh_name) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, image_type, mesh_name]() { - const APIPCamera* camera = getCamera(camera_name); - UDetectionComponent* detection_comp = camera->getDetectionComponent(image_type, false); - - FString name = FString(mesh_name.c_str()); - - if (!detection_comp->object_filter_.wildcard_mesh_names_.Contains(name)) { - detection_comp->object_filter_.wildcard_mesh_names_.Add(name); - } - }, - true); -} - -void PawnSimApi::clearDetectionMeshNames(const std::string& camera_name, ImageCaptureBase::ImageType image_type) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, image_type]() { - const APIPCamera* camera = getCamera(camera_name); - camera->getDetectionComponent(image_type, false)->object_filter_.wildcard_mesh_names_.Empty(); - }, - true); -} - -void PawnSimApi::setDetectionFilterRadius(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const float radius_cm) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, image_type, radius_cm]() { - const APIPCamera* camera = getCamera(camera_name); - camera->getDetectionComponent(image_type, false)->max_distance_to_camera_ = radius_cm; - }, - true); -} - -std::vector PawnSimApi::getDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const -{ - std::vector result; - - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, image_type, &result]() { - const APIPCamera* camera = getCamera(camera_name); - const TArray& detections = camera->getDetectionComponent(image_type, false)->getDetections(); - result.resize(detections.Num()); - - for (int i = 0; i < detections.Num(); i++) { - result[i].name = std::string(TCHAR_TO_UTF8(*(detections[i].Actor->GetFName().ToString()))); - - Vector3r nedWrtOrigin = ned_transform_.toGlobalNed(detections[i].Actor->GetActorLocation()); - result[i].geo_point = msr::airlib::EarthUtils::nedToGeodetic(nedWrtOrigin, - AirSimSettings::singleton().origin_geopoint); - - result[i].box2D.min = Vector2r(detections[i].Box2D.Min.X, detections[i].Box2D.Min.Y); - result[i].box2D.max = Vector2r(detections[i].Box2D.Max.X, detections[i].Box2D.Max.Y); - - result[i].box3D.min = ned_transform_.toLocalNed(detections[i].Box3D.Min); - result[i].box3D.max = ned_transform_.toLocalNed(detections[i].Box3D.Max); - - result[i].relative_pose = toPose(detections[i].RelativeTransform.GetTranslation(), detections[i].RelativeTransform.GetRotation()); - } - }, - true); - - return result; -} - //void playBack() //{ //if (params_.pawn->GetRootPrimitiveComponent()->IsAnySimulatingPhysics()) { @@ -501,62 +415,6 @@ void PawnSimApi::plot(std::istream& s, FColor color, const Vector3r& offset) } } -msr::airlib::CameraInfo PawnSimApi::getCameraInfo(const std::string& camera_name) const -{ - msr::airlib::CameraInfo camera_info; - - const APIPCamera* camera = getCamera(camera_name); - camera_info.pose.position = ned_transform_.toLocalNed(camera->GetActorLocation()); - camera_info.pose.orientation = ned_transform_.toNed(camera->GetActorRotation().Quaternion()); - camera_info.fov = camera->GetCameraComponent()->FieldOfView; - camera_info.proj_mat = camera->getProjectionMatrix(APIPCamera::ImageType::Scene); - return camera_info; -} - -void PawnSimApi::setCameraPose(const std::string& camera_name, const msr::airlib::Pose& pose) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, pose]() { - APIPCamera* camera = getCamera(camera_name); - FTransform pose_unreal = ned_transform_.fromRelativeNed(pose); - camera->setCameraPose(pose_unreal); - }, - true); -} - -void PawnSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, fov_degrees]() { - APIPCamera* camera = getCamera(camera_name); - camera->setCameraFoV(fov_degrees); - }, - true); -} - -void PawnSimApi::setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, param_name, value]() { - APIPCamera* camera = getCamera(camera_name); - camera->distortion_param_instance_->SetScalarParameterValue(FName(param_name.c_str()), value); - }, - true); -} - -std::vector PawnSimApi::getDistortionParams(const std::string& camera_name) -{ - std::vector param_values(5, 0.0); - UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, ¶m_values]() { - APIPCamera* camera = getCamera(camera_name); - camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("K1")), param_values[0]); - camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("K2")), param_values[1]); - camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("K3")), param_values[2]); - camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("P1")), param_values[3]); - camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("P2")), param_values[4]); - }, - true); - - return param_values; -} - //parameters in NED frame PawnSimApi::Pose PawnSimApi::getPose() const { @@ -705,4 +563,4 @@ std::string PawnSimApi::getRecordFileLine(bool is_header_line) const msr::airlib::VehicleApiBase* PawnSimApi::getVehicleApiBase() const { return nullptr; -} \ No newline at end of file +} diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.h b/Unreal/Plugins/AirSim/Source/PawnSimApi.h index a9f1d364c3..00a51f7bc6 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.h +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.h @@ -54,18 +54,18 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase } Params(APawn* pawn_val, const NedTransform* global_transform_val, PawnEvents* pawn_events_val, - const common_utils::UniqueValueMap cameras_val, UClass* pip_camera_class_val, - UParticleSystem* collision_display_template_val, const msr::airlib::GeoPoint home_geopoint_val, - std::string vehicle_name_val) + const common_utils::UniqueValueMap& cameras_val, UClass* pip_camera_class_val, + UParticleSystem* collision_display_template_val, const msr::airlib::GeoPoint& home_geopoint_val, + const std::string& vehicle_name_val) + : pawn(pawn_val) + , global_transform(global_transform_val) + , pawn_events(pawn_events_val) + , cameras(cameras_val) + , pip_camera_class(pip_camera_class_val) + , collision_display_template(collision_display_template_val) + , home_geopoint(home_geopoint_val) + , vehicle_name(vehicle_name_val) { - pawn = pawn_val; - global_transform = global_transform_val; - pawn_events = pawn_events_val; - cameras = cameras_val; - pip_camera_class = pip_camera_class_val; - collision_display_template = collision_display_template_val; - home_geopoint = home_geopoint_val; - vehicle_name = vehicle_name_val; } }; @@ -76,15 +76,8 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase virtual void update() override; virtual const UnrealImageCapture* getImageCapture() const override; - virtual std::vector getImages(const std::vector& request) const override; - virtual std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const override; virtual Pose getPose() const override; virtual void setPose(const Pose& pose, bool ignore_collision) override; - virtual msr::airlib::CameraInfo getCameraInfo(const std::string& camera_name) const override; - virtual void setCameraPose(const std::string& camera_name, const Pose& pose) override; - virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override; - virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) override; - virtual std::vector getDistortionParams(const std::string& camera_name) override; virtual CollisionInfo getCollisionInfo() const override; virtual int getRemoteControlID() const override; @@ -103,11 +96,6 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase virtual std::string getRecordFileLine(bool is_header_line) const override; virtual void reportState(msr::airlib::StateReporter& reporter) override; - virtual void addDetectionFilterMeshName(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& mesh_name) override; - virtual void setDetectionFilterRadius(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const float radius_cm) override; - virtual void clearDetectionMeshNames(const std::string& camera_name, ImageCaptureBase::ImageType image_type) override; - virtual std::vector getDetections(const std::string& camera_name, ImageCaptureBase::ImageType image_type) const override; - protected: //additional interface for derived class virtual void pawnTick(float dt); void setPoseInternal(const Pose& pose, bool ignore_collision); diff --git a/Unreal/Plugins/AirSim/Source/SimHUD/SimHUD.cpp b/Unreal/Plugins/AirSim/Source/SimHUD/SimHUD.cpp index 94f3500d07..71000329c0 100644 --- a/Unreal/Plugins/AirSim/Source/SimHUD/SimHUD.cpp +++ b/Unreal/Plugins/AirSim/Source/SimHUD/SimHUD.cpp @@ -332,22 +332,13 @@ void ASimHUD::initializeSubWindows() subwindow_cameras_[0] = subwindow_cameras_[1] = subwindow_cameras_[2] = nullptr; } - for (size_t window_index = 0; window_index < AirSimSettings::kSubwindowCount; ++window_index) { - - const auto& subwindow_setting = AirSimSettings::singleton().subwindow_settings.at(window_index); - auto vehicle_sim_api = simmode_->getVehicleSimApi(subwindow_setting.vehicle_name); - - if (vehicle_sim_api) { - if (vehicle_sim_api->getCamera(subwindow_setting.camera_name) != nullptr) - subwindow_cameras_[subwindow_setting.window_index] = vehicle_sim_api->getCamera(subwindow_setting.camera_name); - else - UAirBlueprintLib::LogMessageString("CameraID in element in settings.json is invalid", - std::to_string(window_index), - LogDebugLevel::Failure); - } + for (const auto& setting : getSubWindowSettings()) { + APIPCamera* camera = simmode_->getCamera(msr::airlib::CameraDetails(setting.camera_name, setting.vehicle_name, setting.external)); + if (camera) + subwindow_cameras_[setting.window_index] = camera; else - UAirBlueprintLib::LogMessageString("Vehicle in element in settings.json is invalid", - std::to_string(window_index), + UAirBlueprintLib::LogMessageString("Invalid Camera settings in element", + std::to_string(setting.window_index), LogDebugLevel::Failure); } } @@ -420,4 +411,4 @@ bool ASimHUD::readSettingsTextFromFile(const FString& settingsFilepath, std::str } return found; -} \ No newline at end of file +} diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index f374a0a45c..7502bee85b 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -459,6 +459,33 @@ void ASimModeBase::initializeCameraDirector(const FTransform& camera_transform, } } +void ASimModeBase::initializeExternalCameras() +{ + FActorSpawnParameters camera_spawn_params; + camera_spawn_params.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn; + const auto& transform = getGlobalNedTransform(); + + //for each camera in settings + for (const auto& camera_setting_pair : getSettings().external_cameras) { + const auto& setting = camera_setting_pair.second; + + //get pose + FVector position = transform.fromLocalNed(setting.position) - transform.fromLocalNed(Vector3r::Zero()); + FTransform camera_transform(FRotator(setting.rotation.pitch, setting.rotation.yaw, setting.rotation.roll), + position, + FVector(1., 1., 1.)); + + //spawn and attach camera to pawn + camera_spawn_params.Name = FName(("external_" + camera_setting_pair.first).c_str()); + APIPCamera* camera = this->GetWorld()->SpawnActor(pip_camera_class, camera_transform, camera_spawn_params); + + camera->setupCameraFromSettings(setting, transform); + + //add on to our collection + external_cameras_.insert_or_assign(camera_setting_pair.first, camera); + } +} + bool ASimModeBase::toggleRecording() { if (isRecording()) @@ -484,6 +511,17 @@ bool ASimModeBase::isRecording() const return FRecordingThread::isRecording(); } +const APIPCamera* ASimModeBase::getCamera(const msr::airlib::CameraDetails& camera_details) const +{ + return camera_details.external ? getExternalCamera(camera_details.camera_name) + : getVehicleSimApi(camera_details.vehicle_name)->getCamera(camera_details.camera_name); +} + +const UnrealImageCapture* ASimModeBase::getImageCapture(const std::string& vehicle_name, bool external) const +{ + return external ? external_image_capture_.get() : getVehicleSimApi(vehicle_name)->getImageCapture(); +} + //API server start/stop void ASimModeBase::startApiServer() { @@ -693,6 +731,10 @@ void ASimModeBase::setupVehiclesAndCamera() } } + // Create External Cameras + initializeExternalCameras(); + external_image_capture_ = std::make_unique(&external_cameras_); + if (getApiProvider()->hasDefaultVehicle()) { //TODO: better handle no FPV vehicles scenario getVehicleSimApi()->possess(); diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h index 1ec7126a9a..756f227d34 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -15,6 +15,7 @@ #include "PawnSimApi.h" #include "common/StateReporterWrapper.hpp" #include "LoadingScreenWidget.h" +#include "UnrealImageCapture.h" #include "SimModeBase.generated.h" DECLARE_DYNAMIC_MULTICAST_DELEGATE(FLevelLoaded); @@ -92,6 +93,31 @@ class AIRSIM_API ASimModeBase : public AActor return static_cast(api_provider_->getVehicleSimApi(vehicle_name)); } + const APIPCamera* getExternalCamera(const std::string& camera_name) const + { + return external_cameras_.findOrDefault(camera_name, nullptr); + } + + APIPCamera* getExternalCamera(const std::string& camera_name) + { + return const_cast( + static_cast(this)->getExternalCamera(camera_name)); + } + + const APIPCamera* getCamera(const msr::airlib::CameraDetails& camera_details) const; + + APIPCamera* getCamera(const msr::airlib::CameraDetails& camera_details) + { + return const_cast(static_cast(this)->getCamera(camera_details)); + } + + const UnrealImageCapture* getExternalImageCapture() const + { + return external_image_capture_.get(); + } + + const UnrealImageCapture* getImageCapture(const std::string& vehicle_name = "", bool external = false) const; + TMap asset_map; TMap scene_object_map; @@ -121,9 +147,10 @@ class AIRSIM_API ASimModeBase : public AActor void initializeCameraDirector(const FTransform& camera_transform, float follow_distance); void checkVehicleReady(); //checks if vehicle is available to use virtual void updateDebugReport(msr::airlib::StateReporterWrapper& debug_reporter); + virtual void initializeExternalCameras(); protected: //Utility methods for derived classes - virtual const msr::airlib::AirSimSettings& getSettings() const; + virtual const AirSimSettings& getSettings() const; FRotator toFRotator(const AirSimSettings::Rotation& rotation, const FRotator& default_val); protected: @@ -174,6 +201,8 @@ class AIRSIM_API ASimModeBase : public AActor msr::airlib::StateReporterWrapper debug_reporter_; std::vector> vehicle_sim_apis_; + common_utils::UniqueValueMap external_cameras_; + std::unique_ptr external_image_capture_; UPROPERTY() TArray spawned_actors_; //keep refs alive from Unreal GC diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 841630531e..d1f1b2f001 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -729,4 +729,146 @@ std::vector WorldSimApi::getWorldExtents() const result.push_back(lla_max_out); return result; -} \ No newline at end of file +} + +msr::airlib::CameraInfo WorldSimApi::getCameraInfo(const CameraDetails& camera_details) const +{ + msr::airlib::CameraInfo info; + const APIPCamera* camera = simmode_->getCamera(camera_details); + UAirBlueprintLib::RunCommandOnGameThread([camera, &info]() { + info = camera->getCameraInfo(); + }, + true); + + return info; +} + +void WorldSimApi::setCameraPose(const msr::airlib::Pose& pose, const CameraDetails& camera_details) +{ + APIPCamera* camera = simmode_->getCamera(camera_details); + UAirBlueprintLib::RunCommandOnGameThread([camera, &pose]() { + camera->setCameraPose(pose); + }, + true); +} + +void WorldSimApi::setCameraFoV(float fov_degrees, const CameraDetails& camera_details) +{ + APIPCamera* camera = simmode_->getCamera(camera_details); + UAirBlueprintLib::RunCommandOnGameThread([camera, &fov_degrees]() { + camera->setCameraFoV(fov_degrees); + }, + true); +} + +void WorldSimApi::setDistortionParam(const std::string& param_name, float value, const CameraDetails& camera_details) +{ + APIPCamera* camera = simmode_->getCamera(camera_details); + UAirBlueprintLib::RunCommandOnGameThread([camera, ¶m_name, &value]() { + camera->setDistortionParam(param_name, value); + }, + true); +} + +std::vector WorldSimApi::getDistortionParams(const CameraDetails& camera_details) const +{ + std::vector param_values; + const APIPCamera* camera = simmode_->getCamera(camera_details); + UAirBlueprintLib::RunCommandOnGameThread([camera, ¶m_values]() { + param_values = camera->getDistortionParams(); + }, + true); + + return param_values; +} + +std::vector WorldSimApi::getImages( + const std::vector& requests, const std::string& vehicle_name, bool external) const +{ + std::vector responses; + + const UnrealImageCapture* camera = simmode_->getImageCapture(vehicle_name, external); + camera->getImages(requests, responses); + + return responses; +} + +std::vector WorldSimApi::getImage(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) const +{ + std::vector request{ + ImageCaptureBase::ImageRequest(camera_details.camera_name, image_type) + }; + + const auto& response = getImages(request, camera_details.vehicle_name, camera_details.external); + if (response.size() > 0) + return response.at(0).image_data_uint8; + else + return std::vector(); +} + +void WorldSimApi::addDetectionFilterMeshName(ImageCaptureBase::ImageType image_type, const std::string& mesh_name, const CameraDetails& camera_details) +{ + const APIPCamera* camera = simmode_->getCamera(camera_details); + + UAirBlueprintLib::RunCommandOnGameThread([camera, image_type, &mesh_name]() { + camera->getDetectionComponent(image_type, false)->addMeshName(mesh_name); + }, + true); +} + +void WorldSimApi::setDetectionFilterRadius(ImageCaptureBase::ImageType image_type, float radius_cm, const CameraDetails& camera_details) +{ + const APIPCamera* camera = simmode_->getCamera(camera_details); + + UAirBlueprintLib::RunCommandOnGameThread([camera, image_type, radius_cm]() { + camera->getDetectionComponent(image_type, false)->setFilterRadius(radius_cm); + }, + true); +} + +void WorldSimApi::clearDetectionMeshNames(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) +{ + const APIPCamera* camera = simmode_->getCamera(camera_details); + + UAirBlueprintLib::RunCommandOnGameThread([camera, image_type]() { + camera->getDetectionComponent(image_type, false)->clearMeshNames(); + }, + true); +} + +std::vector WorldSimApi::getDetections(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) +{ + std::vector result; + + const APIPCamera* camera = simmode_->getCamera(camera_details); + const NedTransform& ned_transform = camera_details.external + ? simmode_->getGlobalNedTransform() + : simmode_->getVehicleSimApi(camera_details.vehicle_name)->getNedTransform(); + + UAirBlueprintLib::RunCommandOnGameThread([camera, image_type, &result, &ned_transform]() { + const TArray& detections = camera->getDetectionComponent(image_type, false)->getDetections(); + result.resize(detections.Num()); + + for (int i = 0; i < detections.Num(); i++) { + result[i].name = std::string(TCHAR_TO_UTF8(*(detections[i].Actor->GetFName().ToString()))); + + Vector3r nedWrtOrigin = ned_transform.toGlobalNed(detections[i].Actor->GetActorLocation()); + result[i].geo_point = msr::airlib::EarthUtils::nedToGeodetic(nedWrtOrigin, + AirSimSettings::singleton().origin_geopoint); + + result[i].box2D.min = Vector2r(detections[i].Box2D.Min.X, detections[i].Box2D.Min.Y); + result[i].box2D.max = Vector2r(detections[i].Box2D.Max.X, detections[i].Box2D.Max.Y); + + result[i].box3D.min = ned_transform.toLocalNed(detections[i].Box3D.Min); + result[i].box3D.max = ned_transform.toLocalNed(detections[i].Box3D.Max); + + const Vector3r& position = ned_transform.toLocalNed(detections[i].RelativeTransform.GetTranslation()); + const Quaternionr& orientation = ned_transform.toNed(detections[i].RelativeTransform.GetRotation()); + + result[i].relative_pose = Pose(position, orientation); + } + }, + true); + + return result; +} diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index c5e7e466d4..5e38548787 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -16,6 +16,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase typedef msr::airlib::Pose Pose; typedef msr::airlib::Vector3r Vector3r; typedef msr::airlib::MeshPositionVertexBuffersResponse MeshPositionVertexBuffersResponse; + typedef msr::airlib::ImageCaptureBase ImageCaptureBase; + typedef msr::airlib::CameraDetails CameraDetails; WorldSimApi(ASimModeBase* simmode); virtual ~WorldSimApi() = default; @@ -78,6 +80,22 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase virtual bool testLineOfSightBetweenPoints(const msr::airlib::GeoPoint& point1, const msr::airlib::GeoPoint& point2) const override; virtual std::vector getWorldExtents() const override; + // Camera APIs + virtual msr::airlib::CameraInfo getCameraInfo(const CameraDetails& camera_details) const override; + virtual void setCameraPose(const msr::airlib::Pose& pose, const CameraDetails& camera_details) override; + virtual void setCameraFoV(float fov_degrees, const CameraDetails& camera_details) override; + virtual void setDistortionParam(const std::string& param_name, float value, const CameraDetails& camera_details) override; + virtual std::vector getDistortionParams(const CameraDetails& camera_details) const override; + + virtual std::vector getImages(const std::vector& requests, + const std::string& vehicle_name, bool external) const override; + virtual std::vector getImage(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) const override; + + virtual void addDetectionFilterMeshName(ImageCaptureBase::ImageType image_type, const std::string& mesh_name, const CameraDetails& camera_details) override; + virtual void setDetectionFilterRadius(ImageCaptureBase::ImageType image_type, float radius_cm, const CameraDetails& camera_details) override; + virtual void clearDetectionMeshNames(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) override; + virtual std::vector getDetections(ImageCaptureBase::ImageType image_type, const CameraDetails& camera_details) override; + private: AActor* createNewActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh); void spawnPlayer(); @@ -86,4 +104,4 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase ASimModeBase* simmode_; ULevelStreamingDynamic* current_level_; std::vector voxel_grid_; -}; \ No newline at end of file +}; diff --git a/docs/image_apis.md b/docs/image_apis.md index d48442db49..21158d3c3a 100644 --- a/docs/image_apis.md +++ b/docs/image_apis.md @@ -133,6 +133,9 @@ For a more complete ready to run sample code please see [sample code in HelloDro See also [other example code](https://github.com/Microsoft/AirSim/tree/master/Examples/DataCollection/StereoImageGenerator.hpp) that generates specified number of stereo images along with ground truth depth and disparity and saving it to [pfm format](pfm.md). ## Available Cameras + +These are the default cameras already available in each vehicle. Apart from these, you can add more cameras to the vehicles and external cameras which are not attached to any vehicle through the [settings](settings.md). + ### Car The cameras on car can be accessed by following names in API calls: `front_center`, `front_right`, `front_left`, `fpv` and `back_center`. Here FPV camera is driver's head position in the car. ### Multirotor @@ -172,6 +175,11 @@ camera_pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0.26179 client.simSetCameraPose(0, camera_pose); ``` +- `simSetCameraFov` allows changing the Field-of-View of the camera at runtime. +- `simSetDistortionParams`, `simGetDistortionParams` allow setting and fetching the distortion parameters K1, K2, K3, P1, P2 + +All Camera APIs take in 3 common parameters apart from the API-specific ones, `camera_name`(str), `vehicle_name`(str) and `external`(bool, to indicate [External Camera](settings.md#external-cameras)). Camera and vehicle name is used to get the specific camera, if `external` is set to `true`, then the vehicle name is ignored. Also see [external_camera.py](https://github.com/microsoft/AirSim/blob/master/PythonClient/computer_vision/external_camera.py) for example usage of these APIs. + ### Gimbal You can set stabilization for pitch, roll or yaw for any camera [using settings](settings.md#gimbal). diff --git a/docs/settings.md b/docs/settings.md index 63fa1533e8..3a9c8fee99 100644 --- a/docs/settings.md +++ b/docs/settings.md @@ -132,9 +132,9 @@ Below are complete list of settings available along with their default values. I "UpdateIntervalSecs": 60 }, "SubWindows": [ - {"WindowID": 0, "CameraName": "0", "ImageType": 3, "VehicleName": "", "Visible": false}, - {"WindowID": 1, "CameraName": "0", "ImageType": 5, "VehicleName": "", "Visible": false}, - {"WindowID": 2, "CameraName": "0", "ImageType": 0, "VehicleName": "", "Visible": false} + {"WindowID": 0, "CameraName": "0", "ImageType": 3, "VehicleName": "", "Visible": false, "External": false}, + {"WindowID": 1, "CameraName": "0", "ImageType": 5, "VehicleName": "", "Visible": false, "External": false}, + {"WindowID": 2, "CameraName": "0", "ImageType": 0, "VehicleName": "", "Visible": false, "External": false} ], "SegmentationSettings": { "InitMethod": "", @@ -188,6 +188,14 @@ Below are complete list of settings available along with their default values. I "X": NaN, "Y": NaN, "Z": NaN, "Pitch": NaN, "Roll": NaN, "Yaw": NaN } + }, + "ExternalCameras": { + "FixedCamera1": { + // same elements as in CameraDefaults above + }, + "FixedCamera2": { + // same elements as in CameraDefaults above + } } } ``` @@ -218,7 +226,13 @@ Also see [Time of Day API](apis.md#time-of-day-api). This setting specifies the latitude, longitude and altitude of the Player Start component placed in the Unreal environment. The vehicle's home point is computed using this transformation. Note that all coordinates exposed via APIs are using NED system in SI units which means each vehicle starts at (0, 0, 0) in NED system. Time of Day settings are computed for geographical coordinates specified in `OriginGeopoint`. ## SubWindows -This setting determines what is shown in each of 3 subwindows which are visible when you press 0,1,2 keys. The `WindowID` can be 0 to 2, `CameraName` is any [available camera](image_apis.md#available_cameras) on the vehicle. `ImageType` integer value determines what kind of image gets shown according to [ImageType enum](image_apis.md#available-imagetype). `VehicleName` string allows you to specify the vehicle to use the camera from, used when multiple vehicles are specified in the settings. First vehicle's camera will be used if there are any mistakes such as incorrect vehicle name, or only a single vehicle. +This setting determines what is shown in each of 3 subwindows which are visible when you press 1,2,3 keys. + +* `WindowID`: Can be 0 to 2 +* `CameraName`: is any [available camera](image_apis.md#available-cameras) on the vehicle or external camera +* `ImageType`: integer value determines what kind of image gets shown according to [ImageType enum](image_apis.md#available-imagetype-values). +* `VehicleName`: string allows you to specify the vehicle to use the camera from, used when multiple vehicles are specified in the settings. First vehicle's camera will be used if there are any mistakes such as incorrect vehicle name, or only a single vehicle. +* `External`: Set it to `true` if the camera is an external camera. If true, then the `VehicleName` parameter is ignored For example, for a single car vehicle, below shows driver view, front bumper view and rear view as scene, depth and surface normals respectively. ```json @@ -250,6 +264,7 @@ The recording feature allows you to record data such as position, orientation, v * When `PixelsAsFloat` is true, image is saved as [pfm](pfm.md) file instead of png file. * `VehicleName` option allows you to specify separate cameras for individual vehicles. If the `Cameras` element isn't present, `Scene` image from the default camera of each vehicle will be recorded. * If you don't want to record any images and just the vehicle's physics data, then specify the `Cameras` element but leave it empty, like this: `"Cameras": []` + * External cameras are currently not supported in recording For example, the `Cameras` element below records scene & segmentation images for `Car1` & scene for `Car2`- @@ -330,6 +345,9 @@ This adds fluctuations on horizontal line. ### Gimbal The `Gimbal` element allows to freeze camera orientation for pitch, roll and/or yaw. This setting is ignored unless `ImageType` is -1. The `Stabilization` is defaulted to 0 meaning no gimbal i.e. camera orientation changes with body orientation on all axis. The value of 1 means full stabilization. The value between 0 to 1 acts as a weight for fixed angles specified (in degrees, in world-frame) in `Pitch`, `Roll` and `Yaw` elements and orientation of the vehicle body. When any of the angles is omitted from json or set to NaN, that angle is not stabilized (i.e. it moves along with vehicle body). +## External Cameras +This element allows specifying cameras which are separate from the cameras attached to the vehicle, such as a CCTV camera. These are fixed cameras, and don't move along with the vehicles. The key in the element is the name of the camera, and the value i.e. settings are the same as `CameraDefaults` described above. All the camera APIs work with external cameras, including capturing images, changing the pose, etc by passing the parameter `external=True` in the API call. + ## Vehicles Settings Each simulation mode will go through the list of vehicles specified in this setting and create the ones that has `"AutoCreate": true`. Each vehicle specified in this setting has key which becomes the name of the vehicle. If `"Vehicles"` element is missing then this list is populated with default car named "PhysXCar" and default multirotor named "SimpleFlight".