Skip to content

Commit

Permalink
Merge pull request #3536 from rajat2004/ros-settings
Browse files Browse the repository at this point in the history
ROS: Use the same settings as AirSim
  • Loading branch information
Jonathan authored Apr 13, 2021
2 parents 17d2b5d + 7ffdcec commit 210f3ee
Show file tree
Hide file tree
Showing 14 changed files with 64 additions and 41 deletions.
2 changes: 2 additions & 0 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,6 +120,8 @@ class RpcLibClientBase {

void simSetWind(const Vector3r& wind) const;

std::string getSettingsString() const;

protected:
void* getClient();
const void* getClient() const;
Expand Down
2 changes: 2 additions & 0 deletions AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,8 @@ class WorldSimApiBase {
virtual bool isRecording() const = 0;

virtual void setWind(const Vector3r& wind) const = 0;

virtual std::string getSettingsString() const = 0;
};


Expand Down
9 changes: 7 additions & 2 deletions AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -377,6 +377,8 @@ struct AirSimSettings {
std::map<std::string, std::unique_ptr<SensorSetting>> sensor_defaults;
Vector3r wind = Vector3r::Zero();

std::string settings_text_ = "";

public: //methods
static AirSimSettings& singleton()
{
Expand Down Expand Up @@ -417,19 +419,22 @@ struct AirSimSettings {

static void initializeSettings(const std::string& json_settings_text)
{
singleton().settings_text_ = json_settings_text;
Settings& settings_json = Settings::loadJSonString(json_settings_text);
if (! settings_json.isLoadSuccess())
throw std::invalid_argument("Cannot parse JSON settings_json string.");
}

static void createDefaultSettingsFile()
{
std::string settings_filename = Settings::getUserDirectoryFullPath("settings.json");
Settings& settings_json = Settings::loadJSonString("{}");
initializeSettings("{}");

Settings& settings_json = Settings::singleton();
//write some settings_json in new file otherwise the string "null" is written if all settings_json are empty
settings_json.setString("SeeDocsAt", "https://github.com/Microsoft/AirSim/blob/master/docs/settings.md");
settings_json.setDouble("SettingsVersion", 1.2);

std::string settings_filename = Settings::getUserDirectoryFullPath("settings.json");
//TODO: there is a crash in Linux due to settings_json.saveJSonString(). Remove this workaround after we only support Unreal 4.17
//https://answers.unrealengine.com/questions/664905/unreal-crashes-on-two-lines-of-extremely-simple-st.html
settings_json.saveJSonFile(settings_filename);
Expand Down
5 changes: 5 additions & 0 deletions AirLib/src/api/RpcLibClientBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,6 +470,11 @@ void RpcLibClientBase::simSetWind(const Vector3r& wind) const
pimpl_->client.call("simSetWind", conv_wind);
}

std::string RpcLibClientBase::getSettingsString() const
{
return pimpl_->client.call("getSettingsString").as<std::string>();
}

void* RpcLibClientBase::getClient()
{
return &pimpl_->client;
Expand Down
4 changes: 4 additions & 0 deletions AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -383,6 +383,10 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
getWorldSimApi()->setWind(wind.to());
});

pimpl_->server.bind("getSettingsString", [&]() -> std::string {
return getWorldSimApi()->getSettingsString();
});

//if we don't suppress then server will bomb out for exceptions raised by any method
pimpl_->server.suppress_exceptions(true);
}
Expand Down
9 changes: 9 additions & 0 deletions PythonClient/airsim/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -872,6 +872,15 @@ def simAddVehicle(self, vehicle_name, vehicle_type, pose, pawn_path = ""):
"""
return self.client.call('simAddVehicle', vehicle_name, vehicle_type, pose, pawn_path)

def getSettingsString(self):
"""
Fetch the settings text being used by AirSim
Returns:
str: Settings text in JSON format
"""
return self.client.call('getSettingsString')

# ----------------------------------- Multirotor APIs ---------------------------------------------
class MultirotorClient(VehicleClient, object):
def __init__(self, ip = "", port = 41451, timeout_value = 3600):
Expand Down
5 changes: 5 additions & 0 deletions Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,5 +202,10 @@ bool WorldSimApi::addVehicle(const std::string& vehicle_name, const std::string&
return false;
}

std::string WorldSimApi::getSettingsString() const
{
return msr::airlib::AirSimSettings::singleton().settings_text_;
}


#pragma endregion
2 changes: 2 additions & 0 deletions Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase
virtual bool createVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file) override;
virtual bool addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = "") override;

virtual std::string getSettingsString() const override;

private:
SimModeBase * simmode_;
std::string vehicle_name_;
Expand Down
5 changes: 5 additions & 0 deletions Unreal/Plugins/AirSim/Source/WorldSimApi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -573,3 +573,8 @@ void WorldSimApi::setWind(const Vector3r& wind) const
{
simmode_->setWind(wind);
}

std::string WorldSimApi::getSettingsString() const
{
return msr::airlib::AirSimSettings::singleton().settings_text_;
}
2 changes: 2 additions & 0 deletions Unreal/Plugins/AirSim/Source/WorldSimApi.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase {
virtual void setWind(const Vector3r& wind) const override;
virtual bool createVoxelGrid(const Vector3r& position, const int& x_size, const int& y_size, const int& z_size, const float& res, const std::string& output_file) override;

virtual std::string getSettingsString() const override;

private:
AActor* createNewActor(const FActorSpawnParameters& spawn_params, const FTransform& actor_transform, const Vector3r& scale, UStaticMesh* static_mesh);
void spawnPlayer();
Expand Down
1 change: 0 additions & 1 deletion ros/src/airsim_ros_pkgs/include/airsim_ros_wrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -319,7 +319,6 @@ class AirsimROSWrapper
msr::airlib::GeoPoint origin_geo_point_;// gps coord of unreal origin
airsim_ros_pkgs::GPSYaw origin_geo_point_msg_; // todo duplicate

std::vector<VehicleSetting> vehicle_setting_vec_;
AirSimSettingsParser airsim_settings_parser_;
std::unordered_map< std::string, std::unique_ptr< VehicleROS > > vehicle_name_ptr_map_;
static const std::unordered_map<int, std::string> image_type_int_to_string_map_;
Expand Down
9 changes: 4 additions & 5 deletions ros/src/airsim_ros_pkgs/include/airsim_settings_parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,20 +17,19 @@ class AirSimSettingsParser
{
public:
typedef msr::airlib::AirSimSettings AirSimSettings;
typedef msr::airlib::AirSimSettings::VehicleSetting VehicleSetting;

public:
AirSimSettingsParser();
AirSimSettingsParser(const std::string& host_ip);
~AirSimSettingsParser() {};

bool success();

private:
std::string getSimMode();
bool readSettingsTextFromFile(std::string settingsFilepath, std::string& settingsText);
bool getSettingsText(std::string& settingsText);
bool getSettingsText(std::string& settings_text) const;
bool initializeSettings();

bool success_;
std::string settingsText_;
std::string settings_text_;
std::string host_ip_;
};
7 changes: 4 additions & 3 deletions ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,14 @@ AirsimROSWrapper::AirsimROSWrapper(const ros::NodeHandle& nh, const ros::NodeHan
host_ip_(host_ip),
airsim_client_images_(host_ip),
airsim_client_lidar_(host_ip),
airsim_settings_parser_(host_ip),
tf_listener_(tf_buffer_)
{
ros_clock_.clock.fromSec(0);
is_used_lidar_timer_cb_queue_ = false;
is_used_img_timer_cb_queue_ = false;

if (AirSimSettings::singleton().simmode_name != "Car")
if (AirSimSettings::singleton().simmode_name != AirSimSettings::kSimModeTypeCar)
{
airsim_mode_ = AIRSIM_MODE::DRONE;
ROS_INFO("Setting ROS wrapper to DRONE mode");
Expand Down Expand Up @@ -68,7 +69,7 @@ void AirsimROSWrapper::initialize_airsim()
}
else
{
airsim_client_ = std::move(std::unique_ptr<msr::airlib::RpcLibClientBase>(new msr::airlib::CarRpcLibClient(host_ip_)));
airsim_client_ = std::unique_ptr<msr::airlib::RpcLibClientBase>(new msr::airlib::CarRpcLibClient(host_ip_));
}
airsim_client_->confirmConnection();
airsim_client_images_.confirmConnection();
Expand Down Expand Up @@ -189,7 +190,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json()
{
auto& camera_setting = curr_camera_elem.second;
auto& curr_camera_name = curr_camera_elem.first;
// vehicle_setting_vec_.push_back(*vehicle_setting.get());

set_nans_to_zeros_in_pose(*vehicle_setting, camera_setting);
append_static_camera_tf(vehicle_ros.get(), curr_camera_name, camera_setting);
// camera_setting.gimbal
Expand Down
43 changes: 13 additions & 30 deletions ros/src/airsim_ros_pkgs/src/airsim_settings_parser.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include "airsim_settings_parser.h"

AirSimSettingsParser::AirSimSettingsParser()
AirSimSettingsParser::AirSimSettingsParser(const std::string& host_ip)
: host_ip_(host_ip)
{
success_ = initializeSettings();
}
Expand All @@ -10,52 +11,34 @@ bool AirSimSettingsParser::success()
return success_;
}

bool AirSimSettingsParser::readSettingsTextFromFile(std::string settingsFilepath, std::string& settingsText)
bool AirSimSettingsParser::getSettingsText(std::string& settings_text) const
{
// check if path exists
bool found = std::ifstream(settingsFilepath.c_str()).good();
if (found)
{
std::ifstream ifs(settingsFilepath);
std::stringstream buffer;
buffer << ifs.rdbuf();
// todo airsim's simhud.cpp does error checking here
settingsText = buffer.str(); // todo convert to utf8 as done in simhud.cpp?
}
msr::airlib::RpcLibClientBase airsim_client(host_ip_);
airsim_client.confirmConnection();

return found;
}
settings_text = airsim_client.getSettingsString();

bool AirSimSettingsParser::getSettingsText(std::string& settingsText)
{
bool success = readSettingsTextFromFile(msr::airlib::Settings::Settings::getUserDirectoryFullPath("settings.json"), settingsText);
return success;
return !settings_text.empty();
}

std::string AirSimSettingsParser::getSimMode()
{
Settings& settings_json = Settings::loadJSonString(settingsText_);
Settings& settings_json = Settings::loadJSonString(settings_text_);
return settings_json.getString("SimMode", "");
}

// mimics void ASimHUD::initializeSettings()
bool AirSimSettingsParser::initializeSettings()
{
if (getSettingsText(settingsText_))
if (getSettingsText(settings_text_))
{
AirSimSettings::initializeSettings(settingsText_);

// not sure where settings_json initialized in AirSimSettings::initializeSettings() is actually used
Settings& settings_json = Settings::loadJSonString(settingsText_);
std::string simmode_name = settings_json.getString("SimMode", "");
std::cout << "simmode_name: " << simmode_name << std::endl;
AirSimSettings::initializeSettings(settings_text_);

AirSimSettings::singleton().load(std::bind(&AirSimSettingsParser::getSimMode, this));
std::cout << "SimMode: " << AirSimSettings::singleton().simmode_name << std::endl;

return true;
}
else
{
return false;
}

return false;
}

0 comments on commit 210f3ee

Please sign in to comment.