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

Spawn vehicles via rpc #1937

Closed
Closed
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
4 changes: 3 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -361,4 +363,4 @@ xcuserdata/
/Unity/UnityDemo/Assembly-CSharp.csproj
/Unity/UnityDemo/UnityDemo.sln
/Unity/UnityDemo/Logs/
/Unity/UnityDemo/Assets/Plugins/AirsimWrapper.dll
/Unity/UnityDemo/Assets/Plugins/AirsimWrapper.dll
2 changes: 2 additions & 0 deletions AirLib/include/api/RpcLibClientBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,8 @@ class RpcLibClientBase {
vector<ImageCaptureBase::ImageResponse> simGetImages(vector<ImageCaptureBase::ImageRequest> request, const std::string& vehicle_name = "");
vector<uint8_t> simGetImage(const std::string& camera_name, ImageCaptureBase::ImageType type, const std::string& vehicle_name = "");

bool simAddVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const std::string& pawn_path, float north, float east, float down);
Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

client.simAddVehicle("My", "simpleflight", "", 0, 0, 0);
client.enableApiControl(true, "My");
client.armDisarm(true, "My");
client.takeoffAsync(1.0, "My")->waitOnLastTask();
client.moveToPositionAsync(10, 10, -10, 10, 10, DrivetrainType::ForwardOnly, YawMode(false, 0.0), -1.0, 1.0, "My")->waitOnLastTask();
Don't know why these commands go wrong

Copy link

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The error message looks like this:
LogTemp: Error: Exception occurred while updating world: PositionController does not support yaw axis i.e. 3
LogTemp: Error: Exception occurred while updating world: reset() must be called first before update()
LogTemp: Error: Exception occurred while updating world: reset() must be called first before update()
LogTemp: Error: Exception occurred while updating world: reset() must be called first before update()


CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const;

CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const;
Expand Down
4 changes: 4 additions & 0 deletions AirLib/include/api/WorldSimApiBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@
#define air_WorldSimApiBase_hpp

#include "common/CommonStructs.hpp"
#include "common/AirSimSettings.hpp"


namespace msr { namespace airlib {

Expand Down Expand Up @@ -39,6 +41,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 createVehicleAtRuntime(AirSimSettings::VehicleSetting& vehicle_setting) = 0;

virtual void printLogMessage(const std::string& message,
const std::string& message_param = "", unsigned char severity = 0) = 0;

Expand Down
9 changes: 9 additions & 0 deletions AirLib/include/common/AirSimSettings.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -406,6 +406,15 @@ 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 VehicleSetting &vehicle_setting)
{
std::unique_ptr<VehicleSetting> vehicle_setting_p = std::unique_ptr<VehicleSetting>(new VehicleSetting());

// Usually we have a pointer to an entry from the json, but here we have to make a new one
vehicles[vehicle_setting.vehicle_name] = std::move(vehicle_setting_p);
}

const VehicleSetting* getVehicleSetting(const std::string& vehicle_name) const
{
auto it = vehicles.find(vehicle_name);
Expand Down
7 changes: 7 additions & 0 deletions AirLib/include/physics/PhysicsWorld.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,13 @@ class PhysicsWorld {
unlock();
}

void addBody(UpdatableObject* body)
{
lock();
world_.insert(body);
unlock();
}

uint64_t getUpdatePeriodNanos() const
{
return update_period_nanos_;
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 @@ -232,6 +232,11 @@ vector<uint8_t> RpcLibClientBase::simGetImage(const std::string& camera_name, Im
return result;
}

bool RpcLibClientBase::simAddVehicle(const std::string& vehicle_name, const std::string& vehicle_type, const std::string& pawn_path, float north, float east, float down)
{
return pimpl_->client.call("simAddVehicle", vehicle_name, vehicle_type, pawn_path, north, east, down).as<bool>();
}

void RpcLibClientBase::simPrintLogMessage(const std::string& message, std::string message_param, unsigned char severity)
{
pimpl_->client.call("simPrintLogMessage", message, message_param, severity);
Expand Down
23 changes: 21 additions & 2 deletions AirLib/src/api/RpcLibServerBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,8 +115,27 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string&
return result;
});

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 std::string& pawn_path, float north, float east, float down) -> bool {

AirSimSettings::VehicleSetting vehicle_setting;

// TODO expose other VehicleSettings fields
vehicle_setting.vehicle_name = vehicle_name;
vehicle_setting.vehicle_type = vehicle_type;
vehicle_setting.pawn_path = pawn_path;

vehicle_setting.position[0] = north;
vehicle_setting.position[1] = east;
vehicle_setting.position[2] = down;

vehicle_setting.rotation.yaw = 0;
vehicle_setting.rotation.pitch = 0;
vehicle_setting.rotation.roll = 0;

return getWorldSimApi()->createVehicleAtRuntime(vehicle_setting);
});

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);
});
pimpl_->server.bind("simGetVehiclePose", [&](const std::string& vehicle_name) -> RpcLibAdapatorsBase::Pose {
Expand Down
Loading