Skip to content

Commit

Permalink
Merge branch 'master' of https://github.com/saihv/AirSim into saihv-m…
Browse files Browse the repository at this point in the history
…aster
  • Loading branch information
sytelus committed Sep 3, 2017
2 parents d98acc1 + 4fa8342 commit 20ffa49
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 26 deletions.
52 changes: 27 additions & 25 deletions Unreal/Plugins/AirSim/Source/SimMode/SimModeWorldMultiRotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include "physics/PhysicsBody.hpp"
#include <memory>
#include "Logging/MessageLog.h"
#include "vehicles/MultiRotorParamsFactory.hpp"
#include "vehicles/MultiRotorParamsFactory.hpp"


ASimModeWorldMultiRotor::ASimModeWorldMultiRotor()
Expand Down Expand Up @@ -42,10 +42,10 @@ void ASimModeWorldMultiRotor::EndPlay(const EEndPlayReason::Type EndPlayReason)
fpv_vehicle_connector_->stopApiServer();
}

if (isLoggingStarted)
{
FRecordingThread::Shutdown();
isLoggingStarted = false;
if (isLoggingStarted)
{
FRecordingThread::Shutdown();
isLoggingStarted = false;
}

//for (AActor* actor : spawned_actors_) {
Expand All @@ -60,9 +60,9 @@ void ASimModeWorldMultiRotor::EndPlay(const EEndPlayReason::Type EndPlayReason)
Super::EndPlay(EndPlayReason);
}

AVehiclePawnBase* ASimModeWorldMultiRotor::getFpvVehiclePawn()
{
return fpv_vehicle_pawn_;
AVehiclePawnBase* ASimModeWorldMultiRotor::getFpvVehiclePawn()
{
return fpv_vehicle_pawn_;
}

void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& vehicles)
Expand Down Expand Up @@ -118,11 +118,11 @@ void ASimModeWorldMultiRotor::setupVehiclesAndCamera(std::vector<VehiclePtr>& ve
}

//set up vehicle pawns
for (AActor* pawn : pawns)
{
//initialize each vehicle pawn we found
TMultiRotorPawn* vehicle_pawn = static_cast<TMultiRotorPawn*>(pawn);
if (enable_collision_passthrough)
for (AActor* pawn : pawns)
{
//initialize each vehicle pawn we found
TMultiRotorPawn* vehicle_pawn = static_cast<TMultiRotorPawn*>(pawn);
if (enable_collision_passthrough)
vehicle_pawn->EnablePassthroughOnCollisons = true;
vehicle_pawn->initializeForBeginPlay();

Expand Down Expand Up @@ -150,18 +150,18 @@ void ASimModeWorldMultiRotor::Tick(float DeltaSeconds)
if (fpv_vehicle_connector_ != nullptr && fpv_vehicle_connector_->isApiServerStarted() && getVehicleCount() > 0) {

if (isRecording() && getRecordingFile().isRecording()) {
if (!isLoggingStarted)
{
FRecordingThread::ThreadInit(fpv_vehicle_connector_->getCamera(), & getRecordingFile(),
static_cast<msr::airlib::PhysicsBody*>(fpv_vehicle_connector_->getPhysicsBody()), recording_settings);
isLoggingStarted = true;
if (!isLoggingStarted)
{
FRecordingThread::ThreadInit(fpv_vehicle_connector_->getCamera(), & getRecordingFile(),
static_cast<msr::airlib::PhysicsBody*>(fpv_vehicle_connector_->getPhysicsBody()), recording_settings);
isLoggingStarted = true;
}
}

if (!isRecording() && isLoggingStarted)
{
FRecordingThread::Shutdown();
isLoggingStarted = false;
if (!isRecording() && isLoggingStarted)
{
FRecordingThread::Shutdown();
isLoggingStarted = false;
}
}

Expand All @@ -185,13 +185,15 @@ void ASimModeWorldMultiRotor::createVehicles(std::vector<VehiclePtr>& vehicles)

ASimModeWorldBase::VehiclePtr ASimModeWorldMultiRotor::createVehicle(AFlyingPawn* vehicle_pawn)
{
vehicle_params_ = MultiRotorParamsFactory::createConfig(
auto vehicle_params = MultiRotorParamsFactory::createConfig(
vehicle_pawn->VehicleConfigName == "" ? default_vehicle_config
: std::string(TCHAR_TO_UTF8(* vehicle_pawn->VehicleConfigName)));

vehicle_params_.push_back(std::move(vehicle_params));

auto vehicle = std::make_shared<MultiRotorConnector>(
vehicle_pawn, vehicle_params_.get(), enable_rpc, api_server_address,
vehicle_params_->getParams().api_server_port, manual_pose_controller);
vehicle_pawn, vehicle_params_.back().get(), enable_rpc, api_server_address,
vehicle_params_.back()->getParams().api_server_port, manual_pose_controller);
return std::static_pointer_cast<VehicleConnectorBase>(vehicle);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class AIRSIM_API ASimModeWorldMultiRotor : public ASimModeWorldBase
private:

TArray<uint8> image_;
std::unique_ptr<msr::airlib::MultiRotorParams> vehicle_params_;
std::vector <std::unique_ptr<msr::airlib::MultiRotorParams> > vehicle_params_;
bool isLoggingStarted;

UClass* external_camera_class_;
Expand Down

0 comments on commit 20ffa49

Please sign in to comment.