diff --git a/AirSim/AirLib/include/api/RpcLibClientBase.hpp b/AirSim/AirLib/include/api/RpcLibClientBase.hpp index 831b9f2b..a69236bb 100644 --- a/AirSim/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirSim/AirLib/include/api/RpcLibClientBase.hpp @@ -101,7 +101,7 @@ class RpcLibClientBase { msr::airlib::WheelStates simGetWheelStates(const std::string& vehicle_name = "") const; std::vector simSwapTextures(const std::string& tags, int tex_id = 0, int component_id = 0, int material_id = 0); - + std::string getSettingsString() const; protected: void* getClient(); const void* getClient() const; diff --git a/AirSim/AirLib/include/api/WorldSimApiBase.hpp b/AirSim/AirLib/include/api/WorldSimApiBase.hpp index e4d5db2b..ba463b05 100644 --- a/AirSim/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirSim/AirLib/include/api/WorldSimApiBase.hpp @@ -60,6 +60,7 @@ class WorldSimApiBase { virtual std::unique_ptr> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0; virtual vector getMeshPositionVertexBuffers() const = 0; + virtual std::string getSettingsString() const = 0; }; diff --git a/AirSim/AirLib/include/common/AirSimSettings.hpp b/AirSim/AirLib/include/common/AirSimSettings.hpp index 173a0e92..f5dc764b 100644 --- a/AirSim/AirLib/include/common/AirSimSettings.hpp +++ b/AirSim/AirLib/include/common/AirSimSettings.hpp @@ -328,6 +328,8 @@ struct AirSimSettings { std::string speed_unit_label = "m\\s"; std::map> sensor_defaults; + std::string settings_text_ = ""; + public: //methods static AirSimSettings& singleton() { @@ -367,6 +369,7 @@ struct AirSimSettings { static void initializeSettings(const std::string& json_settings_text) { try { + singleton().settings_text_ = json_settings_text; Settings::loadJSonString(json_settings_text); } catch (std::exception &ex) { diff --git a/AirSim/AirLib/src/api/RpcLibClientBase.cpp b/AirSim/AirLib/src/api/RpcLibClientBase.cpp index d4702a34..f7292339 100644 --- a/AirSim/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirSim/AirLib/src/api/RpcLibClientBase.cpp @@ -366,6 +366,10 @@ void RpcLibClientBase::cancelLastTask(const std::string& vehicle_name) { pimpl_->client.call("cancelLastTask", vehicle_name); } +std::string RpcLibClientBase::getSettingsString() const +{ + return pimpl_->client.call("getSettingsString").as(); +} //return value of last task. It should be true if task completed without //cancellation or timeout diff --git a/AirSim/AirLib/src/api/RpcLibServerBase.cpp b/AirSim/AirLib/src/api/RpcLibServerBase.cpp index 8c563f19..fb709f3a 100644 --- a/AirSim/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirSim/AirLib/src/api/RpcLibServerBase.cpp @@ -89,6 +89,9 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& pimpl_->server.bind("getMinRequiredClientVersion", []() -> int { return 1; }); + pimpl_->server.bind("getSettingsString", [&]() -> std::string { + return getWorldSimApi()->getSettingsString(); + }); pimpl_->server.bind("simPause", [&](bool is_paused) -> void { getWorldSimApi()->pause(is_paused); diff --git a/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp b/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp index 017cbfb0..44b1354a 100644 --- a/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp @@ -248,4 +248,9 @@ std::vector WorldSimApi::getMesh responses = UAirBlueprintLib::GetStaticMeshComponents(); }, true); return responses; -} \ No newline at end of file +} + +std::string WorldSimApi::getSettingsString() const +{ + return msr::airlib::AirSimSettings::singleton().settings_text_; +} diff --git a/UE4Project/Plugins/AirSim/Source/WorldSimApi.h b/UE4Project/Plugins/AirSim/Source/WorldSimApi.h index 61ae9092..a6777af1 100644 --- a/UE4Project/Plugins/AirSim/Source/WorldSimApi.h +++ b/UE4Project/Plugins/AirSim/Source/WorldSimApi.h @@ -49,6 +49,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual void simPlotTransforms(const std::vector& poses, float scale, float thickness, float duration, bool is_persistent) override; virtual void simPlotTransformsWithNames(const std::vector& poses, const std::vector& names, float tf_scale, float tf_thickness, float text_scale, const std::vector& text_color_rgba, float duration) override; virtual std::vector getMeshPositionVertexBuffers() const override; + virtual std::string getSettingsString() const override; private: ASimModeBase* simmode_; diff --git a/python/fsds/client.py b/python/fsds/client.py index e2e26464..d01e487d 100644 --- a/python/fsds/client.py +++ b/python/fsds/client.py @@ -196,4 +196,12 @@ def getCarState(self, vehicle_name = 'FSCar'): def getRefereeState(self): referee_state_raw = self.client.call('getRefereeState') - return RefereeState.from_msgpack(referee_state_raw) \ No newline at end of file + return RefereeState.from_msgpack(referee_state_raw) + + def getSettingsString(self): + """ + Fetch the settings text being used by AirSim + Returns: + str: Settings text in JSON format + """ + return self.client.call('getSettingsString') diff --git a/ros/src/fsds_ros_bridge/src/airsim_ros_wrapper.cpp b/ros/src/fsds_ros_bridge/src/airsim_ros_wrapper.cpp index 26daf4ca..4ef2846e 100644 --- a/ros/src/fsds_ros_bridge/src/airsim_ros_wrapper.cpp +++ b/ros/src/fsds_ros_bridge/src/airsim_ros_wrapper.cpp @@ -11,8 +11,9 @@ AirsimROSWrapper::AirsimROSWrapper(const ros::NodeHandle& nh, const ros::NodeHan airsim_client_lidar_(host_ip) { try { - auto settingsText = this->readTextFromFile(common_utils::FileSystem::getConfigFilePath()); - msr::airlib::AirSimSettings::initializeSettings(settingsText); + airsim_client_.confirmConnection(); + std::string settings_text = airsim_client_.getSettingsString(); + msr::airlib::AirSimSettings::initializeSettings(settings_text); msr::airlib::AirSimSettings::singleton().load(); for (const auto &warning : msr::airlib::AirSimSettings::singleton().warning_messages) diff --git a/ros2/src/fsds_ros2_bridge/src/airsim_ros_wrapper.cpp b/ros2/src/fsds_ros2_bridge/src/airsim_ros_wrapper.cpp index 80a0e132..071f8647 100644 --- a/ros2/src/fsds_ros2_bridge/src/airsim_ros_wrapper.cpp +++ b/ros2/src/fsds_ros2_bridge/src/airsim_ros_wrapper.cpp @@ -13,8 +13,9 @@ AirsimROSWrapper::AirsimROSWrapper(const std::shared_ptr& nh, cons static_tf_pub_(this->nh_) { try { - auto settingsText = this->readTextFromFile(common_utils::FileSystem::getConfigFilePath()); - msr::airlib::AirSimSettings::initializeSettings(settingsText); + airsim_client_.confirmConnection(); + std::string settings_text = airsim_client_.getSettingsString(); + msr::airlib::AirSimSettings::initializeSettings(settings_text); msr::airlib::AirSimSettings::singleton().load(); for (const auto &warning : msr::airlib::AirSimSettings::singleton().warning_messages)