diff --git a/.gitignore b/.gitignore index c1564db29d..ec5b0897c7 100644 --- a/.gitignore +++ b/.gitignore @@ -286,12 +286,14 @@ ModelManifest.xml /cmake/MavLinkCom/Makefile /cmake/Makefile /cmake/HelloDrone/Makefile +/cmake/HelloSpawnedDrones/Makefile /cmake/DroneShell/Makefile /cmake/DroneServer/Makefile /cmake/AirLib/Makefile /cmake/AirLibUnity/Makefile /cmake/AirLibUnity/AirLibUnity /cmake/HelloDrone/HelloDrone +/cmake/HelloSpawnedDrones/HelloSpawnedDrones /cmake/DroneShell/DroneShell /cmake/DroneServer/DroneServer cmake/AirLibUnitTests/Makefile diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index 1d17fe9a66..56e9ce567a 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -69,7 +69,7 @@ class RpcLibClientBase { void simPlotLineStrip(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent); void simPlotLineList(const vector& points, const vector& color_rgba, float thickness, float duration, bool is_persistent); void simPlotArrows(const vector& points_start, const vector& points_end, const vector& color_rgba, float thickness, float arrow_size, float duration, bool is_persistent); - void simPlotStrings(const vector& strings, const vector& positions, float scale, const vector& color_rgba, float duration); + void simPlotStrings(const vector& strings, const vector& positions, float scale, const vector& color_rgba, float duration); void simPlotTransforms(const vector& poses, float scale, float thickness, float duration, bool is_persistent); void simPlotTransformsWithNames(const vector& poses, const vector& names, float tf_scale, float tf_thickness, float text_scale, const vector& text_color_rgba, float duration); @@ -97,6 +97,7 @@ class RpcLibClientBase { vector simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name = ""); vector simGetMeshPositionVertexBuffers(); + bool simAddVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = ""); CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const; diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index e98162b306..baaa3c6714 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -5,6 +5,8 @@ #define air_WorldSimApiBase_hpp #include "common/CommonStructs.hpp" +#include "common/AirSimSettings.hpp" + namespace msr { namespace airlib { @@ -45,6 +47,8 @@ class WorldSimApiBase { virtual bool setSegmentationObjectID(const std::string& mesh_name, int object_id, bool is_name_regex = false) = 0; virtual int getSegmentationObjectID(const std::string& mesh_name) const = 0; + virtual bool addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = "") = 0; + virtual void printLogMessage(const std::string& message, const std::string& message_param = "", unsigned char severity = 0) = 0; diff --git a/AirLib/include/common/AirSimSettings.hpp b/AirLib/include/common/AirSimSettings.hpp index 921da43417..2f01fb22c5 100644 --- a/AirLib/include/common/AirSimSettings.hpp +++ b/AirLib/include/common/AirSimSettings.hpp @@ -435,6 +435,22 @@ struct AirSimSettings { settings_json.saveJSonFile(settings_filename); } + // This is for the case when a new vehicle is made on the fly, at runtime + void addVehicleSetting(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path="") + { + auto vehicle_setting = std::unique_ptr(new VehicleSetting()); + + vehicle_setting->vehicle_name = vehicle_name; + vehicle_setting->vehicle_type = vehicle_type; + vehicle_setting->position = pose.position; + vehicle_setting->pawn_path = pawn_path; + + VectorMath::toEulerianAngle(pose.orientation, vehicle_setting->rotation.pitch, + vehicle_setting->rotation.roll, vehicle_setting->rotation.yaw); + + vehicles[vehicle_name] = std::move(vehicle_setting); + } + const VehicleSetting* getVehicleSetting(const std::string& vehicle_name) const { auto it = vehicles.find(vehicle_name); diff --git a/AirLib/include/physics/PhysicsWorld.hpp b/AirLib/include/physics/PhysicsWorld.hpp index f44e334189..dbf0ec8302 100644 --- a/AirLib/include/physics/PhysicsWorld.hpp +++ b/AirLib/include/physics/PhysicsWorld.hpp @@ -43,6 +43,13 @@ class PhysicsWorld { unlock(); } + void addBody(UpdatableObject* body) + { + lock(); + world_.insert(body); + unlock(); + } + uint64_t getUpdatePeriodNanos() const { return update_period_nanos_; diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 60f67d5c5b..50beb9987e 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -40,7 +40,7 @@ STRICT_MODE_OFF STRICT_MODE_ON #ifdef _MSC_VER __pragma(warning( disable : 4239)) -#endif +#endif namespace msr { namespace airlib { @@ -125,7 +125,7 @@ void RpcLibClientBase::confirmConnection() while (getConnectionState() != RpcLibClientBase::ConnectionState::Connected) { std::cout << "X" << std::flush; - clock->sleep_for(pause_time); + clock->sleep_for(pause_time); } std::cout << std::endl << "Connected!" << std::endl; @@ -133,7 +133,7 @@ void RpcLibClientBase::confirmConnection() auto client_ver = getClientVersion(); auto server_min_ver = getMinRequiredServerVersion(); auto client_min_ver = getMinRequiredClientVersion(); - + std::string ver_info = Utils::stringf("Client Ver:%i (Min Req:%i), Server Ver:%i (Min Req:%i)", client_ver, client_min_ver, server_ver, server_min_ver); @@ -221,7 +221,7 @@ void RpcLibClientBase::simSetTraceLine(const std::vector& color_rgba, flo vector RpcLibClientBase::simGetImages(vector request, const std::string& vehicle_name) { - const auto& response_adaptor = pimpl_->client.call("simGetImages", + const auto& response_adaptor = pimpl_->client.call("simGetImages", RpcLibAdapatorsBase::ImageRequest::from(request), vehicle_name) .as>(); @@ -243,6 +243,11 @@ vector RpcLibClientBase::simGetMeshPositionVe return RpcLibAdapatorsBase::MeshPositionVertexBuffersResponse::to(response_adaptor); } +bool RpcLibClientBase::simAddVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path) +{ + return pimpl_->client.call("simAddVehicle", vehicle_name, vehicle_type, RpcLibAdapatorsBase::Pose(pose), pawn_path).as(); +} + void RpcLibClientBase::simPrintLogMessage(const std::string& message, std::string message_param, unsigned char severity) { pimpl_->client.call("simPrintLogMessage", message, message_param, severity); diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 130c409e21..38a8b0cb85 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -49,7 +49,7 @@ struct RpcLibServerBase::impl { ~impl() { } - void stop() { + void stop() { server.close_sessions(); if (!is_async_) { // this deadlocks UI thread if async_run was called while there are pending rpc calls. @@ -91,9 +91,9 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& pimpl_->server.bind("getMinRequiredClientVersion", []() -> int { return 1; }); - - pimpl_->server.bind("simPause", [&](bool is_paused) -> void { - getWorldSimApi()->pause(is_paused); + + pimpl_->server.bind("simPause", [&](bool is_paused) -> void { + getWorldSimApi()->pause(is_paused); }); pimpl_->server.bind("simIsPaused", [&]() -> bool { @@ -110,7 +110,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& pimpl_->server.bind("simSetTimeOfDay", [&](bool is_enabled, const string& start_datetime, bool is_start_datetime_dst, float celestial_clock_speed, float update_interval_secs, bool move_sun) -> void { - getWorldSimApi()->setTimeOfDay(is_enabled, start_datetime, is_start_datetime_dst, + getWorldSimApi()->setTimeOfDay(is_enabled, start_datetime, is_start_datetime_dst, celestial_clock_speed, update_interval_secs, move_sun); }); @@ -122,7 +122,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& getWorldSimApi()->setWeatherParameter(param, val); }); - pimpl_->server.bind("enableApiControl", [&](bool is_enabled, const std::string& vehicle_name) -> void { + pimpl_->server.bind("enableApiControl", [&](bool is_enabled, const std::string& vehicle_name) -> void { getVehicleApi(vehicle_name)->enableApiControl(is_enabled); }); @@ -153,8 +153,12 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return RpcLibAdapatorsBase::MeshPositionVertexBuffersResponse::from(response); }); - pimpl_->server. - bind("simSetVehiclePose", [&](const RpcLibAdapatorsBase::Pose &pose, bool ignore_collision, const std::string& vehicle_name) -> void { + pimpl_->server.bind("simAddVehicle", [&](const std::string& vehicle_name, const std::string& vehicle_type, + const RpcLibAdapatorsBase::Pose& pose, const std::string& pawn_path) -> bool { + return getWorldSimApi()->addVehicle(vehicle_name, vehicle_type, pose.to(), pawn_path); + }); + + pimpl_->server.bind("simSetVehiclePose", [&](const RpcLibAdapatorsBase::Pose &pose, bool ignore_collision, const std::string& vehicle_name) -> void { getVehicleSimApi(vehicle_name)->setPose(pose.to(), ignore_collision); }); @@ -174,7 +178,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& pimpl_->server. bind("simGetSegmentationObjectID", [&](const std::string& mesh_name) -> int { return getWorldSimApi()->getSegmentationObjectID(mesh_name); - }); + }); pimpl_->server.bind("reset", [&]() -> void { //Exit if already resetting. @@ -256,7 +260,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& }); pimpl_->server.bind("simGetCollisionInfo", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::CollisionInfo { - const auto& collision_info = getVehicleSimApi(vehicle_name)->getCollisionInfo(); + const auto& collision_info = getVehicleSimApi(vehicle_name)->getCollisionInfo(); return RpcLibAdapatorsBase::CollisionInfo(collision_info); }); @@ -277,7 +281,7 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& }); pimpl_->server.bind("simGetObjectPose", [&](const std::string& object_name) -> RpcLibAdapatorsBase::Pose { - const auto& pose = getWorldSimApi()->getObjectPose(object_name); + const auto& pose = getWorldSimApi()->getObjectPose(object_name); return RpcLibAdapatorsBase::Pose(pose); }); diff --git a/AirSim.sln b/AirSim.sln index 5d9bf8920d..2ff11e6bfe 100644 --- a/AirSim.sln +++ b/AirSim.sln @@ -1,6 +1,6 @@  Microsoft Visual Studio Solution File, Format Version 12.00 -# Visual Studio 16 +# Visual Studio Version 16 VisualStudioVersion = 16.0.27428.2043 MinimumVisualStudioVersion = 10.0.40219.1 Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "DroneShell", "DroneShell\DroneShell.vcxproj", "{9FE9234B-373A-4D5A-AD6B-FB0B593312DD}" @@ -43,6 +43,8 @@ Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "sgmstereo", "SGM\src\sgmste EndProject Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "stereoPipeline", "SGM\src\stereoPipeline\stereoPipeline.vcxproj", "{E512EB59-4EAB-49D1-9174-0CAF1B40CED0}" EndProject +Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "HelloSpawnedDrones", "HelloSpawnedDrones\HelloSpawnedDrones.vcxproj", "{99CBF376-5EBA-4164-A657-E7D708C9D685}" +EndProject Global GlobalSection(SolutionConfigurationPlatforms) = preSolution Debug|Any CPU = Debug|Any CPU @@ -207,6 +209,18 @@ Global {E512EB59-4EAB-49D1-9174-0CAF1B40CED0}.Release|x64.Build.0 = Release|x64 {E512EB59-4EAB-49D1-9174-0CAF1B40CED0}.Release|x86.ActiveCfg = Release|Win32 {E512EB59-4EAB-49D1-9174-0CAF1B40CED0}.Release|x86.Build.0 = Release|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Debug|Any CPU.ActiveCfg = Debug|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Debug|ARM.ActiveCfg = Debug|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Debug|x64.ActiveCfg = Debug|x64 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Debug|x64.Build.0 = Debug|x64 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Debug|x86.ActiveCfg = Debug|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Debug|x86.Build.0 = Debug|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Release|Any CPU.ActiveCfg = Release|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Release|ARM.ActiveCfg = Release|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Release|x64.ActiveCfg = Release|x64 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Release|x64.Build.0 = Release|x64 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Release|x86.ActiveCfg = Release|Win32 + {99CBF376-5EBA-4164-A657-E7D708C9D685}.Release|x86.Build.0 = Release|Win32 EndGlobalSection GlobalSection(SolutionProperties) = preSolution HideSolutionNode = FALSE diff --git a/HelloDrone/main.cpp b/HelloDrone/main.cpp index 6e0d83574f..578ab69b90 100644 --- a/HelloDrone/main.cpp +++ b/HelloDrone/main.cpp @@ -27,8 +27,10 @@ int main() try { client.confirmConnection(); - std::cout << "Press Enter to get FPV image" << std::endl; std::cin.get(); - vector request = { ImageRequest("0", ImageType::Scene), ImageRequest("1", ImageType::DepthPlanner, true) }; + std::cout << "Press Enter to get FPV image" << std::endl; + std::cin.get(); + + vector request{ ImageRequest("0", ImageType::Scene), ImageRequest("1", ImageType::DepthPlanner, true) }; const vector& response = client.simGetImages(request); std::cout << "# of images received: " << response.size() << std::endl; @@ -56,7 +58,9 @@ int main() } } - std::cout << "Press Enter to arm the drone" << std::endl; std::cin.get(); + std::cout << "Press Enter to arm the drone" << std::endl; + std::cin.get(); + client.enableApiControl(true); client.armDisarm(true); @@ -91,8 +95,8 @@ int main() // << "magnetometer_data.magnetic_field_covariance" << magnetometer_data.magnetic_field_covariance // not implemented in sensor std::cout << "Press Enter to takeoff" << std::endl; std::cin.get(); - float takeoffTimeout = 5; - client.takeoffAsync(takeoffTimeout)->waitOnLastTask(); + float takeoff_timeout = 5; + client.takeoffAsync(takeoff_timeout)->waitOnLastTask(); // switch to explicit hover mode so that this is the fall back when // move* commands are finished. @@ -102,24 +106,26 @@ int main() std::cout << "Press Enter to fly in a 10m box pattern at 3 m/s velocity" << std::endl; std::cin.get(); // moveByVelocityZ is an offboard operation, so we need to set offboard mode. client.enableApiControl(true); + auto position = client.getMultirotorState().getPosition(); float z = position.z(); // current position (NED coordinate system). const float speed = 3.0f; const float size = 10.0f; const float duration = size / speed; - DrivetrainType driveTrain = DrivetrainType::ForwardOnly; + DrivetrainType drivetrain = DrivetrainType::ForwardOnly; YawMode yaw_mode(true, 0); + std::cout << "moveByVelocityZ(" << speed << ", 0, " << z << "," << duration << ")" << std::endl; - client.moveByVelocityZAsync(speed, 0, z, duration, driveTrain, yaw_mode); + client.moveByVelocityZAsync(speed, 0, z, duration, drivetrain, yaw_mode); std::this_thread::sleep_for(std::chrono::duration(duration)); std::cout << "moveByVelocityZ(0, " << speed << "," << z << "," << duration << ")" << std::endl; - client.moveByVelocityZAsync(0, speed, z, duration, driveTrain, yaw_mode); + client.moveByVelocityZAsync(0, speed, z, duration, drivetrain, yaw_mode); std::this_thread::sleep_for(std::chrono::duration(duration)); std::cout << "moveByVelocityZ(" << -speed << ", 0, " << z << "," << duration << ")" << std::endl; - client.moveByVelocityZAsync(-speed, 0, z, duration, driveTrain, yaw_mode); + client.moveByVelocityZAsync(-speed, 0, z, duration, drivetrain, yaw_mode); std::this_thread::sleep_for(std::chrono::duration(duration)); std::cout << "moveByVelocityZ(0, " << -speed << "," << z << "," << duration << ")" << std::endl; - client.moveByVelocityZAsync(0, -speed, z, duration, driveTrain, yaw_mode); + client.moveByVelocityZAsync(0, -speed, z, duration, drivetrain, yaw_mode); std::this_thread::sleep_for(std::chrono::duration(duration)); client.hoverAsync()->waitOnLastTask(); diff --git a/HelloSpawnedDrones/HelloSpawnedDrones.cpp b/HelloSpawnedDrones/HelloSpawnedDrones.cpp new file mode 100644 index 0000000000..0e5b2ba78b --- /dev/null +++ b/HelloSpawnedDrones/HelloSpawnedDrones.cpp @@ -0,0 +1,173 @@ +// Copyright (c) Microsoft Corporation. All rights reserved. +// Licensed under the MIT License. + +#include "common/common_utils/StrictMode.hpp" +STRICT_MODE_OFF +#ifndef RPCLIB_MSGPACK +#define RPCLIB_MSGPACK clmdep_msgpack +#endif // !RPCLIB_MSGPACK +#include "rpc/rpc_error.h" +STRICT_MODE_ON + +#include "vehicles/multirotor/api/MultirotorRpcLibClient.hpp" +#include "common/common_utils/FileSystem.hpp" +#include +#include +#include +#include + + +void runSingleClient(uint16_t port, int ordinal) +{ + using namespace msr::airlib; + const char host[] = "localhost"; + float timeout_s = 60; + + try + { + MultirotorRpcLibClient *client = new MultirotorRpcLibClient(host, port, timeout_s); + std::cout << "Confirming connections..." << std::endl; + client->confirmConnection(); + + std::string vehicle_name = "UAV_" + std::to_string(ordinal); + std::cout << "Vehicle name:" << vehicle_name << std::endl; + + Pose pose(Vector3r(0, 5.0f * (ordinal + 1), 0), Quaternionr(0, 0, 0, 0)); + client->simAddVehicle(vehicle_name, "simpleflight", pose, ""); + + // This is a bit crude, but give it a moment to settle on the ground, else takeoff will fail + std::this_thread::sleep_for(std::chrono::duration(2)); + + // moveByVelocityZ is an offboard operation, so we need to set offboard mode. + client->enableApiControl(true, vehicle_name); + client->armDisarm(true, vehicle_name); + + auto ground_pos = client->getMultirotorState(vehicle_name).getPosition(); + float groundZ = ground_pos.z(); // current position (NED coordinate system). + + float takeoff_timeout = 5; + std::cout << "Initiating takeoff for " << vehicle_name << "..." << std::endl; + client->takeoffAsync(takeoff_timeout, vehicle_name)->waitOnLastTask(); + std::cout << "Completed takeoff for " << vehicle_name << "..." << std::endl; + + const float speed = 3.0f; + + // switch to explicit hover mode so that this is the fallback when + // move* commands are finished. + std::cout << "Initiating hover for " << vehicle_name << "..." << std::endl; + client->hoverAsync(vehicle_name)->waitOnLastTask(); + std::cout << "Completed hover for " << vehicle_name << "..." << std::endl; + + auto position = client->getMultirotorState(vehicle_name).getPosition(); + float duration = 1; + float z = position.z(); // current position (NED coordinate system). + + // Altitude difference between each platform, in meters + const float altitude_delta = 1.0f; + + z -= ordinal * altitude_delta; + float timeout = 10.0f; + client->moveToZAsync(z, speed, timeout, YawMode(), -1.0f, 1.0f, vehicle_name)->waitOnLastTask(); + + std::cout << "Completed move to z " << z << " for " << vehicle_name << "..." << std::endl; + std::cout << "Flying in a 10m box pattern at 3 m/s velocity" << std::endl; + + const float size = 5.0f; + duration = size / speed; + DrivetrainType drivetrain = DrivetrainType::ForwardOnly; + YawMode yaw_mode(true, 0); + + position = client->getMultirotorState(vehicle_name).getPosition(); + std::cout << "Position of " << port << ": " << position << std::endl; + z = position.z(); // current position (NED coordinate system). + + std::cout << "moveByVelocityZ(" << speed << ", 0, " << z << "," << duration << ")" << std::endl; + client->moveByVelocityZAsync(speed, 0, z, duration, drivetrain, yaw_mode, vehicle_name); + std::this_thread::sleep_for(std::chrono::duration(duration)); + std::cout << "moveByVelocityZ(0, " << speed << "," << z << "," << duration << ")" << std::endl; + client->moveByVelocityZAsync(0, speed, z, duration, drivetrain, yaw_mode, vehicle_name); + std::this_thread::sleep_for(std::chrono::duration(duration)); + std::cout << "moveByVelocityZ(" << -speed << ", 0, " << z << "," << duration << ")" << std::endl; + client->moveByVelocityZAsync(-speed, 0, z, duration, drivetrain, yaw_mode, vehicle_name); + std::this_thread::sleep_for(std::chrono::duration(duration)); + std::cout << "moveByVelocityZ(0, " << -speed << "," << z << "," << duration << ")" << std::endl; + client->moveByVelocityZAsync(0, -speed, z, duration, drivetrain, yaw_mode, vehicle_name); + + std::this_thread::sleep_for(std::chrono::duration(duration)); + + client->moveToZAsync(groundZ - 0.5f, speed, timeout, YawMode(), -1.0f, 1.0f, vehicle_name)->waitOnLastTask(); + + std::cout << "Hovering..." << std::endl; + client->hoverAsync(vehicle_name)->waitOnLastTask(); + + client->enableApiControl(true, vehicle_name); + + std::cout << "Landing..." << std::endl; + client->landAsync(timeout, vehicle_name)->waitOnLastTask(); + std::this_thread::sleep_for(std::chrono::duration(5)); + + std::cout << "Disarming..." << std::endl; + client->armDisarm(false, vehicle_name); + + std::cout << "Done!..." << std::endl; + + delete client; + + std::this_thread::sleep_for(std::chrono::duration(50)); + } + catch (rpc::rpc_error& e) + { + std::string msg = e.get_error().as(); + std::cout << "Exception raised by the API, something went wrong." << std::endl << msg << std::endl; + } +} + +int main(int argc, char *argv[]) +{ + using namespace msr::airlib; + + uint16_t rpc_port = 41451; + int num_platforms = 1; + + std::cout << "argc is " << argc << std::endl; + if (argc > 1) + { + std::cout << "Num plats string: " << argv[1] << std::endl; + num_platforms = static_cast(std::stoi(argv[1])); + } + + std::cout << "First port is " << rpc_port << std::endl; + std::cout << "Num platforms: " << num_platforms << std::endl; + std::cout << "Making clients..." << std::endl; + + + try + { + std::cout << "Press Enter to begin..." << std::endl; + std::cin.get(); + + std::vector clientThreads; + + // Count down, so the first one can easily go the highest (without knowing count) + int client_ordinal = num_platforms - 1; + for (int i = 0; i < num_platforms; i++) + { + clientThreads.push_back(std::thread(runSingleClient, rpc_port, client_ordinal)); + client_ordinal--; + + std::this_thread::sleep_for(std::chrono::duration(0.1)); + } + + for (auto &toJoin : clientThreads) + { + toJoin.join(); + } + } + catch (rpc::rpc_error& e) + { + std::string msg = e.get_error().as(); + std::cout << "Exception raised by the API, something went wrong." << std::endl << msg << std::endl; + } + + return 0; +} diff --git a/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj b/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj new file mode 100644 index 0000000000..d150fadca8 --- /dev/null +++ b/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj @@ -0,0 +1,177 @@ + + + + + Debug + Win32 + + + Release + Win32 + + + Debug + x64 + + + Release + x64 + + + + + {4bfb7231-077a-4671-bd21-d3ade3ea36e7} + + + {8510c7a4-bf63-41d2-94f6-d8731d137a5a} + + + + 15.0 + {99CBF376-5EBA-4164-A657-E7D708C9D685} + Win32Proj + HelloSpawnedDrones + 10.0 + + + + Application + true + v142 + Unicode + + + Application + false + v142 + true + Unicode + + + Application + true + v142 + Unicode + + + Application + false + v142 + true + Unicode + + + + + + + + + + + + + + + + + + + + + true + $(ProjectDir)build\$(Platform)\$(Configuration)\ + $(ProjectDir)temp\$(ProjectName)\$(Platform)\$(Configuration)\ + + + true + $(ProjectDir)temp\$(ProjectName)\$(Platform)\$(Configuration)\ + $(ProjectDir)build\$(Platform)\$(Configuration)\ + + + false + $(ProjectDir)build\$(Platform)\$(Configuration)\ + $(ProjectDir)temp\$(ProjectName)\$(Platform)\$(Configuration)\ + + + false + $(ProjectDir)temp\$(ProjectName)\$(Platform)\$(Configuration)\ + $(ProjectDir)build\$(Platform)\$(Configuration)\ + + + + NotUsing + Level3 + Disabled + true + _DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + $(ProjectDir)..\AirLib\deps\rpclib\include;include;$(ProjectDir)..\AirLib\deps\eigen3;$(ProjectDir)..\AirLib\include + + + Console + true + $(ProjectDir)\..\AirLib\deps\MavLinkCom\lib\$(Platform)\$(Configuration);$(ProjectDir)\..\AirLib\deps\rpclib\lib\$(Platform)\$(Configuration);$(ProjectDir)\..\AirLib\lib\$(Platform)\$(Configuration);%(AdditionalLibraryDirectories) + rpc.lib;AirLib.lib;%(AdditionalDependencies) + + + + + Use + Level3 + Disabled + true + WIN32;_DEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + + + Console + true + + + + + Use + Level3 + MaxSpeed + true + true + true + WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + + + Console + true + true + true + + + + + NotUsing + Level3 + MaxSpeed + true + true + true + NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + true + $(ProjectDir)..\AirLib\deps\rpclib\include;include;$(ProjectDir)..\AirLib\deps\eigen3;$(ProjectDir)..\AirLib\include + + + Console + true + true + true + $(ProjectDir)\..\AirLib\deps\MavLinkCom\lib\$(Platform)\$(Configuration);$(ProjectDir)\..\AirLib\deps\rpclib\lib\$(Platform)\$(Configuration);$(ProjectDir)\..\AirLib\lib\$(Platform)\$(Configuration);%(AdditionalLibraryDirectories) + rpc.lib;AirLib.lib;%(AdditionalDependencies) + + + + + + + + + \ No newline at end of file diff --git a/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj.filters b/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj.filters new file mode 100644 index 0000000000..d428262af8 --- /dev/null +++ b/HelloSpawnedDrones/HelloSpawnedDrones.vcxproj.filters @@ -0,0 +1,6 @@ + + + + + + \ No newline at end of file diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index 762a1269a9..0d4026261d 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -856,6 +856,22 @@ def simCreateVoxelGrid(self, position, x, y, z, res, of): """ return self.client.call('simCreateVoxelGrid', position, x, y, z, res, of) + # Add new vehicle via RPC + def simAddVehicle(self, vehicle_name, vehicle_type, pose, pawn_path = ""): + """ + Create vehicle at runtime + + Args: + 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 + + Returns: + bool: Whether vehicle was created + """ + return self.client.call('simAddVehicle', vehicle_name, vehicle_type, pose, pawn_path) + # ----------------------------------- Multirotor APIs --------------------------------------------- class MultirotorClient(VehicleClient, object): def __init__(self, ip = "", port = 41451, timeout_value = 3600): diff --git a/PythonClient/multirotor/add_drone.py b/PythonClient/multirotor/add_drone.py new file mode 100644 index 0000000000..fd740dd5d5 --- /dev/null +++ b/PythonClient/multirotor/add_drone.py @@ -0,0 +1,46 @@ +import setup_path +import airsim +import tempfile +import os +import numpy as np +import cv2 +import pprint + +# connect to the AirSim simulator +client = airsim.MultirotorClient() +client.confirmConnection() + +# add new vehicle +vehicle_name = "Drone2" +pose = airsim.Pose(airsim.Vector3r(0, 0, 0), airsim.to_quaternion(0, 0, 0)) + +client.simAddVehicle(vehicle_name, "simpleflight", pose) +client.enableApiControl(True, vehicle_name) +client.armDisarm(True, vehicle_name) +client.takeoffAsync(10.0, vehicle_name) + +requests = [airsim.ImageRequest("0", airsim.ImageType.DepthVis), #depth visualization image + airsim.ImageRequest("1", airsim.ImageType.DepthPerspective, True), #depth in perspective projection + airsim.ImageRequest("1", airsim.ImageType.Scene), #scene vision image in png format + airsim.ImageRequest("1", airsim.ImageType.Scene, False, False)] #scene vision image in uncompressed RGBA array + +responses = client.simGetImages(requests, vehicle_name=vehicle_name) +print('Retrieved images: %d' % len(responses)) + +tmp_dir = os.path.join(tempfile.gettempdir(), "airsim_drone") +print ("Saving images to %s" % tmp_dir) +try: + os.makedirs(tmp_dir) +except OSError: + if not os.path.isdir(tmp_dir): + raise + +for idx, response in enumerate(responses): + filename = os.path.join(tmp_dir, str(idx)) + + if response.pixels_as_float: + print("Type %d, size %d, pos %s" % (response.image_type, len(response.image_data_float), pprint.pformat(response.camera_position))) + airsim.write_pfm(os.path.normpath(filename + '.pfm'), airsim.get_pfm_array(response)) + else: + print("Type %d, size %d, pos %s" % (response.image_type, len(response.image_data_uint8), pprint.pformat(response.camera_position))) + airsim.write_file(os.path.normpath(filename + '.png'), response.image_data_uint8) \ No newline at end of file diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp index 4679fea828..cc881cad32 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.cpp @@ -195,4 +195,12 @@ void WorldSimApi::setWind(const Vector3r& wind) const simmode_->setWind(wind); }; +bool WorldSimApi::addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const WorldSimApi::Pose& pose, const std::string& pawn_path) +{ + throw std::invalid_argument(common_utils::Utils::stringf( + "addVehicle is not supported on unity").c_str()); + return false; +} + + #pragma endregion diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h index d19928bd9b..548f4b2149 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/WorldSimApi.h @@ -64,6 +64,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; private: SimModeBase * simmode_; diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index e2ef6a0fae..d81d6f9780 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -556,6 +556,91 @@ FRotator ASimModeBase::toFRotator(const msr::airlib::AirSimSettings::Rotation& r return frotator; } +APawn* ASimModeBase::createVehiclePawn(const AirSimSettings::VehicleSetting& vehicle_setting) +{ + //get UU origin of global NED frame + const FTransform uu_origin = getGlobalNedTransform().getGlobalTransform(); + + // compute initial pose + FVector spawn_position = uu_origin.GetLocation(); + Vector3r settings_position = vehicle_setting.position; + if (!VectorMath::hasNan(settings_position)) + spawn_position = getGlobalNedTransform().fromGlobalNed(settings_position); + + FRotator spawn_rotation = toFRotator(vehicle_setting.rotation, uu_origin.Rotator()); + + std::string vehicle_name = vehicle_setting.vehicle_name; + + //spawn vehicle pawn + FActorSpawnParameters pawn_spawn_params; + pawn_spawn_params.Name = FName(vehicle_name.c_str()); + pawn_spawn_params.SpawnCollisionHandlingOverride = + ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn; + + auto vehicle_bp_class = UAirBlueprintLib::LoadClass( + getSettings().pawn_paths.at(getVehiclePawnPathName(vehicle_setting)).pawn_bp); + APawn* spawned_pawn = static_cast(this->GetWorld()->SpawnActor( + vehicle_bp_class, &spawn_position, &spawn_rotation, pawn_spawn_params)); + + spawned_actors_.Add(spawned_pawn); + + return spawned_pawn; +} + +std::unique_ptr ASimModeBase::createVehicleApi(APawn* vehicle_pawn) +{ + initializeVehiclePawn(vehicle_pawn); + + //create vehicle sim api + const auto& ned_transform = getGlobalNedTransform(); + const auto& pawn_ned_pos = ned_transform.toLocalNed(vehicle_pawn->GetActorLocation()); + const auto& home_geopoint = msr::airlib::EarthUtils::nedToGeodetic(pawn_ned_pos, getSettings().origin_geopoint); + const std::string vehicle_name( TCHAR_TO_UTF8(*(vehicle_pawn->GetName())) ); + + PawnSimApi::Params pawn_sim_api_params(vehicle_pawn, &getGlobalNedTransform(), + getVehiclePawnEvents(vehicle_pawn), getVehiclePawnCameras(vehicle_pawn), pip_camera_class, + collision_display_template, home_geopoint, vehicle_name); + + std::unique_ptr vehicle_sim_api = createVehicleSimApi(pawn_sim_api_params); + auto vehicle_sim_api_p = vehicle_sim_api.get(); + auto vehicle_api = getVehicleApi(pawn_sim_api_params, vehicle_sim_api_p); + getApiProvider()->insert_or_assign(vehicle_name, vehicle_api, vehicle_sim_api_p); + + return vehicle_sim_api; +} + +bool ASimModeBase::createVehicleAtRuntime(const std::string& vehicle_name, const std::string& vehicle_type, + const msr::airlib::Pose& pose, const std::string& pawn_path) +{ + if (!isVehicleTypeSupported(vehicle_type)) { + Utils::log(Utils::stringf("Vehicle type %s is not supported in this game mode", vehicle_type.c_str()), Utils::kLogLevelWarn); + return false; + } + + // TODO: Figure out a better way to add more fields + // Maybe allow passing a JSON string for the vehicle settings? + + // Retroactively adjust AirSimSettings, so it's like we knew about this vehicle all along + AirSimSettings::singleton().addVehicleSetting(vehicle_name, vehicle_type, pose, pawn_path); + const auto* vehicle_setting = getSettings().getVehicleSetting(vehicle_name); + + auto spawned_pawn = createVehiclePawn(*vehicle_setting); + + auto vehicle_sim_api = createVehicleApi(spawned_pawn); + + // Usually physics registration happens at init, in ASimModeWorldBase::initializeForPlay(), but not in this case + vehicle_sim_api->reset(); + registerPhysicsBody(vehicle_sim_api.get()); + + // Can't be done before the vehicle apis have been created + if ((vehicle_setting->is_fpv_vehicle || !getApiProvider()->hasDefaultVehicle()) && vehicle_name != "") + getApiProvider()->makeDefaultVehicle(vehicle_name); + + vehicle_sim_apis_.push_back(std::move(vehicle_sim_api)); + + return true; +} + void ASimModeBase::setupVehiclesAndCamera() { //get UU origin of global NED frame @@ -580,31 +665,14 @@ void ASimModeBase::setupVehiclesAndCamera() fpv_pawn = static_cast(pawns[0]); } else { //add vehicles from settings - for (auto const& vehicle_setting_pair : getSettings().vehicles) + for (const auto& vehicle_setting_pair : getSettings().vehicles) { //if vehicle is of type for derived SimMode and auto creatable const auto& vehicle_setting = *vehicle_setting_pair.second; if (vehicle_setting.auto_create && isVehicleTypeSupported(vehicle_setting.vehicle_type)) { - //compute initial pose - FVector spawn_position = uu_origin.GetLocation(); - Vector3r settings_position = vehicle_setting.position; - if (!VectorMath::hasNan(settings_position)) - spawn_position = getGlobalNedTransform().fromGlobalNed(settings_position); - FRotator spawn_rotation = toFRotator(vehicle_setting.rotation, uu_origin.Rotator()); - - //spawn vehicle pawn - FActorSpawnParameters pawn_spawn_params; - pawn_spawn_params.Name = FName(vehicle_setting.vehicle_name.c_str()); - pawn_spawn_params.SpawnCollisionHandlingOverride = - ESpawnActorCollisionHandlingMethod::AdjustIfPossibleButAlwaysSpawn; - auto vehicle_bp_class = UAirBlueprintLib::LoadClass( - getSettings().pawn_paths.at(getVehiclePawnPathName(vehicle_setting)).pawn_bp); - APawn* spawned_pawn = static_cast(this->GetWorld()->SpawnActor( - vehicle_bp_class, &spawn_position, &spawn_rotation, pawn_spawn_params)); - - spawned_actors_.Add(spawned_pawn); + auto spawned_pawn = createVehiclePawn(vehicle_setting); pawns.Add(spawned_pawn); if (vehicle_setting.is_fpv_vehicle) @@ -615,24 +683,11 @@ void ASimModeBase::setupVehiclesAndCamera() //create API objects for each pawn we have for (AActor* pawn : pawns) { - APawn* vehicle_pawn = static_cast(pawn); - - initializeVehiclePawn(vehicle_pawn); + auto vehicle_pawn = static_cast(pawn); - //create vehicle sim api - const auto& ned_transform = getGlobalNedTransform(); - const auto& pawn_ned_pos = ned_transform.toLocalNed(vehicle_pawn->GetActorLocation()); - const auto& home_geopoint= msr::airlib::EarthUtils::nedToGeodetic(pawn_ned_pos, getSettings().origin_geopoint); - const std::string vehicle_name = std::string(TCHAR_TO_UTF8(*(vehicle_pawn->GetName()))); - - PawnSimApi::Params pawn_sim_api_params(vehicle_pawn, &getGlobalNedTransform(), - getVehiclePawnEvents(vehicle_pawn), getVehiclePawnCameras(vehicle_pawn), pip_camera_class, - collision_display_template, home_geopoint, vehicle_name); + auto vehicle_sim_api = createVehicleApi(vehicle_pawn); + std::string vehicle_name = vehicle_sim_api->getVehicleName(); - auto vehicle_sim_api = createVehicleSimApi(pawn_sim_api_params); - auto vehicle_sim_api_p = vehicle_sim_api.get(); - auto vehicle_Api = getVehicleApi(pawn_sim_api_params, vehicle_sim_api_p); - getApiProvider()->insert_or_assign(vehicle_name, vehicle_Api, vehicle_sim_api_p); if ((fpv_pawn == vehicle_pawn || !getApiProvider()->hasDefaultVehicle()) && vehicle_name != "") getApiProvider()->makeDefaultVehicle(vehicle_name); @@ -652,6 +707,12 @@ void ASimModeBase::setupVehiclesAndCamera() checkVehicleReady(); } +void ASimModeBase::registerPhysicsBody(msr::airlib::VehicleSimApiBase *physicsBody) +{ + // derived class shoudl override this method to add new vehicle to the physics engine +} + + void ASimModeBase::getExistingVehiclePawns(TArray& pawns) const { //derived class should override this method to retrieve types of pawns they support diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h index b23be7a3dc..6938413f20 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -75,6 +75,9 @@ class AIRSIM_API ASimModeBase : public AActor void stopApiServer(); bool isApiServerStarted(); + bool createVehicleAtRuntime(const std::string& vehicle_name, const std::string& vehicle_type, + const msr::airlib::Pose& pose, const std::string& pawn_path = ""); + const NedTransform& getGlobalNedTransform(); msr::airlib::ApiProvider* getApiProvider() const @@ -107,8 +110,11 @@ class AIRSIM_API ASimModeBase : public AActor const PawnSimApi::Params& pawn_sim_api_params) const; virtual msr::airlib::VehicleApiBase* getVehicleApi(const PawnSimApi::Params& pawn_sim_api_params, const PawnSimApi* sim_api) const; + virtual void registerPhysicsBody(msr::airlib::VehicleSimApiBase *physicsBody); protected: //optional overrides + virtual APawn* createVehiclePawn(const AirSimSettings::VehicleSetting& vehicle_setting); + virtual std::unique_ptr createVehicleApi(APawn* vehicle_pawn); virtual void setupVehiclesAndCamera(); virtual void setupInputBindings(); //called when SimMode should handle clock speed setting diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp index dd157d5cf3..f325be9ace 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.cpp @@ -21,6 +21,12 @@ void ASimModeWorldBase::initializeForPlay() vehicles, getPhysicsLoopPeriod())); } +void ASimModeWorldBase::registerPhysicsBody(msr::airlib::VehicleSimApiBase *physicsBody) +{ + physics_world_.get()->addBody(physicsBody); +} + + void ASimModeWorldBase::EndPlay(const EEndPlayReason::Type EndPlayReason) { //remove everything that we created in BeginPlay diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.h index 82d65236dd..723d25fc45 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldBase.h @@ -42,6 +42,9 @@ class AIRSIM_API ASimModeWorldBase : public ASimModeBase //should be called by derived class once all api_provider_ is ready to use void initializeForPlay(); + //used for adding physics bodies on the fly + virtual void registerPhysicsBody(msr::airlib::VehicleSimApiBase *physicsBody) override; + long long getPhysicsLoopPeriod() const; void setPhysicsLoopPeriod(long long period); private: diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index f7679c12d7..6de0bacc01 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -268,6 +268,16 @@ void WorldSimApi::setTimeOfDay(bool is_enabled, const std::string& start_datetim celestial_clock_speed, update_interval_secs, move_sun); } +bool WorldSimApi::addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path) +{ + bool result; + UAirBlueprintLib::RunCommandOnGameThread([&]() { + result = simmode_->createVehicleAtRuntime(vehicle_name, vehicle_type, pose, pawn_path); + }, true); + + return result; +} + bool WorldSimApi::setSegmentationObjectID(const std::string& mesh_name, int object_id, bool is_name_regex) { bool success; diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index 9e3ff509fc..8ca7b8de7e 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -38,6 +38,8 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual bool setSegmentationObjectID(const std::string& mesh_name, int object_id, bool is_name_regex = false) override; virtual int getSegmentationObjectID(const std::string& mesh_name) const override; + virtual bool addVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const Pose& pose, const std::string& pawn_path = "") override; + virtual void printLogMessage(const std::string& message, const std::string& message_param = "", unsigned char severity = 0) override; diff --git a/cmake/CMakeLists.txt b/cmake/CMakeLists.txt index 5e31535511..d5dbc29235 100644 --- a/cmake/CMakeLists.txt +++ b/cmake/CMakeLists.txt @@ -6,6 +6,7 @@ add_subdirectory("AirLib") add_subdirectory("MavLinkCom") add_subdirectory("AirLibUnitTests") add_subdirectory("HelloDrone") +add_subdirectory("HelloSpawnedDrones") add_subdirectory("HelloCar") add_subdirectory("DroneShell") add_subdirectory("DroneServer") diff --git a/cmake/HelloSpawnedDrones/CMakeLists.txt b/cmake/HelloSpawnedDrones/CMakeLists.txt new file mode 100644 index 0000000000..32906f0081 --- /dev/null +++ b/cmake/HelloSpawnedDrones/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.5.0) +project(HelloSpawnedDrones) + +LIST(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../cmake-modules") +INCLUDE("${CMAKE_CURRENT_LIST_DIR}/../cmake-modules/CommonSetup.cmake") +CommonSetup() + +IncludeEigen() + +SetupConsoleBuild() + +## Specify additional locations of header files +include_directories( + ${AIRSIM_ROOT}/HelloSpawnedDrones + ${AIRSIM_ROOT}/AirLib/include + ${RPC_LIB_INCLUDES} + ${AIRSIM_ROOT}/MavLinkCom/include + ${AIRSIM_ROOT}/MavLinkCom/common_utils +) + +AddExecutableSource() + +CommonTargetLink() +target_link_libraries(${PROJECT_NAME} AirLib) +target_link_libraries(${PROJECT_NAME} ${RPC_LIB}) diff --git a/docs/apis_cpp.md b/docs/apis_cpp.md index b9255c30f5..0e87e2c2ac 100644 --- a/docs/apis_cpp.md +++ b/docs/apis_cpp.md @@ -88,5 +88,6 @@ int main() ## See Also * [Examples](../Examples) of how to use internal infrastructure in AirSim in your other projects * [DroneShell](../DroneShell) app shows how to make simple interface using C++ APIs to control drones +* [HelloSpawnedDrones](../HelloSpawnedDrones) app shows how to make additional vehicles on the fly * [Python APIs](apis.md)