Added first CarSim integration to vehicle class.

This commit is contained in:
Axel 2020-11-16 16:34:31 +01:00 committed by bernat
parent 7a6edc405c
commit 7739b5eb94
10 changed files with 143 additions and 12 deletions

View File

@ -88,5 +88,9 @@ namespace client {
return boost::static_pointer_cast<TrafficLight>(GetWorld().GetActor(id)); return boost::static_pointer_cast<TrafficLight>(GetWorld().GetActor(id));
} }
void Vehicle::SetCarSimEnabled(bool enabled) {
GetEpisode().Lock()->SetCarSimEnabled(*this, enabled);
}
} // namespace client } // namespace client
} // namespace carla } // namespace carla

View File

@ -87,6 +87,9 @@ namespace client {
/// Retrieve the traffic light actor currently affecting this vehicle. /// Retrieve the traffic light actor currently affecting this vehicle.
SharedPtr<TrafficLight> GetTrafficLight() const; SharedPtr<TrafficLight> GetTrafficLight() const;
/// Enables CarSim simulation if it is availiable
void SetCarSimEnabled(bool enabled);
private: private:
const bool _is_control_sticky; const bool _is_control_sticky;

View File

@ -330,6 +330,10 @@ namespace detail {
_pimpl->AsyncCall("apply_control_to_vehicle", vehicle, control); _pimpl->AsyncCall("apply_control_to_vehicle", vehicle, control);
} }
void Client::SetCarSimEnabled(rpc::ActorId vehicle, bool enabled) {
_pimpl->AsyncCall("set_carsim_enabled", vehicle, enabled);
}
void Client::ApplyControlToWalker(rpc::ActorId walker, const rpc::WalkerControl &control) { void Client::ApplyControlToWalker(rpc::ActorId walker, const rpc::WalkerControl &control) {
_pimpl->AsyncCall("apply_control_to_walker", walker, control); _pimpl->AsyncCall("apply_control_to_walker", walker, control);
} }

View File

@ -211,6 +211,10 @@ namespace detail {
rpc::ActorId vehicle, rpc::ActorId vehicle,
const rpc::VehicleControl &control); const rpc::VehicleControl &control);
void SetCarSimEnabled(
rpc::ActorId vehicle,
bool enabled);
void ApplyControlToWalker( void ApplyControlToWalker(
rpc::ActorId walker, rpc::ActorId walker,
const rpc::WalkerControl &control); const rpc::WalkerControl &control);

View File

@ -445,6 +445,10 @@ namespace detail {
_client.SetLightStateToVehicle(vehicle.GetId(), light_state); _client.SetLightStateToVehicle(vehicle.GetId(), light_state);
} }
void SetCarSimEnabled(Vehicle &vehicle, bool enabled) {
_client.SetCarSimEnabled(vehicle.GetId(), enabled);
}
/// @} /// @}
// ========================================================================= // =========================================================================
/// @name Operations with the recorder /// @name Operations with the recorder

View File

@ -141,6 +141,7 @@ void export_actor() {
.def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState) .def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState)
.def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight) .def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight)
.def("get_traffic_light", &cc::Vehicle::GetTrafficLight) .def("get_traffic_light", &cc::Vehicle::GetTrafficLight)
.def("set_carsim_enabled", &cc::Vehicle::SetCarSimEnabled)
.def(self_ns::str(self_ns::self)) .def(self_ns::str(self_ns::self))
; ;

View File

