diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index 64f3a604d1..f2645392bd 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -129,6 +129,7 @@ namespace airlib bool isRecording(); void simSetWind(const Vector3r& wind) const; + vector listVehicles(); std::string getSettingsString() const; diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index b3960902b7..38906c5dc7 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -82,6 +82,7 @@ namespace airlib virtual bool isRecording() const = 0; virtual void setWind(const Vector3r& wind) const = 0; + virtual vector listVehicles() const = 0; virtual std::string getSettingsString() const = 0; }; diff --git a/AirLib/include/common/common_utils/UniqueValueMap.hpp b/AirLib/include/common/common_utils/UniqueValueMap.hpp index f19fa5c48f..354a1f2a90 100644 --- a/AirLib/include/common/common_utils/UniqueValueMap.hpp +++ b/AirLib/include/common/common_utils/UniqueValueMap.hpp @@ -73,6 +73,15 @@ class UniqueValueMap return vals_.size(); } + std::vector keys() const + { + std::vector ret; + for (const auto& element : map_) { + ret.push_back(element.first); + } + return ret; + } + //TODO: add erase methods private: @@ -80,4 +89,4 @@ class UniqueValueMap std::set vals_; }; } -#endif \ No newline at end of file +#endif diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 147abbca5c..c78a216a2c 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -483,6 +483,11 @@ __pragma(warning(disable : 4239)) pimpl_->client.call("simSetWind", conv_wind); } + vector RpcLibClientBase::listVehicles() + { + return pimpl_->client.call("listVehicles").as>(); + } + std::string RpcLibClientBase::getSettingsString() const { return pimpl_->client.call("getSettingsString").as(); diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 5c0d6a5993..c1ef84324b 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -383,6 +383,10 @@ namespace airlib getWorldSimApi()->setWind(wind.to()); }); + pimpl_->server.bind("listVehicles", [&]() -> vector { + return getWorldSimApi()->listVehicles(); + }); + pimpl_->server.bind("getSettingsString", [&]() -> std::string { return getWorldSimApi()->getSettingsString(); }); diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index a36407c829..b6ef0795bc 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -851,13 +851,22 @@ def simAddVehicle(self, vehicle_name, vehicle_type, pose, pawn_path = ""): vehicle_name (str): Name of the vehicle being created vehicle_type (str): Type of vehicle, e.g. "simpleflight" pose (Pose): Initial pose of the vehicle - pawn_path (str): Vehicle blueprint path, default empty wbich uses the default blueprint for the vehicle type + pawn_path (str, optional): Vehicle blueprint path, default empty wbich uses the default blueprint for the vehicle type Returns: bool: Whether vehicle was created """ return self.client.call('simAddVehicle', vehicle_name, vehicle_type, pose, pawn_path) + def listVehicles(self): + """ + Lists the names of current vehicles + + Returns: + list[str]: List containing names of all vehicles + """ + return self.client.call('listVehicles') + def getSettingsString(self): """ Fetch the settings text being used by AirSim diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp index cfc9ab24f4..0e261e92a6 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp @@ -218,7 +218,17 @@ bool WorldSimApi::isRecording() const void WorldSimApi::setWind(const Vector3r& wind) const { simmode_->setWind(wind); -}; +} + +std::vector WorldSimApi::listVehicles() const +{ + auto vehicle_names = (simmode_->getApiProvider()->getVehicleSimApis()).keys(); + // Remove '' from the list, representing default vehicle + auto position = std::find(vehicle_names.begin(), vehicle_names.end(), ""); + if (position != vehicle_names.end()) + vehicle_names.erase(position); + return vehicle_names; +} bool WorldSimApi::addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const WorldSimApi::Pose& pose, const std::string& pawn_path) { diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h index 95c7310673..38aa367ba3 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h @@ -65,6 +65,7 @@ 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 bool addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = "") override; + virtual std::vector listVehicles() const override; virtual std::string getSettingsString() const override; diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 01b4834793..c7195f8dde 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -607,6 +607,22 @@ void WorldSimApi::setWind(const Vector3r& wind) const simmode_->setWind(wind); } +std::vector WorldSimApi::listVehicles() const +{ + std::vector vehicle_names; + + UAirBlueprintLib::RunCommandOnGameThread([this, &vehicle_names]() { + vehicle_names = (simmode_->getApiProvider()->getVehicleSimApis()).keys(); + }, + true); + + // Remove '' from the list, representing default vehicle + auto position = std::find(vehicle_names.begin(), vehicle_names.end(), ""); + if (position != vehicle_names.end()) + vehicle_names.erase(position); + return vehicle_names; +} + std::string WorldSimApi::getSettingsString() const { return msr::airlib::AirSimSettings::singleton().settings_text_; diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index c784c4b324..8f5adb2e97 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -70,6 +70,7 @@ 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::vector listVehicles() const override; virtual std::string getSettingsString() const override; diff --git a/docs/multi_vehicle.md b/docs/multi_vehicle.md index a63695e0c7..ce02b65079 100644 --- a/docs/multi_vehicle.md +++ b/docs/multi_vehicle.md @@ -53,5 +53,12 @@ The new APIs since AirSim 1.2 allows you to specify `vehicle_name`. This name co [Example code for multirotors](https://github.com/Microsoft/AirSim/tree/master/PythonClient//multirotor/multi_agent_drone.py) +Using APIs for multi-vehicles requires specifying the `vehicle_name`, which needs to be hardcoded in the script or requires parsing of the settings file. There's also a simple API `listVehicles()` which returns a list (vector in C++) of strings containing names of the current vehicles. For example, with the above settings for 2 Cars - + +``` +>>> client.listVehicles() +['Car1', 'Car2'] +``` + ### Demo [![AirSimMultiple Vehicles Demo Video](images/demo_multi_vehicles.png)](https://youtu.be/35dgcuLuF5M)