Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Ros use same settings as airsim #324

Merged
merged 2 commits into from
Sep 3, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion AirSim/AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ class RpcLibClientBase {
msr::airlib::WheelStates simGetWheelStates(const std::string& vehicle_name = "") const;

std::vector<std::string> 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;
Expand Down
1 change: 1 addition & 0 deletions AirSim/AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ class WorldSimApiBase {

virtual std::unique_ptr<std::vector<std::string>> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0;
virtual vector<MeshPositionVertexBuffersResponse> getMeshPositionVertexBuffers() const = 0;
virtual std::string getSettingsString() const = 0;
};


Expand Down
3 changes: 3 additions & 0 deletions AirSim/AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -328,6 +328,8 @@ struct AirSimSettings {
std::string speed_unit_label = "m\\s";
std::map<std::string, std::unique_ptr<SensorSetting>> sensor_defaults;

std::string settings_text_ = "";

public: //methods
static AirSimSettings& singleton()
{
Expand Down Expand Up @@ -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) {
Expand Down
4 changes: 4 additions & 0 deletions AirSim/AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string>();
}

//return value of last task. It should be true if task completed without
//cancellation or timeout
Expand Down
3 changes: 3 additions & 0 deletions AirSim/AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
7 changes: 6 additions & 1 deletion UE4Project/Plugins/AirSim/Source/WorldSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,4 +248,9 @@ std::vector<WorldSimApi::MeshPositionVertexBuffersResponse> WorldSimApi::getMesh
responses = UAirBlueprintLib::GetStaticMeshComponents();
}, true);
return responses;
}
}

std::string WorldSimApi::getSettingsString() const
{
return msr::airlib::AirSimSettings::singleton().settings_text_;
}
1 change: 1 addition & 0 deletions UE4Project/Plugins/AirSim/Source/WorldSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase {
virtual void simPlotTransforms(const std::vector<Pose>& poses, float scale, float thickness, float duration, bool is_persistent) override;
virtual void simPlotTransformsWithNames(const std::vector<Pose>& poses, const std::vector<std::string>& names, float tf_scale, float tf_thickness, float text_scale, const std::vector<float>& text_color_rgba, float duration) override;
virtual std::vector<MeshPositionVertexBuffersResponse> getMeshPositionVertexBuffers() const override;
virtual std::string getSettingsString() const override;

private:
ASimModeBase* simmode_;
Expand Down
10 changes: 9 additions & 1 deletion python/fsds/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
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')
5 changes: 3 additions & 2 deletions ros/src/fsds_ros_bridge/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
5 changes: 3 additions & 2 deletions ros2/src/fsds_ros2_bridge/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,9 @@ AirsimROSWrapper::AirsimROSWrapper(const std::shared_ptr<rclcpp::Node>& 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)
Expand Down