@ -41,6 +41,13 @@ public class Carla : ModuleRules
"ProceduralMeshComponent" "ProceduralMeshComponent"
// ... add other public dependencies that you statically link with here ... // ... add other public dependencies that you statically link with here ...
} }
);
PublicDependencyModuleNames.AddRange(
new string[]
{
"CarSim"
// ... add other public dependencies that you statically link with here ...
}
); );
if (Target.Type == TargetType.Editor) if (Target.Type == TargetType.Editor)
@ -68,6 +75,14 @@ public class Carla : ModuleRules
// ... add private dependencies that you statically link with here ... // ... add private dependencies that you statically link with here ...
} }
); );
PrivateDependencyModuleNames.AddRange(
new string[]
{
"CarSim"
// ... add private dependencies that you statically link with here ...
}
);
PrivateIncludePathModuleNames.AddRange(new string[] { "CarSim" });
DynamicallyLoadedModuleNames.AddRange( DynamicallyLoadedModuleNames.AddRange(
new string[] new string[]

View File

@ -1083,6 +1083,24 @@ void FCarlaServer::FPimpl::BindActions()
return R<void>::Success(); return R<void>::Success();
}; };
BIND_SYNC(set_carsim_enabled) << [this](
cr::ActorId ActorId,
bool bEnabled) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(ActorId);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set carsim: actor not found");
}
auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor());
if (Vehicle == nullptr)
{
RESPOND_ERROR("unable to set carsim: not actor is not a vehicle");
}
Vehicle->SetCarSimEnabled(bEnabled);
return R<void>::Success();
};
// ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ // ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
BIND_SYNC(set_traffic_light_state) << [this]( BIND_SYNC(set_traffic_light_state) << [this](

View File

@ -33,6 +33,8 @@ ACarlaWheeledVehicle::ACarlaWheeledVehicle(const FObjectInitializer& ObjectIniti
VelocityControl = CreateDefaultSubobject<UVehicleVelocityControl>(TEXT("VelocityControl")); VelocityControl = CreateDefaultSubobject<UVehicleVelocityControl>(TEXT("VelocityControl"));
VelocityControl->Deactivate(); VelocityControl->Deactivate();
CarSimMovementComponent = CreateDefaultSubobject<UCarSimMovementComponent>(TEXT("CarSimMovement"));
GetVehicleMovementComponent()->bReverseAsBrake = false; GetVehicleMovementComponent()->bReverseAsBrake = false;
} }
@ -110,6 +112,8 @@ void ACarlaWheeledVehicle::BeginPlay()
} }
Vehicle4W->WheelSetups = NewWheelSetups; Vehicle4W->WheelSetups = NewWheelSetups;
SetCarSimEnabled(false);
} }
void ACarlaWheeledVehicle::AdjustVehicleBounds() void ACarlaWheeledVehicle::AdjustVehicleBounds()
@ -177,6 +181,33 @@ float ACarlaWheeledVehicle::GetMaximumSteerAngle() const
void ACarlaWheeledVehicle::FlushVehicleControl() void ACarlaWheeledVehicle::FlushVehicleControl()
{ {
if (bCarSimEnabled)
{
CarSimMovementComponent->SetThrottleInput(InputControl.Control.Throttle);
CarSimMovementComponent->SetSteeringInput(InputControl.Control.Steer);
CarSimMovementComponent->SetBrakeInput(InputControl.Control.Brake);
if (InputControl.Control.bHandBrake)
{
CarSimMovementComponent->SetBrakeInput(InputControl.Control.Brake + 1.0);
}
// CarSimMovementComponent->SetHandbrakeInput(InputControl.Control.bHandBrake);
// if (LastAppliedControl.bReverse != InputControl.Control.bReverse)
// {
// CarSimMovementComponent->SetUseAutoGears(!InputControl.Control.bReverse);
// CarSimMovementComponent->SetTargetGear(InputControl.Control.bReverse ? -1 : 1, true);
// }
// else
// {
// CarSimMovementComponent->SetUseAutoGears(!InputControl.Control.bManualGearShift);
// if (InputControl.Control.bManualGearShift)
// {
// CarSimMovementComponent->SetTargetGear(InputControl.Control.Gear, true);
// }
// }
InputControl.Control.Gear = CarSimMovementComponent->GetCurrentGear();
}
else
{
auto *MovementComponent = GetVehicleMovementComponent(); auto *MovementComponent = GetVehicleMovementComponent();
MovementComponent->SetThrottleInput(InputControl.Control.Throttle); MovementComponent->SetThrottleInput(InputControl.Control.Throttle);
MovementComponent->SetSteeringInput(InputControl.Control.Steer); MovementComponent->SetSteeringInput(InputControl.Control.Steer);
@ -196,6 +227,7 @@ void ACarlaWheeledVehicle::FlushVehicleControl()
} }
} }
InputControl.Control.Gear = MovementComponent->GetCurrentGear(); InputControl.Control.Gear = MovementComponent->GetCurrentGear();
}
InputControl.Control.bReverse = InputControl.Control.Gear < 0; InputControl.Control.bReverse = InputControl.Control.Gear < 0;
LastAppliedControl = InputControl.Control; LastAppliedControl = InputControl.Control;
InputControl.Priority = EVehicleInputPriority::INVALID; InputControl.Priority = EVehicleInputPriority::INVALID;
@ -453,3 +485,29 @@ void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightS
InputControl.LightState = LightState; InputControl.LightState = LightState;
RefreshLightState(LightState); RefreshLightState(LightState);
} }
//-----CARSIM--------------------------------
void ACarlaWheeledVehicle::SetCarSimEnabled(bool bEnabled)
{
carla::log_warning("Enabling CarSim", bEnabled);
bCarSimEnabled = bEnabled;
if (bCarSimEnabled)
{
GetVehicleMovementComponent()->SetComponentTickEnabled(false);
GetVehicleMovementComponent()->Deactivate();
CarSimMovementComponent->Activate();
CarSimMovementComponent->ResetVsVehicle(false);
CarSimMovementComponent->SyncVsVehicleLocOri();
CarSimMovementComponent->SetComponentTickEnabled(true);
GetMesh()->SetSimulatePhysics(false);
}
else
{
GetVehicleMovementComponent()->SetComponentTickEnabled(true);
GetVehicleMovementComponent()->Activate();
CarSimMovementComponent->SetComponentTickEnabled(false);
CarSimMovementComponent->Deactivate();
GetMesh()->SetSimulatePhysics(true);
}
}
//-------------------------------------------

View File

@ -18,6 +18,10 @@
#include "CoreMinimal.h" #include "CoreMinimal.h"
//-----CARSIM--------------------------------
#include "CarSimMovementComponent.h"
//-------------------------------------------
#include "CarlaWheeledVehicle.generated.h" #include "CarlaWheeledVehicle.generated.h"
class UBoxComponent; class UBoxComponent;
@ -235,4 +239,20 @@ private:
InputControl; InputControl;
FVehicleControl LastAppliedControl; FVehicleControl LastAppliedControl;
//-----CARSIM--------------------------------
public:
UFUNCTION(Category="CARLA Wheeled Vehicle", BlueprintCallable)
void SetCarSimEnabled(bool bEnabled);
private:
UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere)
bool bCarSimEnabled = false;
UPROPERTY(Category="CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly, meta = (AllowPrivateAccess = "true"))
UCarSimMovementComponent * CarSimMovementComponent;
//-------------------------------------------
}; };