From 7fe058ee99dad669a0e77174f03cc46b19e51bd5 Mon Sep 17 00:00:00 2001 From: Rajat Singhal Date: Sat, 13 Feb 2021 00:11:33 +0530 Subject: [PATCH] Fix some warnings, cleanup --- AirLib/include/api/WorldSimApiBase.hpp | 7 +++--- PythonClient/airsim/client.py | 1 - Unreal/Plugins/AirSim/Source/PIPCamera.h | 4 +-- Unreal/Plugins/AirSim/Source/PawnSimApi.h | 1 - .../AirSim/Source/SimMode/SimModeBase.cpp | 12 +++------ .../AirSim/Source/SimMode/SimModeBase.h | 2 +- Unreal/Plugins/AirSim/Source/WorldSimApi.cpp | 25 +++++++++---------- Unreal/Plugins/AirSim/Source/WorldSimApi.h | 8 +++--- 8 files changed, 26 insertions(+), 34 deletions(-) diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index 669898fe41..e2f52caa7c 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -5,8 +5,7 @@ #define air_WorldSimApiBase_hpp #include "common/CommonStructs.hpp" -#include "common/AirSimSettings.hpp" - +#include "common/ImageCaptureBase.hpp" namespace msr { namespace airlib { @@ -82,7 +81,7 @@ class WorldSimApiBase { // Image APIs virtual CameraInfo getCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "", bool external = false) const = 0; - virtual void setCameraPose(const std::string& camera_name, const msr::airlib::Pose& pose, + virtual void setCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = "", bool external = false) = 0; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = "", bool external = false) = 0; @@ -91,7 +90,7 @@ class WorldSimApiBase { virtual std::vector getDistortionParams(const std::string& camera_name, const std::string& vehicle_name = "", bool external = false) const = 0; - virtual std::vector getImages(const std::vector& requests, + virtual std::vector getImages(const std::vector& requests, const std::string& vehicle_name = "", bool external = false) const = 0; virtual std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type, const std::string& vehicle_name = "", bool external = false) const = 0; diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index 4488c03c4d..110ef225c0 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -522,7 +522,6 @@ def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = """ for param_name, value in distortion_params.items(): - # self.client.call('simSetDistortionParam', str(camera_name), param_name, value, vehicle_name, external) self.simSetDistortionParam(camera_name, param_name, value, vehicle_name, external) def simSetDistortionParam(self, camera_name, param_name, value, vehicle_name = '', external = False): diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.h b/Unreal/Plugins/AirSim/Source/PIPCamera.h index 0a5f616daf..17ee22a4cf 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.h +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.h @@ -43,14 +43,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 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); diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.h b/Unreal/Plugins/AirSim/Source/PawnSimApi.h index dd9bda8064..1c8a5a4265 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.h +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.h @@ -33,7 +33,6 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase { typedef msr::airlib::real_T real_T; typedef msr::airlib::Utils Utils; typedef msr::airlib::AirSimSettings::VehicleSetting VehicleSetting; - typedef msr::airlib::ImageCaptureBase ImageCaptureBase; struct Params { APawn* pawn; diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index ad0e028ca7..3243415fcc 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -509,18 +509,14 @@ bool ASimModeBase::isRecording() const const APIPCamera* ASimModeBase::getCamera(const std::string& camera_name, const std::string& vehicle_name, bool external) const { - if (external) - return getExternalCamera(camera_name); - else - return getVehicleSimApi(vehicle_name)->getCamera(camera_name); + return external ? getExternalCamera(camera_name) : + getVehicleSimApi(vehicle_name)->getCamera(camera_name); } const UnrealImageCapture* ASimModeBase::getImageCapture(const std::string& vehicle_name, bool external) const { - if (external) - return external_image_capture_.get(); - else - return getVehicleSimApi(vehicle_name)->getImageCapture(); + return external ? external_image_capture_.get() : + getVehicleSimApi(vehicle_name)->getImageCapture(); } //API server start/stop diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h index 013f5ccb05..95b37ac801 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -151,7 +151,7 @@ class AIRSIM_API ASimModeBase : public AActor 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); diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 160f9ef305..b43122cfb3 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -574,11 +574,11 @@ void WorldSimApi::setWind(const Vector3r& wind) const simmode_->setWind(wind); } -CameraInfo WorldSimApi::getCameraInfo(const std::string& camera_name, const std::string& vehicle_name, bool external) const +msr::airlib::CameraInfo WorldSimApi::getCameraInfo(const std::string& camera_name, const std::string& vehicle_name, bool external) const { - CameraInfo info; - UAirBlueprintLib::RunCommandOnGameThread([this, &camera_name, &vehicle_name, &external, &info]() { - auto camera = simmode_->getCamera(camera_name, vehicle_name, external); + msr::airlib::CameraInfo info; + const auto* camera = simmode_->getCamera(camera_name, vehicle_name, external); + UAirBlueprintLib::RunCommandOnGameThread([camera, &info]() { info = camera->getCameraInfo(); }, true); @@ -588,8 +588,8 @@ CameraInfo WorldSimApi::getCameraInfo(const std::string& camera_name, const std: void WorldSimApi::setCameraPose(const std::string& camera_name, const msr::airlib::Pose& pose, const std::string& vehicle_name, bool external) { - UAirBlueprintLib::RunCommandOnGameThread([this, &camera_name, &vehicle_name, &external, &pose]() { - auto camera = simmode_->getCamera(camera_name, vehicle_name, external); + auto* camera = simmode_->getCamera(camera_name, vehicle_name, external); + UAirBlueprintLib::RunCommandOnGameThread([camera, &pose]() { camera->setCameraPose(pose); }, true); } @@ -597,8 +597,8 @@ void WorldSimApi::setCameraPose(const std::string& camera_name, const msr::airli void WorldSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name, bool external) { - UAirBlueprintLib::RunCommandOnGameThread([this, &camera_name, &vehicle_name, &external, &fov_degrees]() { - auto camera = simmode_->getCamera(camera_name, vehicle_name, external); + auto* camera = simmode_->getCamera(camera_name, vehicle_name, external); + UAirBlueprintLib::RunCommandOnGameThread([camera, &fov_degrees]() { camera->setCameraFoV(fov_degrees); }, true); } @@ -606,9 +606,8 @@ void WorldSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees void WorldSimApi::setDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name, bool external) { - UAirBlueprintLib::RunCommandOnGameThread([this, &camera_name, &vehicle_name, &external, - ¶m_name, &value]() { - auto camera = simmode_->getCamera(camera_name, vehicle_name, external); + auto* camera = simmode_->getCamera(camera_name, vehicle_name, external); + UAirBlueprintLib::RunCommandOnGameThread([camera, ¶m_name, &value]() { camera->setDistortionParam(param_name, value); }, true); } @@ -616,8 +615,8 @@ void WorldSimApi::setDistortionParam(const std::string& camera_name, const std:: std::vector WorldSimApi::getDistortionParams(const std::string& camera_name, const std::string& vehicle_name, bool external) const { std::vector param_values; - UAirBlueprintLib::RunCommandOnGameThread([this, &camera_name, &vehicle_name, &external, ¶m_values]() { - auto camera = simmode_->getCamera(camera_name, vehicle_name, external); + const auto* camera = simmode_->getCamera(camera_name, vehicle_name, external); + UAirBlueprintLib::RunCommandOnGameThread([camera, ¶m_values]() { param_values = camera->getDistortionParams(); }, true); diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index 30f618d9e1..74706ba159 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -82,10 +82,10 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual std::vector getDistortionParams(const std::string& camera_name, const std::string& vehicle_name = "", bool external = false) const override; - std::vector getImages(const std::vector& requests, - const std::string& vehicle_name = "", bool external = false) const; - std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type, - const std::string& vehicle_name = "", bool external = false) const; + virtual std::vector getImages(const std::vector& requests, + const std::string& vehicle_name = "", bool external = false) const override; + virtual std::vector getImage(const std::string& camera_name, ImageCaptureBase::ImageType image_type, + const std::string& vehicle_name = "", bool external = false) const override; private: AActor* createNewActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh);