Skip to content

Commit

Permalink
API framework refactoring, Part 1: pawn wrapper provides API
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Apr 24, 2018
1 parent 57de2f2 commit 9850a08
Show file tree
Hide file tree
Showing 18 changed files with 106 additions and 17 deletions.
1 change: 1 addition & 0 deletions AirLib/AirLib.vcxproj
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<ClInclude Include="include\api\RpcLibClientBase.hpp" />
<ClInclude Include="include\api\RpcLibServerBase.hpp" />
<ClInclude Include="include\api\VehicleApiBase.hpp" />
<ClInclude Include="include\api\WorldApiBase.hpp" />
<ClInclude Include="include\common\AirSimSettings.hpp" />
<ClInclude Include="include\common\ClockBase.hpp" />
<ClInclude Include="include\common\Common.hpp" />
Expand Down
3 changes: 3 additions & 0 deletions AirLib/AirLib.vcxproj.filters
Original file line number Diff line number Diff line change
Expand Up @@ -489,6 +489,9 @@
<ClInclude Include="include\common\EarthCelestial.hpp">
<Filter>Header Files</Filter>
</ClInclude>
<ClInclude Include="include\api\WorldApiBase.hpp">
<Filter>Header Files</Filter>
</ClInclude>
</ItemGroup>
<ItemGroup>
<ClCompile Include="src\safety\ObstacleMap.cpp">
Expand Down
21 changes: 21 additions & 0 deletions AirLib/include/api/SimModeApiBase.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
// Copyright (c) Microsoft Corporation. All rights reserved.
// Licensed under the MIT License.

#ifndef air_SimModeApiBase_hpp
#define air_SimModeApiBase_hpp

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

namespace msr { namespace airlib {


class SimModeApiBase {
public:
virtual VehicleApiBase* getVehicleApi() = 0;
virtual ~SimModeApiBase() = default;
};


}} //namespace
#endif
2 changes: 1 addition & 1 deletion PythonClient/PythonClient.pyproj
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<SchemaVersion>2.0</SchemaVersion>
<ProjectGuid>e2049e20-b6dd-474e-8bca-1c8dc54725aa</ProjectGuid>
<ProjectHome>.</ProjectHome>
<StartupFile>hello_car.py</StartupFile>
<StartupFile>hello_drone.py</StartupFile>
<SearchPath>
</SearchPath>
<WorkingDirectory>.</WorkingDirectory>
Expand Down
23 changes: 14 additions & 9 deletions Unreal/Plugins/AirSim/Source/Car/CarPawn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -217,22 +217,27 @@ void ACarPawn::initializeForBeginPlay(bool enable_rpc, const std::string& api_se
void ACarPawn::reset(bool disable_api_control)
{
keyboard_controls_ = joystick_controls_ = CarPawnApi::CarControls();
api_->reset();
wrapper_->setApi(std::unique_ptr<msr::airlib::CarApiBase>());

if (disable_api_control)
api_->enableApiControl(false);
getApi()->enableApiControl(false);
}

msr::airlib::CarApiBase* ACarPawn::getApi() const
{
return static_cast<msr::airlib::CarApiBase*>(wrapper_->getApi());
}

void ACarPawn::startApiServer(bool enable_rpc, const std::string& api_server_address)
{
if (enable_rpc) {
api_.reset(new CarPawnApi(getVehiclePawnWrapper(), this->GetVehicleMovement()));

wrapper_->setApi(std::unique_ptr<msr::airlib::CarApiBase>(
new CarPawnApi(getVehiclePawnWrapper(), this->GetVehicleMovement())));

#ifdef AIRLIB_NO_RPC
rpclib_server_.reset(new msr::airlib::DebugApiServer());
#else
rpclib_server_.reset(new msr::airlib::CarRpcLibServer(api_.get(), api_server_address));
rpclib_server_.reset(new msr::airlib::CarRpcLibServer(getApi(), api_server_address));
#endif

rpclib_server_->start();
Expand All @@ -248,7 +253,7 @@ void ACarPawn::stopApiServer()
if (rpclib_server_ != nullptr) {
rpclib_server_->stop();
rpclib_server_.reset(nullptr);
api_.reset(nullptr);
wrapper_->setApi(std::unique_ptr<msr::airlib::CarApiBase>());
}
}

Expand Down Expand Up @@ -451,13 +456,13 @@ void ACarPawn::updateCarControls()
}

//if API-client control is not active then we route keyboard/jostick control to car
if (!api_->isApiControlEnabled()) {
if (! getApi()->isApiControlEnabled()) {
//all car controls from anywhere must be routed through API component
api_->setCarControls(current_controls_);
getApi()->setCarControls(current_controls_);
}
else {
UAirBlueprintLib::LogMessageString("Control Mode: ", "API", LogDebugLevel::Informational);
current_controls_ = api_->getCarControls();
current_controls_ = getApi()->getCarControls();
}
UAirBlueprintLib::LogMessageString("Accel: ", std::to_string(current_controls_.throttle), LogDebugLevel::Informational);
UAirBlueprintLib::LogMessageString("Break: ", std::to_string(current_controls_.brake), LogDebugLevel::Informational);
Expand Down
2 changes: 1 addition & 1 deletion Unreal/Plugins/AirSim/Source/Car/CarPawn.h
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,7 @@ class ACarPawn : public AWheeledVehicle

std::string getLogString();
void setupVehicleMovementComponent();
msr::airlib::CarApiBase* getApi() const;


private:
Expand All @@ -141,7 +142,6 @@ class ACarPawn : public AWheeledVehicle
UClass* pip_camera_class_;

std::unique_ptr<msr::airlib::CarRpcLibServer> rpclib_server_;
std::unique_ptr<msr::airlib::CarApiBase> api_;
std::unique_ptr<VehiclePawnWrapper> wrapper_;
msr::airlib::Kinematics::State kinematics_;

Expand Down
1 change: 1 addition & 0 deletions Unreal/Plugins/AirSim/Source/Car/SimModeCar.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ class AIRSIM_API ASimModeCar : public ASimModeBase
virtual void reset() override;
virtual std::string getReport() override;


private:
void setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles);
void updateReport();
Expand Down
14 changes: 10 additions & 4 deletions Unreal/Plugins/AirSim/Source/Multirotor/MultiRotorConnector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,16 +327,22 @@ void MultiRotorConnector::setCameraOrientation(int camera_id, const Quaternionr&
}, true);
}

msr::airlib::MultirotorApi* MultiRotorConnector::getApi() const
{
return static_cast<msr::airlib::MultirotorApi*>(vehicle_pawn_wrapper_->getApi());
}

void MultiRotorConnector::startApiServer()
{
if (enable_rpc_) {
controller_cancelable_.reset(new msr::airlib::MultirotorApi(this));
vehicle_pawn_wrapper_->setApi(
std::unique_ptr<msr::airlib::VehicleApiBase>(new msr::airlib::MultirotorApi(this)));

#ifdef AIRLIB_NO_RPC
rpclib_server_.reset(new msr::airlib::DebugApiServer());
#else
rpclib_server_.reset(new msr::airlib::MultirotorRpcLibServer(
controller_cancelable_.get(), api_server_address_, api_server_port_));
getApi(), api_server_address_, api_server_port_));
#endif

rpclib_server_->start();
Expand All @@ -350,10 +356,10 @@ void MultiRotorConnector::startApiServer()
void MultiRotorConnector::stopApiServer()
{
if (rpclib_server_ != nullptr) {
controller_cancelable_->cancelAllTasks();
getApi()->cancelAllTasks();
rpclib_server_->stop();
rpclib_server_.reset(nullptr);
controller_cancelable_.reset(nullptr);
vehicle_pawn_wrapper_->setApi(std::unique_ptr<msr::airlib::VehicleApiBase>());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ class MultiRotorConnector : public msr::airlib::VehicleConnectorBase
void detectUsbRc();
const msr::airlib::RCData& getRCData();
void resetPrivate();
msr::airlib::MultirotorApi* getApi() const;

private:
MultiRotor vehicle_;
Expand All @@ -81,7 +82,6 @@ class MultiRotorConnector : public msr::airlib::VehicleConnectorBase
VehiclePawnWrapper* vehicle_pawn_wrapper_;

msr::airlib::MultiRotorParams* vehicle_params_;
std::unique_ptr<msr::airlib::MultirotorApi> controller_cancelable_;
std::unique_ptr<msr::airlib::ControlServerBase> rpclib_server_;

struct RotorInfo {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,7 @@ void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& ve
}
}


//find all vehicle pawns
{
TArray<AActor*> pawns;
Expand Down Expand Up @@ -143,6 +144,7 @@ void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& ve
CameraDirector->initializeForBeginPlay(getInitialViewMode(), fpv_vehicle_pawn_wrapper_, external_camera);
}


void ASimModeWorldMultiRotor::Tick(float DeltaSeconds)
{
Super::Tick(DeltaSeconds);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ class AIRSIM_API ASimModeWorldMultiRotor : public ASimModeWorldBase
VehiclePawnWrapper* getFpvVehiclePawnWrapper() const override;
std::string getLogString() const;


protected:
typedef AFlyingPawn TMultiRotorPawn;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
#pragma warning(pop)

#include <dinputd.h>
#include "UnrealMathUtility.h
#include "UnrealMathUtility.h"

// Stuff to filter out XInput devices
#ifndef FALSE
Expand Down
11 changes: 11 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeApi.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
#include "SimModeApi.h"

SimModeApi::SimModeApi(ASimModeBase* simmode)
: simmode_(simmode)
{
}

msr::airlib::VehicleApiBase* SimModeApi::getVehicleApi()
{
return simmode_->getVehicleApi();
}
13 changes: 13 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeApi.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
#pragma once

#include "api/SimModeApiBase.hpp"
#include "SimMode/SimModeBase.h"

class SimModeApi : msr::airlib::SimModeApiBase {
public:
SimModeApi(ASimModeBase* simmode);
virtual msr::airlib::VehicleApiBase* getVehicleApi() override;

private:
ASimModeBase* simmode_;
};
9 changes: 9 additions & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ void ASimModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
Super::EndPlay(EndPlayReason);
}


void ASimModeBase::setupTimeOfDay()
{
sky_sphere_ = nullptr;
Expand Down Expand Up @@ -101,6 +102,14 @@ void ASimModeBase::setupTimeOfDay()
//else ignore
}

msr::airlib::VehicleApiBase* ASimModeBase::getVehicleApi() const
{
auto fpv_vehicle = getFpvVehiclePawnWrapper();
if (fpv_vehicle)
return fpv_vehicle->getApi();
else
return nullptr;
}

void ASimModeBase::setupClockSpeed()
{
Expand Down
1 change: 1 addition & 0 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ class AIRSIM_API ASimModeBase : public AActor
//must be implemented by derived class
//can't use pure virtual because of restriction with Unreal
virtual VehiclePawnWrapper* getFpvVehiclePawnWrapper() const;
virtual msr::airlib::VehicleApiBase* getVehicleApi() const;


protected:
Expand Down
10 changes: 10 additions & 0 deletions Unreal/Plugins/AirSim/Source/VehiclePawnWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,16 @@ void VehiclePawnWrapper::setKinematics(const msr::airlib::Kinematics::State* kin
kinematics_ = kinematics;
}

msr::airlib::VehicleApiBase* VehiclePawnWrapper::getApi() const
{
return api_.get();
}

void VehiclePawnWrapper::setApi(std::unique_ptr<msr::airlib::VehicleApiBase> api)
{
api_ = std::move(api);
}

void VehiclePawnWrapper::getRawVehicleSettings(msr::airlib::Settings& settings) const
{
typedef msr::airlib::AirSimSettings AirSimSettings;
Expand Down
5 changes: 5 additions & 0 deletions Unreal/Plugins/AirSim/Source/VehiclePawnWrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include "PIPCamera.h"
#include "physics/Kinematics.hpp"
#include "NedTransform.h"
#include "api/VehicleApiBase.hpp"
#include "GameFramework/Pawn.h"

class VehiclePawnWrapper
Expand Down Expand Up @@ -94,6 +95,9 @@ class VehiclePawnWrapper

void possess();

msr::airlib::VehicleApiBase* getApi() const;
void setApi(std::unique_ptr<msr::airlib::VehicleApiBase> api);

protected:
UPROPERTY(VisibleAnywhere)
UParticleSystem* collision_display_template;
Expand All @@ -120,6 +124,7 @@ class VehiclePawnWrapper
std::string log_line_;
WrapperConfig config_;
NedTransform ned_transform_;
std::unique_ptr<msr::airlib::VehicleApiBase> api_;

struct State {
FVector start_location;
Expand Down

0 comments on commit 9850a08

Please sign in to comment.