Merge branch 'ue5-dev' into marcel/setup-v2

This commit is contained in:
Marcel Pi 2024-09-18 14:54:23 +02:00
commit dc6edff442
38 changed files with 2216 additions and 1707 deletions

2
.clangd.in Normal file
View File

@ -0,0 +1,2 @@
CompileFlags:
CompilationDatabase: "@CMAKE_CURRENT_BINARY_DIR@"

3
.gitignore vendored
View File

@ -4,6 +4,7 @@
__pycache__/
Build/
Install/
Doxygen/
Dist/
Temp/
@ -11,4 +12,6 @@ out/
CMakeSettings.json
.clangd
Help.md

View File

@ -39,6 +39,11 @@ endif ()
if (WIN32)
add_compile_definitions (_CRT_SECURE_NO_WARNINGS)
check_cxx_compiler_flag(/utf-8 HAS_MSVC_UTF8)
if (HAS_MSVC_UTF8)
add_compile_options (/utf-8)
endif ()
endif ()
set (CARLA_COMMON_DEFINITIONS)

View File

@ -12,29 +12,37 @@ include (FetchContent)
set (CARLA_DEPENDENCIES_PENDING)
macro (carla_git_dependency_add NAME TAG ARCHIVE_URL GIT_URL)
carla_message ("Cloning ${NAME}...")
FetchContent_Declare (
${NAME}
GIT_REPOSITORY ${GIT_URL}
GIT_TAG ${TAG}
GIT_SUBMODULES_RECURSE ON
GIT_SHALLOW ON
GIT_PROGRESS ON
OVERRIDE_FIND_PACKAGE
${ARGN}
)
list (APPEND CARLA_DEPENDENCIES_PENDING ${NAME})
endmacro ()
macro (carla_download_dependency_add NAME TAG ARCHIVE_URL GIT_URL)
carla_message ("Downloading ${NAME}...")
FetchContent_Declare (
${NAME}
URL ${ARCHIVE_URL}
OVERRIDE_FIND_PACKAGE
${ARGN}
)
list (APPEND CARLA_DEPENDENCIES_PENDING ${NAME})
endmacro ()
macro (carla_dependency_add NAME TAG ARCHIVE_URL GIT_URL)
if (PREFER_CLONE)
carla_message ("Cloning ${NAME}...")
FetchContent_Declare (
${NAME}
GIT_REPOSITORY ${GIT_URL}
GIT_TAG ${TAG}
GIT_SUBMODULES_RECURSE ON
GIT_SHALLOW ON
GIT_PROGRESS ON
OVERRIDE_FIND_PACKAGE
${ARGN}
)
list (APPEND CARLA_DEPENDENCIES_PENDING ${NAME})
carla_git_dependency_add (${NAME} ${TAG} ${ARCHIVE_URL} ${GIT_URL} ${ARGN})
else ()
carla_message ("Downloading ${NAME}...")
FetchContent_Declare (
${NAME}
URL ${ARCHIVE_URL}
OVERRIDE_FIND_PACKAGE
${ARGN}
)
list (APPEND CARLA_DEPENDENCIES_PENDING ${NAME})
carla_download_dependency_add (${NAME} ${TAG} ${ARCHIVE_URL} ${GIT_URL} ${ARGN})
endif ()
endmacro ()
@ -182,7 +190,7 @@ carla_dependency_add (
# ==== RECAST ====
carla_dependency_option (RECASTNAVIGATION_BUILDER OFF)
carla_dependency_option (RECASTNAVIGATION_BUILDER ON)
carla_dependency_add (
recastnavigation
${CARLA_RECAST_TAG}

View File

@ -39,7 +39,7 @@ endfunction ()
macro (carla_option NAME DESCRIPTION VALUE)
option (${NAME} ${DESCRIPTION} ${VALUE})
carla_message ("(option) ${NAME} : ${VALUE}")
carla_message ("(option) ${NAME} : ${${NAME}}")
get_property (DOCS GLOBAL PROPERTY CARLA_OPTION_DOCS)
string (
APPEND
@ -55,7 +55,7 @@ endmacro ()
macro (carla_string_option NAME DESCRIPTION VALUE)
set (${NAME} "${VALUE}")
carla_message ("(option) ${NAME} : \"${VALUE}\"")
carla_message ("(option) ${NAME} : \"${${NAME}}\"")
get_property (DOCS GLOBAL PROPERTY CARLA_OPTION_DOCS)
string (
APPEND

View File

@ -18,6 +18,7 @@ cmake_policy (SET CMP0091 NEW)
cmake_policy (SET CMP0074 NEW)
cmake_policy (SET CMP0077 NEW)
cmake_policy (SET CMP0117 NEW)
if (${CMAKE_MINOR_VERSION} GREATER_EQUAL 24)
cmake_policy (SET CMP0135 NEW)
endif ()
@ -121,3 +122,10 @@ file (
${CMAKE_CURRENT_BINARY_DIR}/Help.md
${CARLA_CMAKE_HELP_MESSAGE}
)
if (CMAKE_EXPORT_COMPILE_COMMANDS)
configure_file (
${CARLA_WORKSPACE_PATH}/.clangd.in
${CARLA_WORKSPACE_PATH}/.clangd
)
endif ()

View File

@ -1,5 +1,11 @@
{
"version": 8,
"version": 4,
"cmakeMinimumRequired":
{
"major": 3,
"minor": 27,
"patch": 2
},
"configurePresets":
[
{

View File

@ -1,3 +1,11 @@
project (
libcarla
LANGUAGES
CXX
VERSION
${CARLA_VERSION}
)
set (
LIBCARLA_SOURCE_PATH
${CARLA_WORKSPACE_PATH}/LibCarla/source
@ -15,14 +23,6 @@ carla_two_step_configure_file (
if (BUILD_CARLA_SERVER)
project (
carla-server
LANGUAGES
CXX
VERSION
${CARLA_VERSION}
)
file (
GLOB
LIBCARLA_SERVER_SOURCES
@ -159,14 +159,6 @@ endif ()
if (BUILD_CARLA_CLIENT)
project (
carla-client
LANGUAGES
CXX
VERSION
${CARLA_VERSION}
)
file (
GLOB
LIBCARLA_CLIENT_HEADERS

View File

@ -11,7 +11,7 @@
namespace carla {
namespace geom {
class Location;
struct Location;
class GeoLocation {
public:

View File

@ -19,8 +19,7 @@
namespace carla {
namespace geom {
class Location : public Vector3D {
public:
struct Location : Vector3D {
// =========================================================================
// -- Constructors ---------------------------------------------------------

View File

@ -14,8 +14,9 @@
namespace carla {
namespace geom {
class Vector2D {
public:
struct Vector2D {
static constexpr auto Dim = 2;
// =========================================================================
// -- Public data members --------------------------------------------------

View File

@ -14,8 +14,9 @@
namespace carla {
namespace geom {
class Vector3D {
public:
struct Vector3D {
static constexpr auto Dim = 3;
// =========================================================================
// -- Public data members --------------------------------------------------

View File

@ -11,7 +11,7 @@
#include <vector>
namespace carla {
namespace geom { class Location; }
namespace geom { struct Location; }
namespace road {
class Map;

View File

@ -22,7 +22,7 @@ class AActor;
namespace carla {
namespace geom {
class GeoLocation;
class Vector3D;
struct Vector3D;
}
namespace sensor {
namespace data {

View File

@ -16,313 +16,230 @@
#include <vector>
namespace carla {
namespace rpc {
class VehiclePhysicsControl {
public:
namespace rpc {
struct VehiclePhysicsControl
{
// Engine Setup:
std::vector<geom::Vector2D> torque_curve = {
geom::Vector2D(0.0f, 500.0f),
geom::Vector2D(5000.0f, 500.0f)
};
VehiclePhysicsControl() = default;
float max_torque = 300.0f;
float max_rpm = 5000.0f;
float idle_rpm = 1.0f;
float brake_effect = 1.0f;
float rev_up_moi = 1.0f;
float rev_down_rate = 600.0f;
VehiclePhysicsControl(
const std::vector<carla::geom::Vector2D> &in_torque_curve,
float in_max_torque,
float in_max_rpm,
float in_moi,
float in_rev_down_rate,
// ToDo: Convert to an enum, see EVehicleDifferential.
uint8_t differential_type = 0;
float front_rear_split = 0.5f;
uint8_t in_differential_type,
float in_front_rear_split,
bool use_automatic_gears = true;
float gear_change_time = 0.5f;
float final_ratio = 4.0f;
std::vector<float> forward_gear_ratios = { 2.85, 2.02, 1.35, 1.0, 2.85, 2.02, 1.35, 1.0 };
std::vector<float> reverse_gear_ratios = { 2.86, 2.86 };
float change_up_rpm = 4500.0f;
float change_down_rpm = 2000.0f;
float transmission_efficiency = 0.9f;
bool in_use_gear_autobox,
float in_gear_switch_time,
float in_final_ratio,
std::vector<float> &in_forward_gears,
std::vector<float> &in_reverse_gears,
float in_change_up_rpm,
float in_change_down_rpm,
float in_transmission_efficiency,
float mass = 1000.0f;
float drag_coefficient = 0.3f;
geom::Location center_of_mass = geom::Location(0, 0, 0);
float chassis_width = 180.f;
float chassis_height = 140.f;
float downforce_coefficient = 0.3f;
float drag_area = 0.0f;
geom::Vector3D inertia_tensor_scale = geom::Vector3D(1, 1, 1);
float sleep_threshold = 10.0f;
float sleep_slope_limit = 0.866f;
float in_mass,
float in_drag_coefficient,
geom::Location in_center_of_mass,
const std::vector<carla::geom::Vector2D> &in_steering_curve,
std::vector<WheelPhysicsControl> &in_wheels,
bool in_use_sweep_wheel_collision)
: torque_curve(in_torque_curve),
max_torque(in_max_torque),
max_rpm(in_max_rpm),
moi(in_moi),
rev_down_rate(in_rev_down_rate),
differential_type(in_differential_type),
front_rear_split(in_front_rear_split),
use_gear_autobox(in_use_gear_autobox),
gear_switch_time(in_gear_switch_time),
final_ratio(in_final_ratio),
forward_gears(in_forward_gears),
reverse_gears(in_reverse_gears),
change_up_rpm(in_change_up_rpm),
change_down_rpm(in_change_down_rpm),
transmission_efficiency(in_transmission_efficiency),
mass(in_mass),
drag_coefficient(in_drag_coefficient),
center_of_mass(in_center_of_mass),
steering_curve(in_steering_curve),
wheels(in_wheels),
use_sweep_wheel_collision(in_use_sweep_wheel_collision) {}
std::vector<geom::Vector2D> steering_curve = {
geom::Vector2D(0.0f, 1.0f),
geom::Vector2D(10.0f, 0.5f)
};
std::vector<WheelPhysicsControl> wheels;
const std::vector<float> &GetForwardGears() const {
return forward_gears;
}
bool use_sweep_wheel_collision = false;
void SetForwardGears(std::vector<float> &in_forward_gears) {
forward_gears = in_forward_gears;
}
inline bool operator==(const VehiclePhysicsControl& rhs) const {
const bool cmp[] = {
torque_curve == rhs.torque_curve,
max_torque == rhs.max_torque,
max_rpm == rhs.max_rpm,
idle_rpm == rhs.idle_rpm,
brake_effect == rhs.brake_effect,
rev_up_moi == rhs.rev_up_moi,
rev_down_rate == rhs.rev_down_rate,
differential_type == rhs.differential_type,
front_rear_split == rhs.front_rear_split,
use_automatic_gears == rhs.use_automatic_gears,
gear_change_time == rhs.gear_change_time,
final_ratio == rhs.final_ratio,
forward_gear_ratios == rhs.forward_gear_ratios,
reverse_gear_ratios == rhs.reverse_gear_ratios,
change_up_rpm == rhs.change_up_rpm,
change_down_rpm == rhs.change_down_rpm,
transmission_efficiency == rhs.transmission_efficiency,
mass == rhs.mass,
drag_coefficient == rhs.drag_coefficient,
center_of_mass == rhs.center_of_mass,
chassis_width == rhs.chassis_width,
chassis_height == rhs.chassis_height,
downforce_coefficient == rhs.downforce_coefficient,
drag_area == rhs.drag_area,
inertia_tensor_scale == rhs.inertia_tensor_scale,
sleep_threshold == rhs.sleep_threshold,
sleep_slope_limit == rhs.sleep_slope_limit,
steering_curve == rhs.steering_curve,
wheels == rhs.wheels,
use_sweep_wheel_collision == rhs.use_sweep_wheel_collision,
};
const std::vector<float> &GetReverseGears() const {
return reverse_gears;
}
return std::all_of(
std::begin(cmp),
std::end(cmp),
std::identity());
}
void SetReverseGears(std::vector<float> &in_reverse_gears) {
reverse_gears = in_reverse_gears;
}
const std::vector<WheelPhysicsControl> &GetWheels() const {
return wheels;
}
void SetWheels(std::vector<WheelPhysicsControl> &in_wheels) {
wheels = in_wheels;
}
const std::vector<geom::Vector2D> &GetTorqueCurve() const {
return torque_curve;
}
void SetTorqueCurve(std::vector<geom::Vector2D> &in_torque_curve) {
torque_curve = in_torque_curve;
}
const std::vector<geom::Vector2D> &GetSteeringCurve() const {
return steering_curve;
}
void SetSteeringCurve(std::vector<geom::Vector2D> &in_steering_curve) {
steering_curve = in_steering_curve;
}
void SetUseSweepWheelCollision(bool in_sweep) {
use_sweep_wheel_collision = in_sweep;
}
bool GetUseSweepWheelCollision() {
return use_sweep_wheel_collision;
}
std::vector<geom::Vector2D> torque_curve = {geom::Vector2D(0.0f, 500.0f), geom::Vector2D(5000.0f, 500.0f)};
float max_torque = 300.0f;
float max_rpm = 5000.0f;
float moi = 1.0f;
float rev_down_rate = 600.0f;
// ToDo: Convert to an enum, see EVehicleDifferential.
uint8_t differential_type = 0;
float front_rear_split = 0.5f;
bool use_gear_autobox = true;
float gear_switch_time = 0.5f;
float final_ratio = 4.0f;
std::vector<float> forward_gears = {2.85, 2.02, 1.35, 1.0, 2.85, 2.02, 1.35, 1.0};
std::vector<float> reverse_gears = {2.86, 2.86};
float change_up_rpm = 4500.0f;
float change_down_rpm = 2000.0f;
float transmission_efficiency = 0.9f;
float mass = 1000.0f;
float drag_coefficient = 0.3f;
geom::Location center_of_mass;
std::vector<geom::Vector2D> steering_curve = {geom::Vector2D(0.0f, 1.0f), geom::Vector2D(10.0f, 0.5f)};
std::vector<WheelPhysicsControl> wheels;
bool use_sweep_wheel_collision = false;
bool operator!=(const VehiclePhysicsControl &rhs) const {
return
max_torque != rhs.max_torque ||
max_rpm != rhs.max_rpm ||
moi != rhs.moi ||
rev_down_rate != rhs.rev_down_rate ||
differential_type != rhs.differential_type ||
front_rear_split != rhs.front_rear_split ||
use_gear_autobox != rhs.use_gear_autobox ||
gear_switch_time != rhs.gear_switch_time ||
final_ratio != rhs.final_ratio ||
forward_gears != rhs.forward_gears ||
reverse_gears != rhs.reverse_gears ||
change_up_rpm != rhs.change_up_rpm ||
change_down_rpm != rhs.change_down_rpm ||
transmission_efficiency != rhs.transmission_efficiency ||
mass != rhs.mass ||
drag_coefficient != rhs.drag_coefficient ||
steering_curve != rhs.steering_curve ||
center_of_mass != rhs.center_of_mass ||
wheels != rhs.wheels ||
use_sweep_wheel_collision != rhs.use_sweep_wheel_collision;
}
bool operator==(const VehiclePhysicsControl &rhs) const {
return !(*this != rhs);
}
inline bool operator!=(const VehiclePhysicsControl& rhs) const {
return !(*this == rhs);
}
#ifdef LIBCARLA_INCLUDED_FROM_UE4
VehiclePhysicsControl(const FVehiclePhysicsControl &Control) {
// Engine Setup
torque_curve = std::vector<carla::geom::Vector2D>();
TArray<FRichCurveKey> TorqueCurveKeys = Control.TorqueCurve.GetCopyOfKeys();
for (int32 KeyIdx = 0; KeyIdx < TorqueCurveKeys.Num(); KeyIdx++) {
geom::Vector2D point(TorqueCurveKeys[KeyIdx].Time, TorqueCurveKeys[KeyIdx].Value);
torque_curve.push_back(point);
}
max_torque = Control.MaxTorque;
max_rpm = Control.MaxRPM;
moi = Control.MOI;
rev_down_rate = Control.RevDownRate;
// Differential Setup
differential_type = Control.DifferentialType;
front_rear_split = Control.FrontRearSplit;
// Transmission Setup
use_gear_autobox = Control.bUseGearAutoBox;
gear_switch_time = Control.GearSwitchTime;
final_ratio = Control.FinalRatio;
change_up_rpm = Control.ChangeUpRPM;
change_down_rpm = Control.ChangeDownRPM;
transmission_efficiency = Control.TransmissionEfficiency;
forward_gears = std::vector<float>();
forward_gears.reserve(Control.ForwardGears.Num());
for (const auto &Gear : Control.ForwardGears) {
forward_gears.push_back(Gear);
}
reverse_gears = std::vector<float>();
reverse_gears.reserve(Control.ReverseGears.Num());
for (const auto &Gear : Control.ReverseGears) {
reverse_gears.push_back(Gear);
static VehiclePhysicsControl FromFVehiclePhysicsControl(
const FVehiclePhysicsControl& Control) {
VehiclePhysicsControl Out = { };
Out.torque_curve.reserve(Control.TorqueCurve.GetNumKeys());
for (auto& Key : Control.TorqueCurve.GetConstRefOfKeys())
Out.torque_curve.push_back(geom::Vector2D(Key.Time, Key.Value));
Out.max_torque = Control.MaxTorque;
Out.max_rpm = Control.MaxRPM;
Out.idle_rpm = Control.IdleRPM;
Out.brake_effect = Control.BrakeEffect;
Out.rev_up_moi = Control.RevUpMOI;
Out.rev_down_rate = Control.RevDownRate;
Out.differential_type = Control.DifferentialType;
Out.front_rear_split = Control.FrontRearSplit;
Out.use_automatic_gears = Control.bUseAutomaticGears;
Out.gear_change_time = Control.GearChangeTime;
Out.final_ratio = Control.FinalRatio;
Out.forward_gear_ratios.resize(Control.ForwardGearRatios.Num());
for (size_t i = 0; i != Out.forward_gear_ratios.size(); ++i)
Out.forward_gear_ratios[i] = Control.ForwardGearRatios[i];
Out.reverse_gear_ratios.resize(Control.ReverseGearRatios.Num());
for (size_t i = 0; i != Out.reverse_gear_ratios.size(); ++i)
Out.reverse_gear_ratios[i] = Control.ReverseGearRatios[i];
Out.change_up_rpm = Control.ChangeUpRPM;
Out.change_down_rpm = Control.ChangeDownRPM;
Out.transmission_efficiency = Control.TransmissionEfficiency;
Out.mass = Control.Mass;
Out.drag_coefficient = Control.DragCoefficient;
Out.center_of_mass = Control.CenterOfMass;
Out.chassis_width = Control.ChassisWidth;
Out.chassis_height = Control.ChassisHeight;
Out.downforce_coefficient = Control.DownforceCoefficient;
Out.drag_area = Control.DragArea;
Out.inertia_tensor_scale = geom::Vector3D(
Control.InertiaTensorScale.X,
Control.InertiaTensorScale.Y,
Control.InertiaTensorScale.Z);
Out.sleep_threshold = Control.SleepThreshold;
Out.sleep_slope_limit = Control.SleepSlopeLimit;
Out.steering_curve.reserve(Control.SteeringCurve.GetNumKeys());
for (auto& Key : Control.SteeringCurve.GetConstRefOfKeys())
Out.steering_curve.push_back(geom::Vector2D(Key.Time, Key.Value));
Out.wheels.resize(Control.Wheels.Num());
for (size_t i = 0; i != Out.wheels.size(); ++i)
Out.wheels[i] = WheelPhysicsControl::FromFWheelPhysicsControl(Control.Wheels[i]);
Out.use_sweep_wheel_collision = Control.UseSweepWheelCollision;
return Out;
}
// Vehicle Setup
mass = Control.Mass;
drag_coefficient = Control.DragCoefficient;
steering_curve = std::vector<carla::geom::Vector2D>();
TArray<FRichCurveKey> SteeringCurveKeys = Control.SteeringCurve.GetCopyOfKeys();
for (int32 KeyIdx = 0; KeyIdx < SteeringCurveKeys.Num(); KeyIdx++) {
geom::Vector2D point(SteeringCurveKeys[KeyIdx].Time, SteeringCurveKeys[KeyIdx].Value);
steering_curve.push_back(point);
operator FVehiclePhysicsControl() const {
FVehiclePhysicsControl Control = { };
for (auto [x, y] : torque_curve)
Control.TorqueCurve.AddKey(x, y);
Control.MaxTorque = max_torque;
Control.MaxRPM = max_rpm;
Control.IdleRPM = idle_rpm;
Control.BrakeEffect = brake_effect;
Control.RevUpMOI = rev_up_moi;
Control.RevDownRate = rev_down_rate;
Control.DifferentialType = differential_type;
Control.FrontRearSplit = front_rear_split;
Control.bUseAutomaticGears = use_automatic_gears;
Control.GearChangeTime = gear_change_time;
Control.FinalRatio = final_ratio;
Control.ForwardGearRatios.SetNum(forward_gear_ratios.size());
for (size_t i = 0; i != Control.ForwardGearRatios.Num(); ++i)
Control.ForwardGearRatios[i] = forward_gear_ratios[i];
Control.ReverseGearRatios.SetNum(reverse_gear_ratios.size());
for (size_t i = 0; i != Control.ReverseGearRatios.Num(); ++i)
Control.ReverseGearRatios[i] = reverse_gear_ratios[i];
Control.ChangeUpRPM = change_up_rpm;
Control.ChangeDownRPM = change_down_rpm;
Control.TransmissionEfficiency = transmission_efficiency;
Control.Mass = mass;
Control.DragCoefficient = drag_coefficient;
Control.CenterOfMass = center_of_mass;
Control.ChassisWidth = chassis_width;
Control.ChassisHeight = chassis_height;
Control.DownforceCoefficient = downforce_coefficient;
Control.DragArea = drag_area;
Control.InertiaTensorScale = FVector(
inertia_tensor_scale.x,
inertia_tensor_scale.y,
inertia_tensor_scale.z);
Control.SleepThreshold = sleep_threshold;
Control.SleepSlopeLimit = sleep_slope_limit;
for (auto [x, y] : steering_curve)
Control.SteeringCurve.AddKey(x, y);
Control.Wheels.SetNum(wheels.size());
for (size_t i = 0; i != Control.Wheels.Num(); ++i)
Control.Wheels[i] = wheels[i];
Control.UseSweepWheelCollision = use_sweep_wheel_collision;
return Control;
}
center_of_mass = Control.CenterOfMass;
// Wheels Setup
wheels = std::vector<WheelPhysicsControl>();
for (const auto &Wheel : Control.Wheels) {
wheels.push_back(WheelPhysicsControl(Wheel));
}
use_sweep_wheel_collision = Control.UseSweepWheelCollision;
}
operator FVehiclePhysicsControl() const {
FVehiclePhysicsControl Control;
// Engine Setup
FRichCurve TorqueCurve;
for (const auto &point : torque_curve) {
TorqueCurve.AddKey(point.x, point.y);
}
Control.TorqueCurve = TorqueCurve;
Control.MaxTorque = max_torque;
Control.MaxRPM = max_rpm;
Control.MOI = moi;
Control.RevDownRate = rev_down_rate;
// Differential Setup
Control.DifferentialType = differential_type;
Control.FrontRearSplit = front_rear_split;
// Transmission Setup
Control.bUseGearAutoBox = use_gear_autobox;
Control.GearSwitchTime = gear_switch_time;
Control.FinalRatio = final_ratio;
Control.ChangeUpRPM = change_up_rpm;
Control.ChangeDownRPM = change_down_rpm;
Control.TransmissionEfficiency = transmission_efficiency;
TArray<float> ForwardGears;
ForwardGears.Reserve(forward_gears.size());
for (const auto &gear : forward_gears) {
ForwardGears.Add(gear);
}
Control.ForwardGears = ForwardGears;
TArray<float> ReverseGears;
ReverseGears.Reserve(reverse_gears.size());
for (const auto &gear : reverse_gears) {
ReverseGears.Add(gear);
}
Control.ReverseGears = ReverseGears;
// Vehicle Setup
Control.Mass = mass;
Control.DragCoefficient = drag_coefficient;
// Transmission Setup
FRichCurve SteeringCurve;
for (const auto &point : steering_curve) {
SteeringCurve.AddKey(point.x, point.y);
}
Control.SteeringCurve = SteeringCurve;
Control.CenterOfMass = center_of_mass;
// Wheels Setup
TArray<FWheelPhysicsControl> Wheels;
for (const auto &wheel : wheels) {
Wheels.Add(FWheelPhysicsControl(wheel));
}
Control.Wheels = Wheels;
Control.UseSweepWheelCollision = use_sweep_wheel_collision;
return Control;
}
#endif
MSGPACK_DEFINE_ARRAY(torque_curve,
MSGPACK_DEFINE_ARRAY(
torque_curve,
max_torque,
max_rpm,
moi,
idle_rpm,
brake_effect,
rev_up_moi,
rev_down_rate,
differential_type,
front_rear_split,
use_gear_autobox,
gear_switch_time,
use_automatic_gears,
gear_change_time,
final_ratio,
forward_gears,
reverse_gears,
forward_gear_ratios,
reverse_gear_ratios,
change_up_rpm,
change_down_rpm,
transmission_efficiency,
mass,
drag_coefficient,
center_of_mass,
chassis_width,
chassis_height,
downforce_coefficient,
drag_area,
inertia_tensor_scale,
sleep_threshold,
sleep_slope_limit,
steering_curve,
wheels,
use_sweep_wheel_collision);
};
use_sweep_wheel_collision
);
};
} // namespace rpc
} // namespace rpc
} // namespace carla

View File

@ -6,101 +6,255 @@
#pragma once
#include "carla/geom/Vector2D.h"
#include "carla/geom/Vector3D.h"
#include "carla/geom/Location.h"
#include "carla/MsgPack.h"
namespace carla {
namespace rpc {
namespace rpc {
class WheelPhysicsControl {
public:
struct WheelPhysicsControl {
WheelPhysicsControl() = default;
uint8_t axle_type = 0; // @TODO INTRODUCE ENUM
geom::Vector3D offset = geom::Vector3D(0, 0, 0);
float wheel_radius = 30.0f;
float wheel_width = 30.0f;
float wheel_mass = 30.0f;
float cornering_stiffness = 1000.0f;
float friction_force_multiplier = 3.0f;
float side_slip_modifier = 1.0f;
float slip_threshold = 20.0f;
float skid_threshold = 20.0f;
float max_steer_angle = 70.0f;
bool affected_by_steering = true;
bool affected_by_brake = true;
bool affected_by_handbrake = true;
bool affected_by_engine = true;
bool abs_enabled = false;
bool traction_control_enabled = false;
float max_wheelspin_rotation = 30;
uint8_t external_torque_combine_method = 0; // @TODO INTRODUCE ENUM
std::vector<geom::Vector2D> lateral_slip_graph;
geom::Vector3D suspension_axis = geom::Vector3D(0, 0, -1);
geom::Vector3D suspension_force_offset = geom::Vector3D(0, 0, 0);
float suspension_max_raise = 10.0f;
float suspension_max_drop = 10.0f;
float suspension_damping_ratio = 0.5f;
float wheel_load_ratio = 0.5f;
float spring_rate = 250.0f;
float spring_preload = 50.0f;
int suspension_smoothing = 0;
float rollbar_scaling = 0.15f;
uint8_t sweep_shape = 0; // @TODO INTRODUCE ENUM
uint8_t sweep_type = 0; // @TODO INTRODUCE ENUM
float max_brake_torque = 1500.0f;
float max_hand_brake_torque = 3000.0f;
int32_t wheel_index = -1;
geom::Location location = geom::Location(0, 0, 0);
geom::Location old_location = geom::Location(0, 0, 0);
geom::Location velocity = geom::Location(0, 0, 0);
WheelPhysicsControl(
float in_tire_friction,
float in_max_steer_angle,
float in_radius,
float in_cornering_stiffness,
bool in_abs,
bool in_traction_control,
float in_max_brake_torque,
float in_max_handbrake_torque,
geom::Vector3D in_position)
: tire_friction(in_tire_friction),
max_steer_angle(in_max_steer_angle),
radius(in_radius),
cornering_stiffness(in_cornering_stiffness),
abs(in_abs),
traction_control(in_traction_control),
max_brake_torque(in_max_brake_torque),
max_handbrake_torque(in_max_handbrake_torque),
position(in_position) {}
inline bool operator==(const WheelPhysicsControl& rhs) const {
const bool cmp[] =
{
axle_type == rhs.axle_type,
offset == rhs.offset,
wheel_radius == rhs.wheel_radius,
wheel_width == rhs.wheel_width,
wheel_mass == rhs.wheel_mass,
cornering_stiffness == rhs.cornering_stiffness,
friction_force_multiplier == rhs.friction_force_multiplier,
side_slip_modifier == rhs.side_slip_modifier,
slip_threshold == rhs.slip_threshold,
skid_threshold == rhs.skid_threshold,
max_steer_angle == rhs.max_steer_angle,
affected_by_steering == rhs.affected_by_steering,
affected_by_brake == rhs.affected_by_brake,
affected_by_handbrake == rhs.affected_by_handbrake,
affected_by_engine == rhs.affected_by_engine,
abs_enabled == rhs.abs_enabled,
traction_control_enabled == rhs.traction_control_enabled,
max_wheelspin_rotation == rhs.max_wheelspin_rotation,
external_torque_combine_method == rhs.external_torque_combine_method,
lateral_slip_graph == rhs.lateral_slip_graph,
suspension_axis == rhs.suspension_axis,
suspension_force_offset == rhs.suspension_force_offset,
suspension_max_raise == rhs.suspension_max_raise,
suspension_max_drop == rhs.suspension_max_drop,
suspension_damping_ratio == rhs.suspension_damping_ratio,
wheel_load_ratio == rhs.wheel_load_ratio,
spring_rate == rhs.spring_rate,
spring_preload == rhs.spring_preload,
suspension_smoothing == rhs.suspension_smoothing,
rollbar_scaling == rhs.rollbar_scaling,
sweep_shape == rhs.sweep_shape,
sweep_type == rhs.sweep_type,
max_brake_torque == rhs.max_brake_torque,
max_hand_brake_torque == rhs.max_hand_brake_torque,
wheel_index == rhs.wheel_index,
location == rhs.location,
old_location == rhs.old_location,
velocity == rhs.velocity
};
return std::all_of(std::begin(cmp), std::end(cmp), std::identity());
}
float tire_friction = 3.0f;
float max_steer_angle = 70.0f;
float radius = 30.0f;
float cornering_stiffness = 1000.0f;
bool abs = false;
bool traction_control = false;
float max_brake_torque = 1500.0f;
float max_handbrake_torque = 3000.0f;
geom::Vector3D position = {0.0f, 0.0f, 0.0f};
inline bool operator!=(const WheelPhysicsControl& rhs) const {
return !(*this == rhs);
}
bool operator!=(const WheelPhysicsControl &rhs) const {
return
tire_friction != rhs.tire_friction ||
max_steer_angle != rhs.max_steer_angle ||
radius != rhs.radius ||
cornering_stiffness != rhs.cornering_stiffness ||
abs != rhs.abs ||
traction_control != rhs.traction_control ||
max_brake_torque != rhs.max_brake_torque ||
max_handbrake_torque != rhs.max_handbrake_torque ||
position != rhs.position;
}
bool operator==(const WheelPhysicsControl &rhs) const {
return !(*this != rhs);
}
#ifdef LIBCARLA_INCLUDED_FROM_UE4
WheelPhysicsControl(const FWheelPhysicsControl &Wheel)
: tire_friction(Wheel.FrictionForceMultiplier),
max_steer_angle(Wheel.MaxSteerAngle),
radius(Wheel.Radius),
cornering_stiffness(Wheel.CorneringStiffness),
abs(Wheel.bABSEnabled),
traction_control(Wheel.bTractionControlEnabled),
max_brake_torque(Wheel.MaxBrakeTorque),
max_handbrake_torque(Wheel.MaxHandBrakeTorque),
position(Wheel.Position.X, Wheel.Position.Y, Wheel.Position.Z) {}
static WheelPhysicsControl FromFWheelPhysicsControl(
const FWheelPhysicsControl& Wheel)
{
WheelPhysicsControl Out = { };
Out.axle_type = (uint8_t)Wheel.AxleType;
Out.offset = geom::Vector3D(
Wheel.Offset.X,
Wheel.Offset.Y,
Wheel.Offset.Z);
Out.wheel_radius = Wheel.WheelRadius;
Out.wheel_width = Wheel.WheelWidth;
Out.wheel_mass = Wheel.WheelMass;
Out.cornering_stiffness = Wheel.CorneringStiffness;
Out.friction_force_multiplier = Wheel.FrictionForceMultiplier;
Out.side_slip_modifier = Wheel.SideSlipModifier;
Out.slip_threshold = Wheel.SlipThreshold;
Out.skid_threshold = Wheel.SkidThreshold;
Out.max_steer_angle = Wheel.MaxSteerAngle;
Out.affected_by_steering = Wheel.bAffectedBySteering;
Out.affected_by_brake = Wheel.bAffectedByBrake;
Out.affected_by_handbrake = Wheel.bAffectedByHandbrake;
Out.affected_by_engine = Wheel.bAffectedByEngine;
Out.abs_enabled = Wheel.bABSEnabled;
Out.traction_control_enabled = Wheel.bTractionControlEnabled;
Out.max_wheelspin_rotation = Wheel.MaxWheelspinRotation;
Out.external_torque_combine_method = (uint8_t)Wheel.ExternalTorqueCombineMethod;
Out.lateral_slip_graph.reserve(Wheel.LateralSlipGraph.GetNumKeys());
for (auto& e : Wheel.LateralSlipGraph.GetConstRefOfKeys())
Out.lateral_slip_graph.push_back({ e.Time, e.Value });
Out.suspension_axis = geom::Vector3D(
Wheel.SuspensionAxis.X,
Wheel.SuspensionAxis.Y,
Wheel.SuspensionAxis.Z);
Out.suspension_force_offset = geom::Vector3D(
Wheel.SuspensionForceOffset.X,
Wheel.SuspensionForceOffset.Y,
Wheel.SuspensionForceOffset.Z);
Out.suspension_max_raise = Wheel.SuspensionMaxRaise;
Out.suspension_max_drop = Wheel.SuspensionMaxDrop;
Out.suspension_damping_ratio = Wheel.SuspensionDampingRatio;
Out.wheel_load_ratio = Wheel.WheelLoadRatio;
Out.spring_rate = Wheel.SpringRate;
Out.spring_preload = Wheel.SpringPreload;
Out.suspension_smoothing = Wheel.SuspensionSmoothing;
Out.rollbar_scaling = Wheel.RollbarScaling;
Out.sweep_shape = (uint8_t)Wheel.SweepShape;
Out.sweep_type = (uint8_t)Wheel.SweepType;
Out.max_brake_torque = Wheel.MaxBrakeTorque;
Out.max_hand_brake_torque = Wheel.MaxHandBrakeTorque;
Out.wheel_index = Wheel.WheelIndex;
Out.location = Wheel.Location;
Out.old_location = Wheel.OldLocation;
Out.velocity = Wheel.Velocity;
return Out;
}
operator FWheelPhysicsControl() const {
FWheelPhysicsControl Wheel;
Wheel.FrictionForceMultiplier = tire_friction;
Wheel.MaxSteerAngle = max_steer_angle;
Wheel.Radius = radius;
Wheel.CorneringStiffness = cornering_stiffness;
Wheel.bABSEnabled = abs;
Wheel.bTractionControlEnabled = traction_control;
Wheel.MaxBrakeTorque = max_brake_torque;
Wheel.MaxHandBrakeTorque = max_handbrake_torque;
Wheel.Position = {position.x, position.y, position.z};
return Wheel;
}
operator FWheelPhysicsControl() const {
FWheelPhysicsControl Wheel;
Wheel.AxleType = (EAxleType)axle_type;
Wheel.Offset = FVector(offset.x, offset.y, offset.z);
Wheel.WheelRadius = wheel_radius;
Wheel.WheelWidth = wheel_width;
Wheel.WheelMass = wheel_mass;
Wheel.CorneringStiffness = cornering_stiffness;
Wheel.FrictionForceMultiplier = friction_force_multiplier;
Wheel.SideSlipModifier = side_slip_modifier;
Wheel.SlipThreshold = slip_threshold;
Wheel.SkidThreshold = skid_threshold;
Wheel.MaxSteerAngle = max_steer_angle;
Wheel.bAffectedBySteering = affected_by_steering;
Wheel.bAffectedByBrake = affected_by_brake;
Wheel.bAffectedByHandbrake = affected_by_handbrake;
Wheel.bAffectedByEngine = affected_by_engine;
Wheel.bABSEnabled = abs_enabled;
Wheel.bTractionControlEnabled = traction_control_enabled;
Wheel.MaxWheelspinRotation = max_wheelspin_rotation;
Wheel.ExternalTorqueCombineMethod = (ETorqueCombineMethod)external_torque_combine_method;
for (auto [x, y] : lateral_slip_graph)
Wheel.LateralSlipGraph.AddKey(x, y);
Wheel.SuspensionAxis = FVector(
suspension_axis.x,
suspension_axis.y,
suspension_axis.z);
Wheel.SuspensionForceOffset = FVector(
suspension_force_offset.x,
suspension_force_offset.y,
suspension_force_offset.z);
Wheel.SuspensionMaxRaise = suspension_max_raise;
Wheel.SuspensionMaxDrop = suspension_max_drop;
Wheel.SuspensionDampingRatio = suspension_damping_ratio;
Wheel.WheelLoadRatio = wheel_load_ratio;
Wheel.SpringRate = spring_rate;
Wheel.SpringPreload = spring_preload;
Wheel.SuspensionSmoothing = suspension_smoothing;
Wheel.RollbarScaling = rollbar_scaling;
Wheel.SweepShape = (ESweepShape)sweep_shape;
Wheel.SweepType = (ESweepType)sweep_type;
Wheel.MaxBrakeTorque = max_brake_torque;
Wheel.MaxHandBrakeTorque = max_hand_brake_torque;
Wheel.WheelIndex = wheel_index;
Wheel.Location = location;
Wheel.OldLocation = old_location;
Wheel.Velocity = velocity;
return Wheel;
}
#endif
MSGPACK_DEFINE_ARRAY(tire_friction,
max_steer_angle,
radius,
MSGPACK_DEFINE_ARRAY(
axle_type,
offset,
wheel_radius,
wheel_width,
wheel_mass,
cornering_stiffness,
abs,
traction_control,
friction_force_multiplier,
side_slip_modifier,
slip_threshold,
skid_threshold,
max_steer_angle,
affected_by_steering,
affected_by_brake,
affected_by_handbrake,
affected_by_engine,
abs_enabled,
traction_control_enabled,
max_wheelspin_rotation,
external_torque_combine_method,
lateral_slip_graph,
suspension_axis,
suspension_force_offset,
suspension_max_raise,
suspension_max_drop,
suspension_damping_ratio,
wheel_load_ratio,
spring_rate,
spring_preload,
suspension_smoothing,
rollbar_scaling,
sweep_shape,
sweep_type,
max_brake_torque,
max_handbrake_torque,
position)
};
max_hand_brake_torque,
wheel_index,
location,
old_location,
velocity)
};
}
}
}

View File

@ -15,7 +15,6 @@
#include <boost/asio/connect.hpp>
#include <boost/asio/read.hpp>
#include <boost/asio/write.hpp>
#include <boost/asio/post.hpp>
#include <boost/asio/bind_executor.hpp>
#include <exception>
@ -86,7 +85,6 @@ namespace tcp {
void Client::Connect() {
auto self = shared_from_this();
boost::asio::post(_strand, [this, self]() {
if (_done) {
return;
}
@ -139,18 +137,15 @@ namespace tcp {
log_debug("streaming client: connecting to", ep);
_socket.async_connect(ep, boost::asio::bind_executor(_strand, handle_connect));
});
}
void Client::Stop() {
_connection_timer.cancel();
auto self = shared_from_this();
boost::asio::post(_strand, [this, self]() {
_done = true;
if (_socket.is_open()) {
_socket.close();
}
});
}
void Client::Reconnect() {
@ -165,7 +160,6 @@ namespace tcp {
void Client::ReadData() {
auto self = shared_from_this();
boost::asio::post(_strand, [this, self]() {
if (_done) {
return;
}
@ -182,7 +176,7 @@ namespace tcp {
// Move the buffer to the callback function and start reading the next
// piece of data.
// log_debug("streaming client: success reading data, calling the callback");
boost::asio::post(_strand, [self, message]() { self->_callback(message->pop()); });
_callback(message->pop());
ReadData();
} else {
// As usual, if anything fails start over from the very top.
@ -219,7 +213,6 @@ namespace tcp {
_socket,
message->size_as_buffer(),
boost::asio::bind_executor(_strand, handle_read_header));
});
}
} // namespace tcp

View File

@ -79,43 +79,39 @@ namespace tcp {
DEBUG_ASSERT(message != nullptr);
DEBUG_ASSERT(!message->empty());
auto self = shared_from_this();
boost::asio::post(_strand, [=]() {
if (!_socket.is_open()) {
if (!_socket.is_open()) {
return;
}
if (_is_writing) {
if (_server.IsSynchronousMode()) {
// wait until previous message has been sent
while (_is_writing) {
std::this_thread::yield();
}
} else {
// ignore this message
log_debug("session", _session_id, ": connection too slow: message discarded");
return;
}
if (_is_writing) {
if (_server.IsSynchronousMode()) {
// wait until previous message has been sent
while (_is_writing) {
std::this_thread::yield();
}
} else {
// ignore this message
log_debug("session", _session_id, ": connection too slow: message discarded");
return;
}
}
_is_writing = true;
auto handle_sent = [this, self, message](const boost::system::error_code &ec, size_t DEBUG_ONLY(bytes)) {
_is_writing = false;
if (ec) {
log_info("session", _session_id, ": error sending data :", ec.message());
CloseNow(ec);
} else {
DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes"));
DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size());
}
_is_writing = true;
};
auto handle_sent = [this, self, message](const boost::system::error_code &ec, size_t DEBUG_ONLY(bytes)) {
_is_writing = false;
if (ec) {
log_info("session", _session_id, ": error sending data :", ec.message());
CloseNow(ec);
} else {
DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes"));
DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size());
}
};
log_debug("session", _session_id, ": sending message of", message->size(), "bytes");
log_debug("session", _session_id, ": sending message of", message->size(), "bytes");
_deadline.expires_from_now(_timeout);
boost::asio::async_write(
_socket,
message->GetBufferSequence(),
handle_sent);
});
_deadline.expires_from_now(_timeout);
boost::asio::async_write(_socket, message->GetBufferSequence(),
boost::asio::bind_executor(_strand, handle_sent));
}
void ServerSession::Close() {

View File

@ -36,6 +36,18 @@ set (
${CMAKE_CURRENT_SOURCE_DIR}/carla
)
set (
CARLA_PYTHON_API_CMAKE_ARGS
"\t'-G${CMAKE_GENERATOR}'"
)
if (CMAKE_TOOLCHAIN_FILE)
set (
CARLA_PYTHON_API_CMAKE_ARGS
"${CARLA_PYTHON_API_CMAKE_ARGS},\n\'\t--toolchain=${CMAKE_TOOLCHAIN_FILE}\'"
)
endif ()
carla_two_step_configure_file (
${CARLA_PYTHON_API_CARLA_PATH}/pyproject.toml
${CARLA_PYTHON_API_CARLA_PATH}/pyproject.toml.in

View File

@ -480,26 +480,36 @@ namespace rpc {
inline std::ostream &operator<<(std::ostream &out, const VehiclePhysicsControl &control) {
out << "VehiclePhysicsControl(torque_curve=" << control.torque_curve
<< ", max_torque=" << std::to_string(control.max_torque)
<< ", max_rpm=" << std::to_string(control.max_rpm)
<< ", moi=" << std::to_string(control.moi)
<< ", rev_down_rate=" << std::to_string(control.rev_down_rate)
<< ", differential_type=" << std::to_string(control.differential_type)
<< ", front_rear_split=" << std::to_string(control.front_rear_split)
<< ", use_gear_autobox=" << boolalpha(control.use_gear_autobox)
<< ", gear_switch_time=" << std::to_string(control.gear_switch_time)
<< ", final_ratio=" << std::to_string(control.final_ratio)
<< ", forward_gears=" << control.forward_gears
<< ", reverse_gears=" << control.reverse_gears
<< ", change_up_rpm=" << std::to_string(control.change_up_rpm)
<< ", change_down_rpm=" << std::to_string(control.change_down_rpm)
<< ", transmission_efficiency=" << std::to_string(control.transmission_efficiency)
<< ", mass=" << std::to_string(control.mass)
<< ", drag_coefficient=" << std::to_string(control.drag_coefficient)
<< ", center_of_mass=" << control.center_of_mass
<< ", steering_curve=" << control.steering_curve
<< ", wheels=" << control.wheels
<< ", use_sweep_wheel_collision=" << control.use_sweep_wheel_collision << ')';
<< ", max_torque=" << control.max_torque
<< ", max_rpm=" << control.max_rpm
<< ", idle_rpm=" << control.idle_rpm
<< ", brake_effect=" << control.brake_effect
<< ", rev_up_moi=" << control.rev_up_moi
<< ", rev_down_rate=" << control.rev_down_rate
<< ", differential_type=" << control.differential_type
<< ", front_rear_split=" << control.front_rear_split
<< ", use_automatic_gears=" << control.use_automatic_gears
<< ", gear_change_time=" << control.gear_change_time
<< ", final_ratio=" << control.final_ratio
<< ", forward_gear_ratios=" << control.forward_gear_ratios
<< ", reverse_gear_ratios=" << control.reverse_gear_ratios
<< ", change_up_rpm=" << control.change_up_rpm
<< ", change_down_rpm=" << control.change_down_rpm
<< ", transmission_efficiency=" << control.transmission_efficiency
<< ", mass=" << control.mass
<< ", drag_coefficient=" << control.drag_coefficient
<< ", center_of_mass=" << control.center_of_mass
<< ", chassis_width=" << control.chassis_width
<< ", chassis_height=" << control.chassis_height
<< ", downforce_coefficient=" << control.downforce_coefficient
<< ", drag_area=" << control.drag_area
<< ", inertia_tensor_scale=" << control.inertia_tensor_scale
<< ", sleep_threshold=" << control.sleep_threshold
<< ", sleep_slope_limit=" << control.sleep_slope_limit
<< ", steering_curv=" << control.steering_curve
<< ", wheels=" << control.wheels
<< ", use_sweep_wheel_collision=" << control.use_sweep_wheel_collision
<< ")";
return out;
}
@ -556,4 +566,4 @@ inline auto MakeCallback(boost::python::object callback) {
PyErr_Print();
}
};
}
}

View File

@ -7,8 +7,10 @@ wheel.packages = ['carla']
cmake.version = '>=@CMAKE_MAJOR_VERSION@.@CMAKE_MINOR_VERSION@'
cmake.build-type = '@CMAKE_BUILD_TYPE@'
cmake.args = [
'-DCMAKE_TOOLCHAIN_FILE=@CMAKE_TOOLCHAIN_FILE@'
@CARLA_PYTHON_API_CMAKE_ARGS@
]
ninja.version=">=1.10"
ninja.make-fallback=true
[project]
name = 'carla'

View File

@ -61,36 +61,36 @@ static void SetWheels(carla::rpc::VehiclePhysicsControl &self, const boost::pyth
self.wheels = wheels;
}
static auto GetForwardGears(const carla::rpc::VehiclePhysicsControl &self) {
const auto &gears = self.GetForwardGears();
static auto GetForwardGearRatios(const carla::rpc::VehiclePhysicsControl &self) {
const auto &gears = self.GetForwardGearRatios();
boost::python::object get_iter = boost::python::iterator<std::vector<float>>();
boost::python::object iter = get_iter(gears);
return boost::python::list(iter);
}
static void SetForwardGears(carla::rpc::VehiclePhysicsControl &self, const boost::python::list &list) {
static void SetForwardGearRatios(carla::rpc::VehiclePhysicsControl &self, const boost::python::list &list) {
std::vector<float> gears;
auto length = boost::python::len(list);
for (auto i = 0u; i < length; ++i) {
gears.push_back(boost::python::extract<float &>(list[i]));
}
self.SetForwardGears(gears);
self.SetForwardGearRatios(gears);
}
static auto GetReverseGears(const carla::rpc::VehiclePhysicsControl &self) {
const auto &gears = self.GetReverseGears();
static auto GetReverseGearRatios(const carla::rpc::VehiclePhysicsControl &self) {
const auto &gears = self.GetReverseGearRatios();
boost::python::object get_iter = boost::python::iterator<std::vector<float>>();
boost::python::object iter = get_iter(gears);
return boost::python::list(iter);
}
static void SetReverseGears(carla::rpc::VehiclePhysicsControl &self, const boost::python::list &list) {
static void SetReverseGearRatios(carla::rpc::VehiclePhysicsControl &self, const boost::python::list &list) {
std::vector<float> gears;
auto length = boost::python::len(list);
for (auto i = 0u; i < length; ++i) {
gears.push_back(boost::python::extract<float &>(list[i]));
}
self.SetReverseGears(gears);
self.SetReverseGearRatios(gears);
}
static auto GetTorqueCurve(const carla::rpc::VehiclePhysicsControl &self) {
@ -117,34 +117,39 @@ static void SetSteeringCurve(carla::rpc::VehiclePhysicsControl &self, const boos
boost::python::object VehiclePhysicsControl_init(boost::python::tuple args, boost::python::dict kwargs) {
// Args names
const uint32_t NUM_ARGUMENTS = 21;
const char *args_names[NUM_ARGUMENTS] = {
const char* const args_names[] = {
"torque_curve",
"max_torque",
"max_rpm",
"moi",
"idle_rpm",
"brake_effect",
"rev_up_moi",
"rev_down_rate",
"differential_type",
"front_rear_split",
"use_gear_autobox",
"gear_switch_time",
"use_automatic_gears",
"gear_change_time",
"final_ratio",
"forward_gears",
"reverse_gears",
"forward_gear_ratios",
"reverse_gear_ratios",
"change_up_rpm",
"change_down_rpm",
"transmission_efficiency",
"mass",
"drag_coefficient",
"center_of_mass",
"chassis_width",
"chassis_height",
"downforce_coefficient",
"drag_area",
"inertia_tensor_scale",
"sleep_threshold",
"sleep_slope_limit",
"steering_curve",
"wheels",
"use_sweep_wheel_collision",
"use_sweep_wheel_collision"
};
const auto NUM_ARGUMENTS = sizeof(args_names) / sizeof(const char*);
boost::python::object self = args[0];
args = boost::python::tuple(args.slice(1, boost::python::_));
@ -365,26 +370,35 @@ void export_control() {
.def("__init__", raw_function(VehiclePhysicsControl_init))
.def(init<>())
.add_property("torque_curve", &GetTorqueCurve, &SetTorqueCurve)
.def_readwrite("max_torque", &cr::VehiclePhysicsControl::max_torque)
.def_readwrite("max_rpm", &cr::VehiclePhysicsControl::max_rpm)
.def_readwrite("moi", &cr::VehiclePhysicsControl::moi)
.def_readwrite("rev_down_rate", &cr::VehiclePhysicsControl::rev_down_rate)
.def_readwrite("differential_type", &cr::VehiclePhysicsControl::differential_type)
.def_readwrite("front_rear_split", &cr::VehiclePhysicsControl::front_rear_split)
.def_readwrite("use_gear_autobox", &cr::VehiclePhysicsControl::use_gear_autobox)
.def_readwrite("gear_switch_time", &cr::VehiclePhysicsControl::gear_switch_time)
.def_readwrite("final_ratio", &cr::VehiclePhysicsControl::final_ratio)
.add_property("forward_gears", &GetForwardGears, &SetForwardGears)
.add_property("reverse_gears", &GetReverseGears, &SetReverseGears)
.def_readwrite("change_up_rpm", &cr::VehiclePhysicsControl::change_up_rpm)
.def_readwrite("change_down_rpm", &cr::VehiclePhysicsControl::change_down_rpm)
.def_readwrite("transmission_efficiency", &cr::VehiclePhysicsControl::mass)
.def_readwrite("mass", &cr::VehiclePhysicsControl::mass)
.def_readwrite("drag_coefficient", &cr::VehiclePhysicsControl::drag_coefficient)
.def_readwrite("center_of_mass", &cr::VehiclePhysicsControl::center_of_mass)
.add_property("max_torque", &cr::VehiclePhysicsControl::max_torque)
.add_property("max_rpm", &cr::VehiclePhysicsControl::max_rpm)
.add_property("idle_rpm", &cr::VehiclePhysicsControl::idle_rpm)
.add_property("brake_effect", &cr::VehiclePhysicsControl::brake_effect)
.add_property("rev_up_moi", &cr::VehiclePhysicsControl::rev_up_moi)
.add_property("rev_down_rate", &cr::VehiclePhysicsControl::rev_down_rate)
.add_property("differential_type", &cr::VehiclePhysicsControl::differential_type)
.add_property("front_rear_split", &cr::VehiclePhysicsControl::front_rear_split)
.add_property("use_automatic_gears", &cr::VehiclePhysicsControl::use_automatic_gears)
.add_property("gear_change_time", &cr::VehiclePhysicsControl::gear_change_time)
.add_property("final_ratio", &cr::VehiclePhysicsControl::final_ratio)
.add_property("forward_gear_ratios", &GetForwardGearRatios, &SetForwardGearRatios)
.add_property("reverse_gear_ratios", &GetReverseGearRatios, &SetReverseGearRatios)
.add_property("change_up_rpm", &cr::VehiclePhysicsControl::change_up_rpm)
.add_property("change_down_rpm", &cr::VehiclePhysicsControl::change_down_rpm)
.add_property("transmission_efficiency", &cr::VehiclePhysicsControl::transmission_efficiency)
.add_property("mass", &cr::VehiclePhysicsControl::mass)
.add_property("drag_coefficient", &cr::VehiclePhysicsControl::drag_coefficient)
.add_property("center_of_mass", &cr::VehiclePhysicsControl::center_of_mass)
.add_property("chassis_width", &cr::VehiclePhysicsControl::chassis_width)
.add_property("chassis_height", &cr::VehiclePhysicsControl::chassis_height)
.add_property("downforce_coefficient", &cr::VehiclePhysicsControl::downforce_coefficient)
.add_property("drag_area", &cr::VehiclePhysicsControl::drag_area)
.add_property("inertia_tensor_scale", &cr::VehiclePhysicsControl::inertia_tensor_scale)
.add_property("sleep_threshold", &cr::VehiclePhysicsControl::sleep_threshold)
.add_property("sleep_slope_limit", &cr::VehiclePhysicsControl::sleep_slope_limit)
.add_property("steering_curve", &GetSteeringCurve, &SetSteeringCurve)
.add_property("wheels", &GetWheels, &SetWheels)
.def_readwrite("use_sweep_wheel_collision", &cr::VehiclePhysicsControl::use_sweep_wheel_collision)
.add_property("use_sweep_wheel_collision", &cr::VehiclePhysicsControl::use_sweep_wheel_collision)
.def("__eq__", &cr::VehiclePhysicsControl::operator==)
.def("__ne__", &cr::VehiclePhysicsControl::operator!=)
.def(self_ns::str(self_ns::self))

View File

@ -1,2 +1 @@
carla.so
carla.pyd
_out/

View File

@ -1329,7 +1329,7 @@ def main():
argparser.add_argument(
'--generation',
metavar='G',
default='4',
default='All',
help='restrict to certain actor generation (values: "1","2","3","4","All" - default: "4")')
argparser.add_argument(
'--rolename',

View File

@ -95,7 +95,7 @@ endif ()
set (
UE_DEPENDENCIES_ORDER_ONLY
UE_DEPENDENCIES
carla-server
libsqlite3
Boost::asio
@ -108,12 +108,18 @@ set (
rpc
)
set (UE_DEPENDENCIES ${UE_DEPENDENCIES_ORDER_ONLY})
set (UE_DEPENDENCIES_ORDER_ONLY ${UE_DEPENDENCIES})
if (BUILD_CARLA_CLIENT)
list (APPEND UE_DEPENDENCIES_ORDER_ONLY carla-client)
endif ()
list (
APPEND
UE_DEPENDENCIES_ORDER_ONLY
RecastBuilder
)
set (
@ -357,10 +363,23 @@ add_dependencies (
${UE_DEPENDENCIES_ORDER_ONLY}
)
function (add_carla_ue_package_target PACKAGE_CONFIGURATION UE_BUILD_CONFIGURATION)
function (
add_carla_ue_package_target
PACKAGE_CONFIGURATION
UE_BUILD_CONFIGURATION)
set (
CARLA_TARGET_PACKAGE_PATH
${CARLA_PACKAGE_PATH}/${UE_SYSTEM_NAME}
)
if (NOT "${PACKAGE_CONFIGURATION}" STREQUAL "")
set (TARGET_NAME_SUFFIX -${PACKAGE_CONFIGURATION})
string (TOLOWER "${TARGET_NAME_SUFFIX}" TARGET_NAME_SUFFIX)
else ()
set (PACKAGE_CONFIGURATION "default (shipping)")
endif ()
carla_add_custom_target (
carla-unreal-package${TARGET_NAME_SUFFIX}
"Create a CARLA package in ${PACKAGE_CONFIGURATION} mode."
@ -395,7 +414,6 @@ function (add_carla_ue_package_target PACKAGE_CONFIGURATION UE_BUILD_CONFIGURATI
VERBATIM
)
set (CARLA_TARGET_PACKAGE_PATH ${CARLA_PACKAGE_PATH}/${UE_SYSTEM_NAME})
add_custom_command (
TARGET carla-unreal-package${TARGET_NAME_SUFFIX}
POST_BUILD
@ -432,7 +450,7 @@ function (add_carla_ue_package_target PACKAGE_CONFIGURATION UE_BUILD_CONFIGURATI
add_dependencies (
carla-unreal-package${TARGET_NAME_SUFFIX}
${UE_DEPENDENCIES_ORDER_ONLY}
carla-unreal-editor
)
carla_add_custom_target (

View File

@ -56,6 +56,11 @@ r.Shadow.Virtual.Enable=1
r.RayTracing.Shadows.AvoidSelfIntersectionTraceDistance=6
r.ReflectionCaptureResolution=256
r.SkinCache.SceneMemoryLimitInMB=1024
#Virtual shadow maps fix temporal
r.Shadow.Virtual.MaxPhysicalPages=8192
r.Shadow.Virtual.MaxPhysicalPagesSceneCapture=4096
r.Shadow.Virtual.Cache=0
r.Shadow.Virtual.SMRT.SamplesPerRayDirectional=0
[/Script/AIModule.AISense_Sight]
bAutoRegisterAllPawnsAsSources=False
@ -67,15 +72,6 @@ RuntimeGeneration=Static
[/Script/AIModule.CrowdManager]
MaxAgents=1000
[/Script/LinuxTargetPlatform.LinuxTargetSettings]
SpatializationPlugin=
SourceDataOverridePlugin=
ReverbPlugin=
OcclusionPlugin=
SoundCueCookQualityIndex=-1
-TargetedRHIs=SF_VULKAN_SM5
+TargetedRHIs=SF_VULKAN_SM6
[/Script/Engine.PhysicsSettings]
DefaultGravityZ=-980.000000
DefaultTerminalVelocity=4000.000000
@ -119,10 +115,19 @@ InitialAverageFrameRate=0.016667
# PhysXTreeRebuildRate=10
DefaultBroadphaseSettings=(bUseMBPOnClient=False,bUseMBPOnServer=False,MBPBounds=(Min=(X=0.000000,Y=0.000000,Z=0.000000),Max=(X=0.000000,Y=0.000000,Z=0.000000),IsValid=0),MBPNumSubdivs=2)
[/Script/LinuxTargetPlatform.LinuxTargetSettings]
SpatializationPlugin=
SourceDataOverridePlugin=
ReverbPlugin=
OcclusionPlugin=
SoundCueCookQualityIndex=-1
-TargetedRHIs=SF_VULKAN_SM5
+TargetedRHIs=SF_VULKAN_SM6
[/Script/WindowsTargetPlatform.WindowsTargetSettings]
DefaultGraphicsRHI=DefaultGraphicsRHI_DX12
-D3D12TargetedShaderFormats=PCD3D_SM5
+D3D12TargetedShaderFormats=PCD3D_SM6
+D3D12TargetedShaderFormats=PCD3D_ES31
+VulkanTargetedShaderFormats=SF_VULKAN_SM6
Compiler=Default
AudioSampleRate=48000

View File

@ -459,19 +459,19 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation ExposureCompensation;
ExposureCompensation.Id = TEXT("exposure_compensation");
ExposureCompensation.Type = EActorAttributeType::Float;
ExposureCompensation.RecommendedValues = { TEXT("1.35") };
ExposureCompensation.RecommendedValues = { TEXT("1.5") };
ExposureCompensation.bRestrictToRecommended = false;
FActorVariation HighlightContrastScaleVariation;
HighlightContrastScaleVariation.Id = TEXT("highlight_contrast_scale");
HighlightContrastScaleVariation.Type = EActorAttributeType::Float;
HighlightContrastScaleVariation.RecommendedValues = { TEXT("0.8") };
HighlightContrastScaleVariation.RecommendedValues = { TEXT("0.3") };
HighlightContrastScaleVariation.bRestrictToRecommended = false;
FActorVariation ShadowContrastScaleVariation;
ShadowContrastScaleVariation.Id = TEXT("shadow_constrast_scale");
ShadowContrastScaleVariation.Type = EActorAttributeType::Float;
ShadowContrastScaleVariation.RecommendedValues = { TEXT("0.85") };
ShadowContrastScaleVariation.RecommendedValues = { TEXT("0.65") };
ShadowContrastScaleVariation.bRestrictToRecommended = false;
// - Manual ------------------------------------------------
@ -483,14 +483,14 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation ShutterSpeed; // (1/t)
ShutterSpeed.Id = TEXT("shutter_speed");
ShutterSpeed.Type = EActorAttributeType::Float;
ShutterSpeed.RecommendedValues = { TEXT("25.0") };
ShutterSpeed.RecommendedValues = { TEXT("15.0") };
ShutterSpeed.bRestrictToRecommended = false;
// The camera sensor sensitivity.
FActorVariation ISO; // S
ISO.Id = TEXT("iso");
ISO.Type = EActorAttributeType::Float;
ISO.RecommendedValues = { TEXT("200.0") };
ISO.RecommendedValues = { TEXT("300000.0") };
ISO.bRestrictToRecommended = false;
// Defines the size of the opening for the camera lens.
@ -498,7 +498,7 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation Aperture; // N
Aperture.Id = TEXT("fstop");
Aperture.Type = EActorAttributeType::Float;
Aperture.RecommendedValues = { TEXT("7.1") };
Aperture.RecommendedValues = { TEXT("9.8") };
Aperture.bRestrictToRecommended = false;
// Defines the opening of the camera lens, Aperture is 1.0/fstop,
@ -601,7 +601,7 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation FilmToe;
FilmToe.Id = TEXT("toe");
FilmToe.Type = EActorAttributeType::Float;
FilmToe.RecommendedValues = { TEXT("0.6") };
FilmToe.RecommendedValues = { TEXT("0.55") };
FilmToe.bRestrictToRecommended = false;
FActorVariation FilmShoulder;
@ -626,7 +626,7 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation Temperature;
Temperature.Id = TEXT("temp");
Temperature.Type = EActorAttributeType::Float;
Temperature.RecommendedValues = { TEXT("5000.0") };
Temperature.RecommendedValues = { TEXT("7700.0") };
Temperature.bRestrictToRecommended = false;
FActorVariation Tint;
@ -650,13 +650,13 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation ColorSaturation;
ColorSaturation.Id = TEXT("color_saturation");
ColorSaturation.Type = EActorAttributeType::Float;
ColorSaturation.RecommendedValues = { ColorToFString(FLinearColor(0.45f, 0.45f, 0.45f).ToFColorSRGB()) };
ColorSaturation.RecommendedValues = { ColorToFString(FLinearColor(0.5f, 0.5f, 0.5f).ToFColorSRGB()) };
ColorSaturation.bRestrictToRecommended = false;
FActorVariation ColorContrast;
ColorContrast.Id = TEXT("color_contrast");
ColorContrast.Type = EActorAttributeType::Vector;
ColorContrast.RecommendedValues = { VectorToFString(FVector(1.35f, 1.35f, 1.35f)) };
ColorContrast.RecommendedValues = { VectorToFString(FVector(1.6f, 1.6f, 1.6f)) };
ColorContrast.bRestrictToRecommended = false;
FActorVariation ColorGamma;
@ -680,13 +680,13 @@ void UActorBlueprintFunctionLibrary::MakeCameraDefinition(
FActorVariation SceneColorTint;
SceneColorTint.Id = TEXT("scene_color_tint");
SceneColorTint.Type = EActorAttributeType::RGBColor;
SceneColorTint.RecommendedValues = { ColorToFString(FLinearColor(0.783308, 0.893718, 0.936458).ToFColorSRGB()) };
SceneColorTint.RecommendedValues = { ColorToFString(FLinearColor(0.785339f, 0.879092f, 0.93125f).ToFColorSRGB()) };
SceneColorTint.bRestrictToRecommended = false;
FActorVariation VignetteIntensity;
VignetteIntensity.Id = TEXT("vignette_intensity");
VignetteIntensity.Type = EActorAttributeType::Float;
VignetteIntensity.RecommendedValues = { TEXT("0.4") };
VignetteIntensity.RecommendedValues = { TEXT("0.7") };
VignetteIntensity.bRestrictToRecommended = false;
@ -1682,22 +1682,22 @@ void UActorBlueprintFunctionLibrary::SetCamera(
Camera->SetBloomIntensity(
RetrieveActorAttributeToFloat("bloom_intensity", Description.Variations, 0.0f));
// Exposure, histogram mode by default
if (RetrieveActorAttributeToString("exposure_mode", Description.Variations, "histogram") == "histogram")
{
Camera->SetExposureMethod(EAutoExposureMethod::AEM_Histogram);
}
else
if (RetrieveActorAttributeToString("exposure_mode", Description.Variations, "histogram") != "histogram")
{
Camera->SetExposureMethod(EAutoExposureMethod::AEM_Manual);
}
else
{
Camera->SetExposureMethod(EAutoExposureMethod::AEM_Histogram);
}
Camera->SetExposureCompensation(
RetrieveActorAttributeToFloat("exposure_compensation", Description.Variations, 1.35f));
RetrieveActorAttributeToFloat("exposure_compensation", Description.Variations, 1.5f));
Camera->SetShutterSpeed(
RetrieveActorAttributeToFloat("shutter_speed", Description.Variations, 25.0f));
RetrieveActorAttributeToFloat("shutter_speed", Description.Variations, 15.0f));
Camera->SetISO(
RetrieveActorAttributeToFloat("iso", Description.Variations, 200.0f));
RetrieveActorAttributeToFloat("iso", Description.Variations, 300000.0f));
Camera->SetAperture(
RetrieveActorAttributeToFloat("fstop", Description.Variations, 7.1f));
RetrieveActorAttributeToFloat("fstop", Description.Variations, 9.8f));
Camera->SetExposureMinBrightness(
RetrieveActorAttributeToFloat("exposure_min_bright", Description.Variations, 0.0f));
@ -1708,9 +1708,9 @@ void UActorBlueprintFunctionLibrary::SetCamera(
Camera->SetExposureSpeedDown(
RetrieveActorAttributeToFloat("exposure_speed_down", Description.Variations, 1.0f));
Camera->SetHighlightContrastScale(
RetrieveActorAttributeToFloat("highlight_contrast_scale", Description.Variations, 0.8f));
RetrieveActorAttributeToFloat("highlight_contrast_scale", Description.Variations, 0.3f));
Camera->SetShadowContrastScale(
RetrieveActorAttributeToFloat("shadow_constrast_scale", Description.Variations, 0.85f));
RetrieveActorAttributeToFloat("shadow_constrast_scale", Description.Variations, 0.65f));
// This is deprecated:
Camera->SetExposureCalibrationConstant(
RetrieveActorAttributeToFloat("calibration_constant", Description.Variations, 16.0f));
@ -1731,7 +1731,7 @@ void UActorBlueprintFunctionLibrary::SetCamera(
Camera->SetFilmSlope(
RetrieveActorAttributeToFloat("slope", Description.Variations, 0.88f));
Camera->SetFilmToe(
RetrieveActorAttributeToFloat("toe", Description.Variations, 0.6f));
RetrieveActorAttributeToFloat("toe", Description.Variations, 0.55f));
Camera->SetFilmShoulder(
RetrieveActorAttributeToFloat("shoulder", Description.Variations, 0.26f));
Camera->SetFilmBlackClip(
@ -1740,7 +1740,7 @@ void UActorBlueprintFunctionLibrary::SetCamera(
RetrieveActorAttributeToFloat("white_clip", Description.Variations, 0.04f));
Camera->SetWhiteTemp(
RetrieveActorAttributeToFloat("temp", Description.Variations, 5000.0f));
RetrieveActorAttributeToFloat("temp", Description.Variations, 7700.0f));
Camera->SetWhiteTint(
RetrieveActorAttributeToFloat("tint", Description.Variations, -0.15f));
@ -1749,12 +1749,12 @@ void UActorBlueprintFunctionLibrary::SetCamera(
Camera->SetChromAberrOffset(
RetrieveActorAttributeToFloat("chromatic_aberration_offset", Description.Variations, 0.0f));
auto ColorSaturation = FLinearColor(RetrieveActorAttributeToColor("color_saturation", Description.Variations, FLinearColor(0.45f, 0.45f, 0.45f).ToFColorSRGB()));
auto ColorSaturation = FLinearColor(RetrieveActorAttributeToColor("color_saturation", Description.Variations, FLinearColor(0.5f, 0.5f, 0.5f).ToFColorSRGB()));
Camera->SetColorSaturation(
FVector4(ColorSaturation.R, ColorSaturation.G, ColorSaturation.B, ColorSaturation.A));
// Temporal comments until FVector is implemented in clientside
FVector ColorContrast = FVector(RetrieveActorAttributeToVector("color_contrast", Description.Variations, FVector(1.3f, 1.3f, 1.3f)));
FVector ColorContrast = FVector(RetrieveActorAttributeToVector("color_contrast", Description.Variations, FVector(1.6f, 1.6f, 1.6f)));
Camera->SetColorContrast(
FVector4(ColorContrast.X, ColorContrast.Y, ColorContrast.Z, 1.0f));
@ -1771,10 +1771,10 @@ void UActorBlueprintFunctionLibrary::SetCamera(
RetrieveActorAttributeToFloat("tone_curve_amount", Description.Variations, 1.0f));
Camera->SetSceneColorTint(
RetrieveActorAttributeToColor("scene_color_tint", Description.Variations, FLinearColor(0.783308f, 0.893718f, 0.936458f).ToFColorSRGB()));
RetrieveActorAttributeToColor("scene_color_tint", Description.Variations, FLinearColor(0.785339f, 0.879092f, 0.93125f).ToFColorSRGB()));
Camera->SetVignetteIntensity(
RetrieveActorAttributeToFloat("vignette_intensity", Description.Variations, 0.4f));
RetrieveActorAttributeToFloat("vignette_intensity", Description.Variations, 0.7f));
}
}

View File

@ -13,17 +13,21 @@
#include <compiler/enable-ue4-macros.h>
void CarlaRecorderPhysicsControl::Write(std::ostream &OutFile)
void CarlaRecorderPhysicsControl::Write(std::ostream& OutFile)
{
carla::rpc::VehiclePhysicsControl RPCPhysicsControl(VehiclePhysicsControl);
auto RPCPhysicsControl = carla::rpc::VehiclePhysicsControl::FromFVehiclePhysicsControl(
VehiclePhysicsControl);
WriteValue<uint32_t>(OutFile, this->DatabaseId);
WriteValue(OutFile, RPCPhysicsControl.max_torque);
WriteValue(OutFile, RPCPhysicsControl.max_rpm);
WriteValue(OutFile, RPCPhysicsControl.moi);
WriteValue(OutFile, RPCPhysicsControl.idle_rpm);
WriteValue(OutFile, RPCPhysicsControl.brake_effect);
WriteValue(OutFile, RPCPhysicsControl.rev_up_moi);
WriteValue(OutFile, RPCPhysicsControl.rev_down_rate);
WriteValue(OutFile, RPCPhysicsControl.differential_type);
WriteValue(OutFile, RPCPhysicsControl.front_rear_split);
WriteValue(OutFile, RPCPhysicsControl.use_gear_autobox);
WriteValue(OutFile, RPCPhysicsControl.use_automatic_gears);
WriteValue(OutFile, RPCPhysicsControl.gear_change_time);
WriteValue(OutFile, RPCPhysicsControl.final_ratio);
WriteValue(OutFile, RPCPhysicsControl.change_up_rpm);
WriteValue(OutFile, RPCPhysicsControl.change_down_rpm);
@ -31,57 +35,55 @@ void CarlaRecorderPhysicsControl::Write(std::ostream &OutFile)
WriteValue(OutFile, RPCPhysicsControl.mass);
WriteValue(OutFile, RPCPhysicsControl.drag_coefficient);
WriteValue(OutFile, RPCPhysicsControl.center_of_mass);
// torque curve
WriteValue(OutFile, RPCPhysicsControl.chassis_width);
WriteValue(OutFile, RPCPhysicsControl.chassis_height);
WriteValue(OutFile, RPCPhysicsControl.downforce_coefficient);
WriteValue(OutFile, RPCPhysicsControl.drag_area);
WriteValue(OutFile, RPCPhysicsControl.inertia_tensor_scale);
WriteValue(OutFile, RPCPhysicsControl.sleep_threshold);
WriteValue(OutFile, RPCPhysicsControl.sleep_slope_limit);
WriteValue(OutFile, RPCPhysicsControl.use_sweep_wheel_collision);
WriteStdVector(OutFile, RPCPhysicsControl.torque_curve);
// forward gears
WriteStdVector(OutFile, RPCPhysicsControl.forward_gears);
// reverse gears
WriteStdVector(OutFile, RPCPhysicsControl.reverse_gears);
// steering curve
WriteStdVector(OutFile, RPCPhysicsControl.forward_gear_ratios);
WriteStdVector(OutFile, RPCPhysicsControl.reverse_gear_ratios);
WriteStdVector(OutFile, RPCPhysicsControl.steering_curve);
// wheels
WriteStdVector(OutFile, RPCPhysicsControl.wheels);
}
void CarlaRecorderPhysicsControl::Read(std::istream &InFile)
void CarlaRecorderPhysicsControl::Read(std::istream& InFile)
{
carla::rpc::VehiclePhysicsControl RPCPhysicsControl;
ReadValue<uint32_t>(InFile, this->DatabaseId);
ReadValue(InFile, RPCPhysicsControl.max_torque);
ReadValue(InFile, RPCPhysicsControl.max_rpm);
ReadValue(InFile, RPCPhysicsControl.moi);
ReadValue(InFile, RPCPhysicsControl.idle_rpm);
ReadValue(InFile, RPCPhysicsControl.brake_effect);
ReadValue(InFile, RPCPhysicsControl.rev_up_moi);
ReadValue(InFile, RPCPhysicsControl.rev_down_rate);
ReadValue(InFile, RPCPhysicsControl.differential_type);
ReadValue(InFile, RPCPhysicsControl.front_rear_split);
ReadValue(InFile, RPCPhysicsControl.use_gear_autobox);
ReadValue(InFile, RPCPhysicsControl.use_automatic_gears);
ReadValue(InFile, RPCPhysicsControl.gear_change_time);
ReadValue(InFile, RPCPhysicsControl.final_ratio);
ReadValue(InFile, RPCPhysicsControl.change_up_rpm);
ReadValue(InFile, RPCPhysicsControl.change_down_rpm);
ReadValue(InFile, RPCPhysicsControl.transmission_efficiency);
ReadValue(InFile, RPCPhysicsControl.final_ratio);
ReadValue(InFile, RPCPhysicsControl.mass);
ReadValue(InFile, RPCPhysicsControl.drag_coefficient);
ReadValue(InFile, RPCPhysicsControl.center_of_mass);
// torque curve
ReadValue(InFile, RPCPhysicsControl.chassis_width);
ReadValue(InFile, RPCPhysicsControl.chassis_height);
ReadValue(InFile, RPCPhysicsControl.downforce_coefficient);
ReadValue(InFile, RPCPhysicsControl.drag_area);
ReadValue(InFile, RPCPhysicsControl.inertia_tensor_scale);
ReadValue(InFile, RPCPhysicsControl.sleep_threshold);
ReadValue(InFile, RPCPhysicsControl.sleep_slope_limit);
ReadValue(InFile, RPCPhysicsControl.use_sweep_wheel_collision);
ReadStdVector(InFile, RPCPhysicsControl.torque_curve);
// forward gears
ReadStdVector(InFile, RPCPhysicsControl.forward_gears);
// reverse gears
ReadStdVector(InFile, RPCPhysicsControl.reverse_gears);
// steering curve
ReadStdVector(InFile, RPCPhysicsControl.forward_gear_ratios);
ReadStdVector(InFile, RPCPhysicsControl.reverse_gear_ratios);
ReadStdVector(InFile, RPCPhysicsControl.steering_curve);
// wheels
ReadStdVector(InFile, RPCPhysicsControl.wheels);
VehiclePhysicsControl = FVehiclePhysicsControl(RPCPhysicsControl);
}
@ -92,12 +94,12 @@ void CarlaRecorderPhysicsControls::Clear(void)
PhysicsControls.clear();
}
void CarlaRecorderPhysicsControls::Add(const CarlaRecorderPhysicsControl &InObj)
void CarlaRecorderPhysicsControls::Add(const CarlaRecorderPhysicsControl& InObj)
{
PhysicsControls.push_back(InObj);
}
void CarlaRecorderPhysicsControls::Write(std::ostream &OutFile)
void CarlaRecorderPhysicsControls::Write(std::ostream& OutFile)
{
if (PhysicsControls.size() == 0)
{

View File

@ -23,11 +23,11 @@ ACollisionSensor::ACollisionSensor(const FObjectInitializer& ObjectInitializer)
FActorDefinition ACollisionSensor::GetSensorDefinition()
{
return UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(
TEXT("other"),
TEXT("collision"));
TEXT("other"),
TEXT("collision"));
}
void ACollisionSensor::SetOwner(AActor *NewOwner)
void ACollisionSensor::SetOwner(AActor* NewOwner)
{
Super::SetOwner(NewOwner);
@ -40,10 +40,10 @@ void ACollisionSensor::SetOwner(AActor *NewOwner)
}
void ACollisionSensor::OnCollisionEvent(
AActor *Actor,
AActor *OtherActor,
FVector NormalImpulse,
const FHitResult &Hit)
AActor* Actor,
AActor* OtherActor,
FVector NormalImpulse,
const FHitResult& Hit)
{
if (Actor == nullptr || OtherActor == nullptr)
{
@ -54,21 +54,21 @@ void ACollisionSensor::OnCollisionEvent(
// remove all items from previous frames
CollisionRegistry.erase(
std::remove_if(
CollisionRegistry.begin(),
CollisionRegistry.end(),
[CurrentFrame](std::tuple<uint64_t, AActor*, AActor*> Item)
{
return std::get<0>(Item) < CurrentFrame;
}),
CollisionRegistry.end());
std::remove_if(
CollisionRegistry.begin(),
CollisionRegistry.end(),
[CurrentFrame](std::tuple<uint64_t, AActor*, AActor*> Item)
{
return std::get<0>(Item) < CurrentFrame;
}),
CollisionRegistry.end());
// check if this collision has been procesed already in this frame
for (auto& Collision: CollisionRegistry)
for (auto& Collision : CollisionRegistry)
{
if (std::get<0>(Collision) == CurrentFrame &&
std::get<1>(Collision) == Actor &&
std::get<2>(Collision) == OtherActor)
std::get<1>(Collision) == Actor &&
std::get<2>(Collision) == OtherActor)
{
return;
}
@ -78,37 +78,51 @@ void ACollisionSensor::OnCollisionEvent(
constexpr float TO_METERS = 1e-2;
NormalImpulse *= TO_METERS;
GetDataStream(*this).SerializeAndSend(
*this,
CurrentEpisode.SerializeActor(Actor),
CurrentEpisode.SerializeActor(OtherActor),
carla::geom::Vector3D(
(float)NormalImpulse.X,
(float)NormalImpulse.Y,
(float)NormalImpulse.Z));
*this,
CurrentEpisode.SerializeActor(Actor),
CurrentEpisode.SerializeActor(OtherActor),
carla::geom::Vector3D(
(float)NormalImpulse.X,
(float)NormalImpulse.Y,
(float)NormalImpulse.Z));
// record the collision event
if (CurrentEpisode.GetRecorder()->IsEnabled()){
CurrentEpisode.GetRecorder()->AddCollision(Actor, OtherActor);
if (CurrentEpisode.GetRecorder()->IsEnabled()) {
CurrentEpisode.GetRecorder()->AddCollision(Actor, OtherActor);
}
CollisionRegistry.emplace_back(CurrentFrame, Actor, OtherActor);
// ROS2
#if defined(WITH_ROS2)
#if defined(WITH_ROS2)
auto ROS2 = carla::ros2::ROS2::GetInstance();
if (ROS2->IsEnabled())
{
TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send");
auto StreamId = carla::streaming::detail::token_type(GetToken()).get_stream_id();
auto NormalImpulseVector = carla::geom::Vector3D(
(float)NormalImpulse.X,
(float)NormalImpulse.Y,
(float)NormalImpulse.Z);
AActor* ParentActor = GetAttachParentActor();
if (ParentActor)
{
FTransform LocalTransformRelativeToParent = GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform());
ROS2->ProcessDataFromCollisionSensor(0, StreamId, LocalTransformRelativeToParent, OtherActor->GetUniqueID(), carla::geom::Vector3D{NormalImpulse.X, NormalImpulse.Y, NormalImpulse.Z}, this);
ROS2->ProcessDataFromCollisionSensor(
0, StreamId,
LocalTransformRelativeToParent,
OtherActor->GetUniqueID(),
NormalImpulseVector,
this);
}
else
{
ROS2->ProcessDataFromCollisionSensor(0, StreamId, GetActorTransform(), OtherActor->GetUniqueID(), carla::geom::Vector3D{NormalImpulse.X, NormalImpulse.Y, NormalImpulse.Z}, this);
ROS2->ProcessDataFromCollisionSensor(
0, StreamId,
GetActorTransform(),
OtherActor->GetUniqueID(),
NormalImpulseVector,
this);
}
}
#endif
#endif
}

View File

@ -226,7 +226,16 @@ namespace ImageUtil
static void ReadImageDataAsyncCommand(
struct ReadImageDataContext
{
EPixelFormat Format;
FIntPoint Size;
ReadImageDataAsyncCallback Callback;
TUniquePtr<FRHIGPUTextureReadback> Readback;
};
static void ReadImageDataBegin(
ReadImageDataContext& Self,
UTextureRenderTarget2D& RenderTarget,
ReadImageDataAsyncCallback&& Callback)
{
@ -239,12 +248,13 @@ namespace ImageUtil
auto Texture = Resource->GetRenderTargetTexture();
if (Texture == nullptr)
return;
auto Readback = MakeUnique<FRHIGPUTextureReadback>(
Self.Callback = std::move(Callback);
Self.Readback = MakeUnique<FRHIGPUTextureReadback>(
TEXT("ReadImageData-Readback"));
auto Size = Texture->GetSizeXY();
auto Format = Texture->GetFormat();
Self.Size = Texture->GetSizeXY();
Self.Format = Texture->GetFormat();
auto ResolveRect = FResolveRect();
Readback->EnqueueCopy(CmdList, Texture, ResolveRect);
Self.Readback->EnqueueCopy(CmdList, Texture, ResolveRect);
auto Query = RenderQueryPool->AllocateQuery();
CmdList.EndRenderQuery(Query.GetQuery());
@ -252,26 +262,42 @@ namespace ImageUtil
uint64 DeltaTime;
RHIGetRenderQueryResult(Query.GetQuery(), DeltaTime, true);
Query.ReleaseQuery();
}
static void ReadImageDataEnd(
ReadImageDataContext& Self)
{
int32 RowPitch, BufferHeight;
auto MappedPtr = Self.Readback->Lock(RowPitch, &BufferHeight);
if (MappedPtr != nullptr)
{
ScopedCallback Unlock = [&] { Self.Readback->Unlock(); };
Self.Callback(MappedPtr, RowPitch, BufferHeight, Self.Format, Self.Size);
}
}
static void ReadImageDataEndAsync(
ReadImageDataContext&& Self)
{
AsyncTask(
ENamedThreads::HighTaskPriority, [
Readback = MoveTemp(Readback),
Callback = std::move(Callback),
Size,
Format]
Self = std::move(Self)]() mutable
{
while (!Readback->IsReady())
while (!Self.Readback->IsReady())
std::this_thread::yield();
int32 RowPitch, BufferHeight;
auto MappedPtr = Readback->Lock(RowPitch, &BufferHeight);
if (MappedPtr != nullptr)
{
ScopedCallback Unlock = [&] { Readback->Unlock(); };
Callback(MappedPtr, RowPitch, BufferHeight, Format, Size);
}
ReadImageDataEnd(Self);
});
}
static void ReadImageDataAsyncCommand(
UTextureRenderTarget2D& RenderTarget,
ReadImageDataAsyncCallback&& Callback)
{
ReadImageDataContext Context = { };
ReadImageDataBegin(Context, RenderTarget, std::move(Callback));
ReadImageDataEndAsync(std::move(Context));
}
bool ReadImageDataAsync(
@ -287,14 +313,14 @@ namespace ImageUtil
else
{
ENQUEUE_RENDER_COMMAND(ReadImageDataAsyncCmd)([
&RenderTarget,
Callback = std::move(Callback)
&RenderTarget, Callback = std::move(Callback)
](auto& CmdList) mutable
{
ReadImageDataAsyncCommand(
RenderTarget,
std::move(Callback));
ReadImageDataContext Context = { };
ReadImageDataBegin(Context, RenderTarget, std::move(Callback));
ReadImageDataEnd(Context);
});
FlushRenderingCommands();
}
return true;
}

View File

@ -1349,7 +1349,7 @@ BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_
Response,
" Actor Id: " + FString::FromInt(ActorId));
}
return cr::VehiclePhysicsControl(PhysicsControl);
return cr::VehiclePhysicsControl::FromFVehiclePhysicsControl(PhysicsControl);
};
BIND_SYNC(get_vehicle_light_state) << [this](

View File

@ -69,12 +69,12 @@ void ACarlaWheeledVehicle::BeginPlay()
for (FName& ComponentName : ConstraintComponentNames)
{
UPhysicsConstraintComponent* ConstraintComponent =
Cast<UPhysicsConstraintComponent>(GetDefaultSubobjectByName(ComponentName));
Cast<UPhysicsConstraintComponent>(GetDefaultSubobjectByName(ComponentName));
if (ConstraintComponent)
{
UPrimitiveComponent* DoorComponent = Cast<UPrimitiveComponent>(
GetDefaultSubobjectByName(ConstraintComponent->ComponentName1.ComponentName));
if(DoorComponent)
GetDefaultSubobjectByName(ConstraintComponent->ComponentName1.ComponentName));
if (DoorComponent)
{
UE_LOG(LogCarla, Log, TEXT("Door name: %s"), *(DoorComponent->GetName()));
FTransform ComponentWorldTransform = DoorComponent->GetComponentTransform();
@ -101,9 +101,9 @@ void ACarlaWheeledVehicle::BeginPlay()
if (!ConstraintsComponents.Contains(Constraint))
{
UPrimitiveComponent* CollisionDisabledComponent1 = Cast<UPrimitiveComponent>(
GetDefaultSubobjectByName(Constraint->ComponentName1.ComponentName));
GetDefaultSubobjectByName(Constraint->ComponentName1.ComponentName));
UPrimitiveComponent* CollisionDisabledComponent2 = Cast<UPrimitiveComponent>(
GetDefaultSubobjectByName(Constraint->ComponentName2.ComponentName));
GetDefaultSubobjectByName(Constraint->ComponentName2.ComponentName));
if (CollisionDisabledComponent1)
{
CollisionDisableConstraints.Add(CollisionDisabledComponent1, Constraint);
@ -132,11 +132,11 @@ void ACarlaWheeledVehicle::BeginPlay()
// Check if it overlaps with a Friction trigger, if so, update the friction
// scale.
TArray<AActor *> OverlapActors;
TArray<AActor*> OverlapActors;
GetOverlappingActors(OverlapActors, AFrictionTrigger::StaticClass());
for (const auto &Actor : OverlapActors)
for (const auto& Actor : OverlapActors)
{
AFrictionTrigger *FrictionTrigger = Cast<AFrictionTrigger>(Actor);
AFrictionTrigger* FrictionTrigger = Cast<AFrictionTrigger>(Actor);
if (FrictionTrigger)
{
FrictionScale = FrictionTrigger->Friction;
@ -147,7 +147,7 @@ void ACarlaWheeledVehicle::BeginPlay()
TArray<FChaosWheelSetup> NewWheelSetups = MovementComponent->WheelSetups;
for (const FChaosWheelSetup& WheelSetup : NewWheelSetups)
{
UChaosVehicleWheel *Wheel = WheelSetup.WheelClass.GetDefaultObject();
UChaosVehicleWheel* Wheel = WheelSetup.WheelClass.GetDefaultObject();
check(Wheel != nullptr);
}
@ -171,20 +171,20 @@ bool ACarlaWheeledVehicle::IsInVehicleRange(const FVector& Location) const
void ACarlaWheeledVehicle::UpdateDetectionBox()
{
const FTransform GlobalTransform = GetActorTransform();
const FVector Vec { DetectionSize, DetectionSize, DetectionSize };
const FVector Vec{ DetectionSize, DetectionSize, DetectionSize };
FBox Box = FBox(-Vec, Vec);
const FTransform NonScaledTransform(GlobalTransform.GetRotation(), GlobalTransform.GetLocation(), {1.0f, 1.0f, 1.0f});
const FTransform NonScaledTransform(GlobalTransform.GetRotation(), GlobalTransform.GetLocation(), { 1.0f, 1.0f, 1.0f });
FoliageBoundingBox = Box.TransformBy(NonScaledTransform);
}
const TArray<int32> ACarlaWheeledVehicle::GetFoliageInstancesCloseToVehicle(const UInstancedStaticMeshComponent* Component) const
{
{
TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaWheeledVehicle::GetFoliageInstancesCloseToVehicle);
return Component->GetInstancesOverlappingBox(FoliageBoundingBox);
}
FBox ACarlaWheeledVehicle::GetDetectionBox() const
{
{
TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaWheeledVehicle::GetDetectionBox);
return FoliageBoundingBox;
}
@ -269,7 +269,7 @@ float ACarlaWheeledVehicle::GetMaximumSteerAngle() const
const auto& Wheels = MovementComponent->WheelSetups;
check(Wheels.Num() > 0);
const UChaosVehicleWheel* FrontWheel =
Cast<UChaosVehicleWheel>(Wheels[0].WheelClass->GetDefaultObject());
Cast<UChaosVehicleWheel>(Wheels[0].WheelClass->GetDefaultObject());
check(FrontWheel != nullptr);
return FrontWheel->MaxSteerAngle;
}
@ -333,7 +333,7 @@ TArray<float> ACarlaWheeledVehicle::GetWheelsFrictionScale()
{
check(Movement != nullptr);
for (auto &Wheel : Movement->Wheels)
for (auto& Wheel : Movement->Wheels)
{
WheelsFrictionScale.Add(Wheel->FrictionForceMultiplier);
}
@ -342,7 +342,7 @@ TArray<float> ACarlaWheeledVehicle::GetWheelsFrictionScale()
return WheelsFrictionScale;
}
void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float> &WheelsFrictionScale)
void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float>& WheelsFrictionScale)
{
UChaosWheeledVehicleMovementComponent* Movement = GetChaosWheeledVehicleMovementComponent();
if (Movement)
@ -359,72 +359,99 @@ void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float> &WheelsFrictionS
FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const
{
FVehiclePhysicsControl PhysicsControl;
UChaosWheeledVehicleMovementComponent* VehicleMovComponent = GetChaosWheeledVehicleMovementComponent();
check(VehicleMovComponent != nullptr);
// Engine Setup
PhysicsControl.TorqueCurve = VehicleMovComponent->EngineSetup.TorqueCurve.EditorCurveData;
PhysicsControl.MaxTorque = VehicleMovComponent->EngineSetup.MaxTorque;
PhysicsControl.MaxRPM = VehicleMovComponent->EngineSetup.MaxRPM;
PhysicsControl.MOI = VehicleMovComponent->EngineSetup.EngineRevUpMOI;
PhysicsControl.RevDownRate = VehicleMovComponent->EngineSetup.EngineRevDownRate;
// Differential Setup
PhysicsControl.DifferentialType = static_cast<uint8>(VehicleMovComponent->DifferentialSetup.DifferentialType);
PhysicsControl.FrontRearSplit = VehicleMovComponent->DifferentialSetup.FrontRearSplit;
// Transmission Setup
PhysicsControl.bUseGearAutoBox = VehicleMovComponent->TransmissionSetup.bUseAutomaticGears;
PhysicsControl.FinalRatio = VehicleMovComponent->TransmissionSetup.FinalRatio;
PhysicsControl.ForwardGears = VehicleMovComponent->TransmissionSetup.ForwardGearRatios;
PhysicsControl.ReverseGears = VehicleMovComponent->TransmissionSetup.ReverseGearRatios;
PhysicsControl.ChangeUpRPM = VehicleMovComponent->TransmissionSetup.ChangeUpRPM;
PhysicsControl.ChangeDownRPM = VehicleMovComponent->TransmissionSetup.ChangeDownRPM;
PhysicsControl.GearSwitchTime = VehicleMovComponent->TransmissionSetup.GearChangeTime;
PhysicsControl.TransmissionEfficiency = VehicleMovComponent->TransmissionSetup.TransmissionEfficiency;
// VehicleMovComponent Setup
PhysicsControl.Mass = VehicleMovComponent->Mass;
PhysicsControl.DragCoefficient = VehicleMovComponent->DragCoefficient;
// Center of mass offset (Center of mass is always zero vector in local
// position)
UPrimitiveComponent *UpdatedPrimitive = Cast<UPrimitiveComponent>(VehicleMovComponent->UpdatedComponent);
check(UpdatedPrimitive != nullptr);
PhysicsControl.CenterOfMass = UpdatedPrimitive->GetCenterOfMass();
// Transmission Setup
PhysicsControl.SteeringCurve = VehicleMovComponent->SteeringSetup.SteeringCurve.EditorCurveData;
FVehiclePhysicsControl PhysicsControl = { };
auto VehicleMovComponentPtr = GetChaosWheeledVehicleMovementComponent();
check(VehicleMovComponentPtr != nullptr);
auto& VehicleMovComponent = *VehicleMovComponentPtr;
auto& EngineSetup = VehicleMovComponent.EngineSetup;
auto RCurve = EngineSetup.TorqueCurve.GetRichCurve();
check(RCurve != nullptr);
PhysicsControl.TorqueCurve = *RCurve;
PhysicsControl.MaxTorque = EngineSetup.MaxTorque;
PhysicsControl.MaxRPM = EngineSetup.MaxRPM;
PhysicsControl.IdleRPM = EngineSetup.EngineIdleRPM;
PhysicsControl.BrakeEffect = EngineSetup.EngineBrakeEffect;
PhysicsControl.RevUpMOI = EngineSetup.EngineRevUpMOI;
PhysicsControl.RevDownRate = EngineSetup.EngineRevDownRate;
auto& DifferentialSetup = VehicleMovComponent.DifferentialSetup;
PhysicsControl.DifferentialType = (uint8_t)DifferentialSetup.DifferentialType;
PhysicsControl.FrontRearSplit = DifferentialSetup.FrontRearSplit;
auto& TransmissionSetup = VehicleMovComponent.TransmissionSetup;
PhysicsControl.bUseAutomaticGears = TransmissionSetup.bUseAutomaticGears;
PhysicsControl.GearChangeTime = TransmissionSetup.GearChangeTime;
PhysicsControl.FinalRatio = TransmissionSetup.FinalRatio;
PhysicsControl.ForwardGearRatios = TransmissionSetup.ForwardGearRatios;
PhysicsControl.ReverseGearRatios = TransmissionSetup.ReverseGearRatios;
PhysicsControl.ChangeUpRPM = TransmissionSetup.ChangeUpRPM;
PhysicsControl.ChangeDownRPM = TransmissionSetup.ChangeDownRPM;
PhysicsControl.TransmissionEfficiency = TransmissionSetup.TransmissionEfficiency;
PhysicsControl.Mass = VehicleMovComponent.Mass;
PhysicsControl.DragCoefficient = VehicleMovComponent.DragCoefficient;
auto PrimitiveComponentPtr = Cast<UPrimitiveComponent>(VehicleMovComponent.UpdatedComponent);
check(PrimitiveComponentPtr != nullptr);
PhysicsControl.CenterOfMass = PrimitiveComponentPtr->GetCenterOfMass();
PhysicsControl.ChassisWidth = VehicleMovComponent.ChassisWidth;
PhysicsControl.ChassisHeight = VehicleMovComponent.ChassisHeight;
PhysicsControl.DownforceCoefficient = VehicleMovComponent.DownforceCoefficient;
PhysicsControl.DragArea = VehicleMovComponent.DragArea;
PhysicsControl.InertiaTensorScale = VehicleMovComponent.InertiaTensorScale;
PhysicsControl.SleepThreshold = VehicleMovComponent.SleepThreshold;
PhysicsControl.SleepSlopeLimit = VehicleMovComponent.SleepSlopeLimit;
RCurve = VehicleMovComponent.SteeringSetup.SteeringCurve.GetRichCurve();
check(RCurve != nullptr);
PhysicsControl.SteeringCurve = *RCurve;
PhysicsControl.UseSweepWheelCollision = false;
// Wheels Setup
TArray<FWheelPhysicsControl> Wheels;
for (int32 i = 0; i < VehicleMovComponent->WheelSetups.Num(); ++i)
PhysicsControl.Wheels.SetNum(VehicleMovComponent.WheelSetups.Num());
for (int32 i = 0; i < PhysicsControl.Wheels.Num(); ++i)
{
FWheelPhysicsControl PhysicsWheel;
PhysicsWheel.Radius = VehicleMovComponent->Wheels[i]->WheelRadius;
PhysicsWheel.FrictionForceMultiplier = VehicleMovComponent->Wheels[i]->FrictionForceMultiplier;
PhysicsWheel.MaxSteerAngle = VehicleMovComponent->Wheels[i]->MaxSteerAngle;
PhysicsWheel.MaxBrakeTorque = VehicleMovComponent->Wheels[i]->MaxBrakeTorque;
PhysicsWheel.MaxHandBrakeTorque = VehicleMovComponent->Wheels[i]->MaxHandBrakeTorque;
PhysicsWheel.Position = VehicleMovComponent->Wheels[i]->Location;
PhysicsWheel.CorneringStiffness = VehicleMovComponent->Wheels[i]->CorneringStiffness;
PhysicsWheel.bABSEnabled = VehicleMovComponent->Wheels[i]->bABSEnabled;
PhysicsWheel.bTractionControlEnabled = VehicleMovComponent->Wheels[i]->bTractionControlEnabled;
if(VehicleMovComponent->Wheels[i]->SweepShape == ESweepShape::Spherecast)
{
// If some of the wheels use Spherecast, it will be used for everyone if we call ApplyPhisicsControl() as it has no sense to have it only for one.
auto& In = *VehicleMovComponent.Wheels[i];
auto& Out = PhysicsControl.Wheels[i];
Out.AxleType = In.AxleType;
Out.Offset = In.Offset;
Out.WheelRadius = In.WheelRadius;
Out.WheelWidth = In.WheelWidth;
Out.WheelMass = In.WheelMass;
Out.CorneringStiffness = In.CorneringStiffness;
Out.FrictionForceMultiplier = In.FrictionForceMultiplier;
Out.SideSlipModifier = In.SideSlipModifier;
Out.SlipThreshold = In.SlipThreshold;
Out.SkidThreshold = In.SkidThreshold;
Out.MaxSteerAngle = In.MaxSteerAngle;
Out.bAffectedBySteering = In.bAffectedBySteering;
Out.bAffectedByBrake = In.bAffectedByBrake;
Out.bAffectedByHandbrake = In.bAffectedByHandbrake;
Out.bAffectedByEngine = In.bAffectedByEngine;
Out.bABSEnabled = In.bABSEnabled;
Out.bTractionControlEnabled = In.bTractionControlEnabled;
Out.MaxWheelspinRotation = In.MaxWheelspinRotation;
Out.ExternalTorqueCombineMethod = In.ExternalTorqueCombineMethod;
RCurve = In.LateralSlipGraph.GetRichCurve();
check(RCurve != nullptr);
Out.LateralSlipGraph = *RCurve;
Out.SuspensionAxis = In.SuspensionAxis;
Out.SuspensionForceOffset = In.SuspensionForceOffset;
Out.SuspensionMaxRaise = In.SuspensionMaxRaise;
Out.SuspensionMaxDrop = In.SuspensionMaxDrop;
Out.SuspensionDampingRatio = In.SuspensionDampingRatio;
Out.WheelLoadRatio = In.WheelLoadRatio;
Out.SpringRate = In.SpringRate;
Out.SpringPreload = In.SpringPreload;
Out.SuspensionSmoothing = In.SuspensionSmoothing;
Out.RollbarScaling = In.RollbarScaling;
Out.SweepShape = In.SweepShape;
Out.SweepType = In.SweepType;
Out.MaxBrakeTorque = In.MaxBrakeTorque;
Out.MaxHandBrakeTorque = In.MaxHandBrakeTorque;
Out.WheelIndex = In.WheelIndex;
Out.Location = In.Location;
Out.OldLocation = In.OldLocation;
Out.Velocity = In.Velocity;
// If some of the wheels use Spherecast, it will be used for everyone
// if we call ApplyPhisicsControl() as it has no sense to have it only for one.
if (In.SweepShape == ESweepShape::Spherecast)
PhysicsControl.UseSweepWheelCollision = true;
}
Wheels.Add(PhysicsWheel);
}
PhysicsControl.Wheels = Wheels;
return PhysicsControl;
}
@ -438,81 +465,117 @@ void ACarlaWheeledVehicle::RestoreVehiclePhysicsControl()
ApplyVehiclePhysicsControl(LastPhysicsControl);
}
void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl)
void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(
const FVehiclePhysicsControl& PhysicsControl)
{
LastPhysicsControl = PhysicsControl;
UChaosWheeledVehicleMovementComponent* VehicleMovComponent = GetChaosWheeledVehicleMovementComponent();
check(VehicleMovComponent != nullptr);
// Engine Setup
VehicleMovComponent->EngineSetup.TorqueCurve.EditorCurveData = PhysicsControl.TorqueCurve;
VehicleMovComponent->EngineSetup.MaxTorque = PhysicsControl.MaxTorque;
VehicleMovComponent->EngineSetup.MaxRPM = PhysicsControl.MaxRPM;
VehicleMovComponent->EngineSetup.EngineRevUpMOI = PhysicsControl.MOI;
VehicleMovComponent->EngineSetup.EngineRevDownRate = PhysicsControl.RevDownRate;
// Differential Setup
VehicleMovComponent->DifferentialSetup.DifferentialType = static_cast<EVehicleDifferential>(PhysicsControl.DifferentialType);
VehicleMovComponent->DifferentialSetup.FrontRearSplit = PhysicsControl.FrontRearSplit;
// Transmission Setup
VehicleMovComponent->TransmissionSetup.bUseAutomaticGears = PhysicsControl.bUseGearAutoBox;
VehicleMovComponent->TransmissionSetup.FinalRatio = PhysicsControl.FinalRatio;
VehicleMovComponent->TransmissionSetup.ForwardGearRatios = PhysicsControl.ForwardGears;
VehicleMovComponent->TransmissionSetup.ReverseGearRatios = PhysicsControl.ReverseGears;
VehicleMovComponent->TransmissionSetup.ChangeUpRPM = PhysicsControl.ChangeUpRPM;
VehicleMovComponent->TransmissionSetup.ChangeDownRPM = PhysicsControl.ChangeDownRPM;
VehicleMovComponent->TransmissionSetup.GearChangeTime = PhysicsControl.GearSwitchTime;
VehicleMovComponent->TransmissionSetup.TransmissionEfficiency = PhysicsControl.TransmissionEfficiency;
// Vehicle Setup
VehicleMovComponent->Mass = PhysicsControl.Mass;
VehicleMovComponent->DragCoefficient = PhysicsControl.DragCoefficient;
// Center of mass
UPrimitiveComponent *UpdatedPrimitive = Cast<UPrimitiveComponent>(VehicleMovComponent->UpdatedComponent);
check(UpdatedPrimitive != nullptr);
UpdatedPrimitive->BodyInstance.COMNudge = PhysicsControl.CenterOfMass;
// Transmission Setup
VehicleMovComponent->SteeringSetup.SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve;
auto VehicleMovComponentPtr = GetChaosWheeledVehicleMovementComponent();
check(VehicleMovComponentPtr != nullptr);
auto& VehicleMovComponent = *VehicleMovComponentPtr;
auto& EngineSetup = VehicleMovComponent.EngineSetup;
EngineSetup.TorqueCurve.EditorCurveData = PhysicsControl.TorqueCurve;
EngineSetup.MaxTorque = PhysicsControl.MaxTorque;
EngineSetup.MaxRPM = PhysicsControl.MaxRPM;
EngineSetup.EngineIdleRPM = PhysicsControl.IdleRPM;
EngineSetup.EngineBrakeEffect = PhysicsControl.BrakeEffect;
EngineSetup.EngineRevUpMOI = PhysicsControl.RevUpMOI;
EngineSetup.EngineRevDownRate = PhysicsControl.RevDownRate;
auto& DifferentialSetup = VehicleMovComponent.DifferentialSetup;
DifferentialSetup.DifferentialType = (EVehicleDifferential)PhysicsControl.DifferentialType;
DifferentialSetup.FrontRearSplit = PhysicsControl.FrontRearSplit;
auto& TransmissionSetup = VehicleMovComponent.TransmissionSetup;
TransmissionSetup.bUseAutomaticGears = PhysicsControl.bUseAutomaticGears;
TransmissionSetup.GearChangeTime = PhysicsControl.GearChangeTime;
TransmissionSetup.FinalRatio = PhysicsControl.FinalRatio;
TransmissionSetup.ForwardGearRatios = PhysicsControl.ForwardGearRatios;
TransmissionSetup.ReverseGearRatios = PhysicsControl.ReverseGearRatios;
TransmissionSetup.ChangeUpRPM = PhysicsControl.ChangeUpRPM;
TransmissionSetup.ChangeDownRPM = PhysicsControl.ChangeDownRPM;
TransmissionSetup.TransmissionEfficiency = PhysicsControl.TransmissionEfficiency;
VehicleMovComponent.Mass = PhysicsControl.Mass;
VehicleMovComponent.DragCoefficient = PhysicsControl.DragCoefficient;
auto PrimitiveComponentPtr = Cast<UPrimitiveComponent>(VehicleMovComponent.UpdatedComponent);
check(PrimitiveComponentPtr != nullptr);
auto& PrimitiveComponent = *PrimitiveComponentPtr;
PrimitiveComponent.SetCenterOfMass(PhysicsControl.CenterOfMass);
VehicleMovComponent.ChassisWidth = PhysicsControl.ChassisWidth;
VehicleMovComponent.ChassisHeight = PhysicsControl.ChassisHeight;
VehicleMovComponent.DownforceCoefficient = PhysicsControl.DownforceCoefficient;
VehicleMovComponent.DragArea = PhysicsControl.DragArea;
VehicleMovComponent.InertiaTensorScale = PhysicsControl.InertiaTensorScale;
VehicleMovComponent.SleepThreshold = PhysicsControl.SleepThreshold;
VehicleMovComponent.SleepSlopeLimit = PhysicsControl.SleepSlopeLimit;
auto& SteeringSetup = VehicleMovComponent.SteeringSetup;
SteeringSetup.SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve;
// Wheels Setup
const int PhysicsWheelsNum = PhysicsControl.Wheels.Num();
// TODO:: What about bikes or NW vehicles?
if (PhysicsWheelsNum != 4)
auto WheelCount = PhysicsControl.Wheels.Num();
// @TODO: What about bikes or NW vehicles?
if (WheelCount != 4)
{
UE_LOG(LogCarla, Error, TEXT("Number of WheelPhysicsControl is not 4."));
return;
}
// Change, if required, the collision mode for wheels
TArray<FChaosWheelSetup> NewWheelSetups = VehicleMovComponent->WheelSetups;
for (int32 i = 0; i < PhysicsWheelsNum; ++i)
{
UChaosVehicleWheel *Wheel = NewWheelSetups[i].WheelClass.GetDefaultObject();
check(Wheel != nullptr);
}
VehicleMovComponent->WheelSetups = NewWheelSetups;
for (auto& WheelSetup : VehicleMovComponent.WheelSetups)
check(WheelSetup.WheelClass != nullptr);
for (int32 i = 0; i < PhysicsWheelsNum; ++i)
for (int32 i = 0; i < WheelCount; ++i)
{
VehicleMovComponent->SetWheelRadius(i, PhysicsControl.Wheels[i].Radius);
VehicleMovComponent->SetWheelFrictionMultiplier(i, PhysicsControl.Wheels[i].FrictionForceMultiplier);
VehicleMovComponent->SetWheelMaxSteerAngle(i, PhysicsControl.Wheels[i].MaxSteerAngle);
VehicleMovComponent->SetWheelMaxBrakeTorque(i, PhysicsControl.Wheels[i].MaxBrakeTorque);
VehicleMovComponent->SetWheelHandbrakeTorque(i, PhysicsControl.Wheels[i].MaxHandBrakeTorque);
VehicleMovComponent->SetABSEnabled(i, PhysicsControl.Wheels[i].bABSEnabled);
VehicleMovComponent->SetTractionControlEnabled(i, PhysicsControl.Wheels[i].bTractionControlEnabled);
VehicleMovComponent->Wheels[i]->CorneringStiffness = PhysicsControl.Wheels[i].CorneringStiffness;
VehicleMovComponent->Wheels[i]->SweepShape = PhysicsControl.UseSweepWheelCollision ? ESweepShape::Spherecast : ESweepShape::Raycast;
auto& In = PhysicsControl.Wheels[i];
auto OutPtr = VehicleMovComponent.Wheels[i];
check(OutPtr != nullptr);
auto& Out = *OutPtr;
Out.AxleType = In.AxleType;
Out.Offset = In.Offset;
VehicleMovComponent.SetWheelRadius(i, In.WheelRadius);
Out.WheelWidth = In.WheelWidth;
Out.WheelMass = In.WheelMass;
Out.CorneringStiffness = In.CorneringStiffness;
VehicleMovComponent.SetWheelFrictionMultiplier(i, In.FrictionForceMultiplier);
Out.SideSlipModifier = In.SideSlipModifier;
Out.SlipThreshold = In.SlipThreshold;
Out.SkidThreshold = In.SkidThreshold;
VehicleMovComponent.SetWheelMaxSteerAngle(i, In.MaxSteerAngle);
Out.bAffectedBySteering = In.bAffectedBySteering;
Out.bAffectedByBrake = In.bAffectedByBrake;
Out.bAffectedByHandbrake = In.bAffectedByHandbrake;
Out.bAffectedByEngine = In.bAffectedByEngine;
VehicleMovComponent.SetABSEnabled(i, In.bABSEnabled);
VehicleMovComponent.SetTractionControlEnabled(i, In.bTractionControlEnabled);
Out.MaxWheelspinRotation = In.MaxWheelspinRotation;
Out.ExternalTorqueCombineMethod = In.ExternalTorqueCombineMethod;
Out.LateralSlipGraph.EditorCurveData = In.LateralSlipGraph;
Out.SuspensionAxis = In.SuspensionAxis;
Out.SuspensionForceOffset = In.SuspensionForceOffset;
Out.SuspensionMaxRaise = In.SuspensionMaxRaise;
Out.SuspensionMaxDrop = In.SuspensionMaxDrop;
Out.SuspensionDampingRatio = In.SuspensionDampingRatio;
Out.WheelLoadRatio = In.WheelLoadRatio;
Out.SpringRate = In.SpringRate;
Out.SpringPreload = In.SpringPreload;
Out.SuspensionSmoothing = In.SuspensionSmoothing;
Out.RollbarScaling = In.RollbarScaling;
Out.SweepShape = In.SweepShape;
Out.SweepType = In.SweepType;
VehicleMovComponent.SetWheelMaxBrakeTorque(i, In.MaxBrakeTorque);
VehicleMovComponent.SetWheelHandbrakeTorque(i, In.MaxHandBrakeTorque);
Out.WheelIndex = In.WheelIndex;
Out.Location = In.Location;
Out.OldLocation = In.OldLocation;
Out.Velocity = In.Velocity;
Out.SweepShape =
PhysicsControl.UseSweepWheelCollision ?
ESweepShape::Spherecast :
ESweepShape::Raycast;
}
ResetConstraints();
auto * Recorder = UCarlaStatics::GetRecorder(GetWorld());
auto* Recorder = UCarlaStatics::GetRecorder(GetWorld());
if (Recorder && Recorder->IsEnabled())
{
Recorder->AddPhysicsControl(*this);
@ -522,7 +585,7 @@ void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsContr
AckermannController.UpdateVehiclePhysics(this);
}
void ACarlaWheeledVehicle::ApplyVehicleControl(const FVehicleControl &Control, EVehicleInputPriority Priority)
void ACarlaWheeledVehicle::ApplyVehicleControl(const FVehicleControl& Control, EVehicleInputPriority Priority)
{
if (bAckermannControlActive) {
AckermannController.Reset();
@ -536,14 +599,14 @@ void ACarlaWheeledVehicle::ApplyVehicleControl(const FVehicleControl &Control, E
}
}
void ACarlaWheeledVehicle::ApplyVehicleAckermannControl(const FVehicleAckermannControl &AckermannControl, EVehicleInputPriority Priority)
{
bAckermannControlActive = true;
LastAppliedAckermannControl = AckermannControl;
AckermannController.SetTargetPoint(AckermannControl);
}
void ACarlaWheeledVehicle::ApplyVehicleAckermannControl(const FVehicleAckermannControl& AckermannControl, EVehicleInputPriority Priority)
{
bAckermannControlActive = true;
LastAppliedAckermannControl = AckermannControl;
AckermannController.SetTargetPoint(AckermannControl);
}
void ACarlaWheeledVehicle::ActivateVelocityControl(const FVector &Velocity)
void ACarlaWheeledVehicle::ActivateVelocityControl(const FVector& Velocity)
{
VelocityControl->Activate(Velocity);
}
@ -564,45 +627,45 @@ void ACarlaWheeledVehicle::ShowDebugTelemetry(bool Enabled)
ACarlaHUD* hud = Cast<ACarlaHUD>(GetWorld()->GetFirstPlayerController()->GetHUD());
if (hud) {
// Set/Unset the car movement component in HUD to show the temetry
if (Enabled) {
hud->AddDebugVehicleForTelemetry(GetChaosWheeledVehicleMovementComponent());
}
else{
if (hud->DebugVehicle == GetChaosWheeledVehicleMovementComponent()) {
hud->AddDebugVehicleForTelemetry(nullptr);
//GetChaosWheeledVehicleMovementComponent()->StopTelemetry();
}
// Set/Unset the car movement component in HUD to show the temetry
if (Enabled) {
hud->AddDebugVehicleForTelemetry(GetChaosWheeledVehicleMovementComponent());
}
else{
if (hud->DebugVehicle == GetChaosWheeledVehicleMovementComponent()) {
hud->AddDebugVehicleForTelemetry(nullptr);
//GetChaosWheeledVehicleMovementComponent()->StopTelemetry();
}
}
}
else {
UE_LOG(LogCarla, Warning, TEXT("ACarlaWheeledVehicle::ShowDebugTelemetry:: Cannot find HUD for debug info"));
UE_LOG(LogCarla, Warning, TEXT("ACarlaWheeledVehicle::ShowDebugTelemetry:: Cannot find HUD for debug info"));
}
}
*/
}
void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightState)
void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState& LightState)
{
if (LightState.Position != InputControl.LightState.Position ||
LightState.LowBeam != InputControl.LightState.LowBeam ||
LightState.HighBeam != InputControl.LightState.HighBeam ||
LightState.Brake != InputControl.LightState.Brake ||
LightState.RightBlinker != InputControl.LightState.RightBlinker ||
LightState.LeftBlinker != InputControl.LightState.LeftBlinker ||
LightState.Reverse != InputControl.LightState.Reverse ||
LightState.Fog != InputControl.LightState.Fog ||
LightState.Interior != InputControl.LightState.Interior ||
LightState.Special1 != InputControl.LightState.Special1 ||
LightState.Special2 != InputControl.LightState.Special2)
LightState.LowBeam != InputControl.LightState.LowBeam ||
LightState.HighBeam != InputControl.LightState.HighBeam ||
LightState.Brake != InputControl.LightState.Brake ||
LightState.RightBlinker != InputControl.LightState.RightBlinker ||
LightState.LeftBlinker != InputControl.LightState.LeftBlinker ||
LightState.Reverse != InputControl.LightState.Reverse ||
LightState.Fog != InputControl.LightState.Fog ||
LightState.Interior != InputControl.LightState.Interior ||
LightState.Special1 != InputControl.LightState.Special1 ||
LightState.Special2 != InputControl.LightState.Special2)
{
InputControl.LightState = LightState;
RefreshLightState(LightState);
}
}
void ACarlaWheeledVehicle::SetFailureState(const carla::rpc::VehicleFailureState &InFailureState)
void ACarlaWheeledVehicle::SetFailureState(const carla::rpc::VehicleFailureState& InFailureState)
{
FailureState = InFailureState;
}
@ -616,15 +679,15 @@ void ACarlaWheeledVehicle::SetCarlaMovementComponent(UBaseCarlaMovementComponent
BaseMovementComponent = NewBaseMovementComponent;
}
void ACarlaWheeledVehicle::SetWheelSteerDirection(EVehicleWheelLocation WheelLocation, float AngleInDeg)
void ACarlaWheeledVehicle::SetWheelSteerDirection(EVehicleWheelLocation WheelLocation, float AngleInDeg)
{
if (bPhysicsEnabled == false)
{
check((uint8)WheelLocation >= 0)
UVehicleAnimationInstance *VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
UVehicleAnimationInstance* VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
check(VehicleAnim != nullptr)
// ToDo We need to investigate about this
//VehicleAnim->GetWheelAnimData()SetWheelRotYaw((uint8)WheelLocation, AngleInDeg);
// ToDo We need to investigate about this
//VehicleAnim->GetWheelAnimData()SetWheelRotYaw((uint8)WheelLocation, AngleInDeg);
}
else
{
@ -636,25 +699,25 @@ float ACarlaWheeledVehicle::GetWheelSteerAngle(EVehicleWheelLocation WheelLocati
#if 0 // @CARLAUE5 // ToDo We need to investigate about this
check((uint8)WheelLocation >= 0)
UVehicleAnimationInstance *VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
UVehicleAnimationInstance* VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
check(VehicleAnim != nullptr)
check(VehicleAnim->GetWheeledVehicleMovementComponent() != nullptr)
check(VehicleAnim->GetWheeledVehicleMovementComponent() != nullptr)
if (bPhysicsEnabled == true)
{
return VehicleAnim->GetWheeledVehicleMovementComponent()->Wheels[(uint8)WheelLocation]->GetSteerAngle();
}
else
{
return VehicleAnim->GetWheelRotAngle((uint8)WheelLocation);
}
if (bPhysicsEnabled == true)
{
return VehicleAnim->GetWheeledVehicleMovementComponent()->Wheels[(uint8)WheelLocation]->GetSteerAngle();
}
else
{
return VehicleAnim->GetWheelRotAngle((uint8)WheelLocation);
}
#else
return 0.0F;
return 0.0F;
#endif
}
void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) {
if(!GetCarlaMovementComponent<UDefaultMovementComponent>())
if (!GetCarlaMovementComponent<UDefaultMovementComponent>())
{
return;
}
@ -664,27 +727,27 @@ void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) {
{
check(Movement != nullptr);
if(bPhysicsEnabled == enabled)
if (bPhysicsEnabled == enabled)
return;
SetActorEnableCollision(true);
UPrimitiveComponent* RootPrimitive =
Cast<UPrimitiveComponent>(GetRootComponent());
Cast<UPrimitiveComponent>(GetRootComponent());
RootPrimitive->SetSimulatePhysics(enabled);
RootPrimitive->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
UVehicleAnimationInstance *VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
UVehicleAnimationInstance* VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
check(VehicleAnim != nullptr)
if (enabled)
{
Movement->RecreatePhysicsState();
//VehicleAnim->ResetWheelCustomRotations();
}
else
{
Movement->DestroyPhysicsState();
}
if (enabled)
{
Movement->RecreatePhysicsState();
//VehicleAnim->ResetWheelCustomRotations();
}
else
{
Movement->DestroyPhysicsState();
}
bPhysicsEnabled = enabled;
ResetConstraints();
@ -754,9 +817,9 @@ void ACarlaWheeledVehicle::OpenDoorPhys(const EVehicleDoor DoorIdx)
UPhysicsConstraintComponent* Constraint = ConstraintsComponents[static_cast<int>(DoorIdx)];
UPrimitiveComponent* DoorComponent = ConstraintDoor[Constraint];
DoorComponent->DetachFromComponent(
FDetachmentTransformRules(EDetachmentRule::KeepWorld, false));
FDetachmentTransformRules(EDetachmentRule::KeepWorld, false));
FTransform DoorInitialTransform =
DoorComponentsTransform[DoorComponent] * GetActorTransform();
DoorComponentsTransform[DoorComponent] * GetActorTransform();
DoorComponent->SetWorldTransform(DoorInitialTransform);
DoorComponent->SetSimulatePhysics(true);
DoorComponent->SetCollisionProfileName(TEXT("BlockAll"));
@ -773,7 +836,7 @@ void ACarlaWheeledVehicle::OpenDoorPhys(const EVehicleDoor DoorIdx)
Constraint->InitComponentConstraint();
UPhysicsConstraintComponent** CollisionDisable =
CollisionDisableConstraints.Find(DoorComponent);
CollisionDisableConstraints.Find(DoorComponent);
if (CollisionDisable)
{
(*CollisionDisable)->InitComponentConstraint();
@ -787,21 +850,21 @@ void ACarlaWheeledVehicle::CloseDoorPhys(const EVehicleDoor DoorIdx)
UPhysicsConstraintComponent* Constraint = ConstraintsComponents[static_cast<int>(DoorIdx)];
UPrimitiveComponent* DoorComponent = ConstraintDoor[Constraint];
FTransform DoorInitialTransform =
DoorComponentsTransform[DoorComponent] * GetActorTransform();
DoorComponentsTransform[DoorComponent] * GetActorTransform();
DoorComponent->SetSimulatePhysics(false);
DoorComponent->SetCollisionProfileName(TEXT("NoCollision"));
DoorComponent->SetWorldTransform(DoorInitialTransform);
DoorComponent->AttachToComponent(
GetMesh(), FAttachmentTransformRules(EAttachmentRule::KeepWorld, true));
GetMesh(), FAttachmentTransformRules(EAttachmentRule::KeepWorld, true));
RecordDoorChange(DoorIdx, false);
}
void ACarlaWheeledVehicle::RecordDoorChange(const EVehicleDoor DoorIdx, bool bIsOpen)
{
auto * Recorder = UCarlaStatics::GetRecorder(GetWorld());
auto* Recorder = UCarlaStatics::GetRecorder(GetWorld());
if (Recorder && Recorder->IsEnabled())
{
Recorder->AddVehicleDoor(*this, DoorIdx, bIsOpen);
Recorder->AddVehicleDoor(*this, DoorIdx, bIsOpen);
}
}
@ -812,28 +875,28 @@ void ACarlaWheeledVehicle::ApplyRolloverBehavior()
// The angular velocity reduction is applied in 4 stages, to improve its smoothness.
// Case 4 starts the timer to set the rollover flag, so users are notified.
switch (RolloverBehaviorTracker) {
case 0: CheckRollover(roll, std::make_pair(130.0, 230.0)); break;
case 1: CheckRollover(roll, std::make_pair(140.0, 220.0)); break;
case 2: CheckRollover(roll, std::make_pair(150.0, 210.0)); break;
case 3: CheckRollover(roll, std::make_pair(160.0, 200.0)); break;
case 4:
GetWorld()->GetTimerManager().SetTimer(TimerHandler, this, &ACarlaWheeledVehicle::SetRolloverFlag, RolloverFlagTime);
RolloverBehaviorTracker += 1;
break;
case 5: break;
default:
RolloverBehaviorTracker = 5;
case 0: CheckRollover(roll, std::make_pair(130.0, 230.0)); break;
case 1: CheckRollover(roll, std::make_pair(140.0, 220.0)); break;
case 2: CheckRollover(roll, std::make_pair(150.0, 210.0)); break;
case 3: CheckRollover(roll, std::make_pair(160.0, 200.0)); break;
case 4:
GetWorld()->GetTimerManager().SetTimer(TimerHandler, this, &ACarlaWheeledVehicle::SetRolloverFlag, RolloverFlagTime);
RolloverBehaviorTracker += 1;
break;
case 5: break;
default:
RolloverBehaviorTracker = 5;
}
// In case the vehicle recovers, reset the rollover tracker
if (RolloverBehaviorTracker > 0 && -30 < roll && roll < 30){
if (RolloverBehaviorTracker > 0 && -30 < roll && roll < 30) {
RolloverBehaviorTracker = 0;
FailureState = carla::rpc::VehicleFailureState::None;
}
}
void ACarlaWheeledVehicle::CheckRollover(const float roll, const std::pair<float, float> threshold_roll){
if (threshold_roll.first < roll && roll < threshold_roll.second){
void ACarlaWheeledVehicle::CheckRollover(const float roll, const std::pair<float, float> threshold_roll) {
if (threshold_roll.first < roll && roll < threshold_roll.second) {
auto Root = Cast<UPrimitiveComponent>(GetRootComponent());
auto AngularVelocity = Root->GetPhysicsAngularVelocityInDegrees();
Root->SetPhysicsAngularVelocityInDegrees((1 - RolloverBehaviorForce) * AngularVelocity);
@ -841,14 +904,14 @@ void ACarlaWheeledVehicle::CheckRollover(const float roll, const std::pair<float
}
}
void ACarlaWheeledVehicle::SetRolloverFlag(){
void ACarlaWheeledVehicle::SetRolloverFlag() {
// Make sure the vehicle hasn't recovered since the timer started
if (RolloverBehaviorTracker >= 4) {
FailureState = carla::rpc::VehicleFailureState::Rollover;
}
}
carla::rpc::VehicleFailureState ACarlaWheeledVehicle::GetFailureState() const{
carla::rpc::VehicleFailureState ACarlaWheeledVehicle::GetFailureState() const {
return FailureState;
}
@ -883,13 +946,13 @@ void ACarlaWheeledVehicle::RemoveReferenceToManager()
}
FRotator ACarlaWheeledVehicle::GetPhysicsConstraintAngle(
UPhysicsConstraintComponent* Component)
UPhysicsConstraintComponent* Component)
{
return Component->ConstraintInstance.AngularRotationOffset;
}
void ACarlaWheeledVehicle::SetPhysicsConstraintAngle(
UPhysicsConstraintComponent* Component, const FRotator &NewAngle)
UPhysicsConstraintComponent* Component, const FRotator& NewAngle)
{
Component->ConstraintInstance.AngularRotationOffset = NewAngle;
}

View File

@ -23,13 +23,19 @@ struct CARLA_API FVehiclePhysicsControl
FRichCurve TorqueCurve;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float MaxTorque = 300.0f;;
float MaxTorque = 300.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float MaxRPM = 5000.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float MOI = 1.0f;
float IdleRPM = 1.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float BrakeEffect = 1.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float RevUpMOI = 1.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float RevDownRate = 600.0f;
@ -38,25 +44,25 @@ struct CARLA_API FVehiclePhysicsControl
// ToDo: Convert to an enum, see EVehicleDifferential.
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
uint8 DifferentialType = 0;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float FrontRearSplit = 0.5f;
// Transmission Setup
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
bool bUseGearAutoBox = true;
bool bUseAutomaticGears = true;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float GearSwitchTime = 0.5f;
float GearChangeTime = 0.5f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float FinalRatio = 4.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
TArray<float> ForwardGears = {2.85, 2.02, 1.35, 1.0, 2.85, 2.02, 1.35, 1.0};
TArray<float> ForwardGearRatios = { 2.85, 2.02, 1.35, 1.0, 2.85, 2.02, 1.35, 1.0 };
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
TArray<float> ReverseGears = {2.86, 2.86};
TArray<float> ReverseGearRatios = { 2.86, 2.86 };
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float ChangeUpRPM = 4500.0f;
@ -78,12 +84,55 @@ struct CARLA_API FVehiclePhysicsControl
FRichCurve SteeringCurve;
// Center Of Mass
UPROPERTY(Category = "Vehicle Center Of Mass", EditAnywhere, BlueprintReadWrite)
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
FVector CenterOfMass = FVector::ZeroVector;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float ChassisWidth = 180.f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float ChassisHeight = 140.f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float DownforceCoefficient = 0.3f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float DragArea = 0.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
FVector InertiaTensorScale = FVector(1.0f, 1.0f, 1.0f);
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float SleepThreshold = 10.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float SleepSlopeLimit = 0.866f; // 30º
/*
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
TArray<FVehicleAerofoilConfig> Aerofoils;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
TArray<FVehicleThrustConfig> Thrusters;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
FVehicleTorqueControlConfig TorqueControl;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
FVehicleTargetRotationControlConfig TargetRotationControl;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
FVehicleStabilizeControlConfig StabilizeControl;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
uint32 VehicleSetupTag;
*/
// Wheels Setup
TArray<FWheelPhysicsControl> Wheels;
UPROPERTY(Category = "Vehicle Wheels Configuration", EditAnywhere, BlueprintReadWrite)
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
bool UseSweepWheelCollision = false;
};

View File

@ -5,7 +5,7 @@
// For a copy, see <https://opensource.org/licenses/MIT>.
#pragma once
#include "ChaosVehicleWheel.h"
#include "WheelPhysicsControl.generated.h"
USTRUCT(BlueprintType)
@ -13,30 +13,166 @@ struct CARLA_API FWheelPhysicsControl
{
GENERATED_BODY()
UPROPERTY(Category = "Wheel Tire Friction", EditAnywhere, BlueprintReadWrite)
float FrictionForceMultiplier = 3.5f;
/** If left undefined then the bAffectedByEngine value is used, if defined then bAffectedByEngine is ignored and the differential setup on the vehicle defines which wheels get power from the engine */
UPROPERTY(EditAnywhere, Category = Wheel)
EAxleType AxleType;
UPROPERTY(Category = "Wheel Max Steer Angle", EditAnywhere, BlueprintReadWrite)
float MaxSteerAngle = 70.0f;
/**
* If BoneName is specified, offset the wheel from the bone's location.
* Otherwise this offsets the wheel from the vehicle's origin.
*/
UPROPERTY(EditAnywhere, Category = Wheel)
FVector Offset;
UPROPERTY(Category = "Wheel Shape Radius", EditAnywhere, BlueprintReadWrite)
float Radius = 30.0f;
/** Radius of the wheel */
UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.01", UIMin = "0.01"))
float WheelRadius;
UPROPERTY(Category = "Tyre Cornering Ability", EditAnywhere, BlueprintReadWrite)
float CorneringStiffness = 1000.0f;
/** Width of the wheel */
UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.01", UIMin = "0.01"))
float WheelWidth;
UPROPERTY(Category = "Advanced Braking System Enabled", EditAnywhere, BlueprintReadWrite)
bool bABSEnabled = false;
/** Mass of the wheel Kg */
UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.01", UIMin = "0.01"))
float WheelMass;
UPROPERTY(Category = "Straight Line Traction Control Enabled", EditAnywhere, BlueprintReadWrite)
bool bTractionControlEnabled = false;
/** Tyre Cornering Ability */
UPROPERTY(EditAnywhere, Category = Wheel)
float CorneringStiffness;
UPROPERTY(Category = "Wheel Max Brake Torque (Nm)", EditAnywhere, BlueprintReadWrite)
float MaxBrakeTorque = 1500.0f;
/** Friction Force Multiplier */
UPROPERTY(EditAnywhere, Category = Wheel)
float FrictionForceMultiplier;
UPROPERTY(Category = "Wheel Max Handbrake Torque (Nm)", EditAnywhere, BlueprintReadWrite)
float MaxHandBrakeTorque = 3000.0f;
/** Wheel Lateral Skid Grip Loss, lower number less grip on skid */
UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"))
float SideSlipModifier;
/** Wheel Longitudinal Slip Threshold */
UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.0", UIMin = "0.0"))
float SlipThreshold;
/** Wheel Lateral Skid Threshold */
UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.0", UIMin = "0.0"))
float SkidThreshold;
// steer angle in degrees for this wheel
UPROPERTY(EditAnywhere, Category = WheelsSetup)
float MaxSteerAngle;
/** Whether steering should affect this wheel */
UPROPERTY(EditAnywhere, Category = WheelsSetup)
bool bAffectedBySteering;
/** Whether brake should affect this wheel */
UPROPERTY(EditAnywhere, Category = Wheel)
bool bAffectedByBrake;
/** Whether handbrake should affect this wheel */
UPROPERTY(EditAnywhere, Category = Wheel)
bool bAffectedByHandbrake;
/** Whether engine should power this wheel */
UPROPERTY(EditAnywhere, Category = Wheel)
bool bAffectedByEngine;
/** Advanced Braking System Enabled */
UPROPERTY(EditAnywhere, Category = Wheel)
bool bABSEnabled;
/** Straight Line Traction Control Enabled */
UPROPERTY(EditAnywhere, Category = Wheel)
bool bTractionControlEnabled;
/** Max Wheelspin rotation rad/sec */
UPROPERTY(EditAnywhere, Category = Wheel)
float MaxWheelspinRotation;
/** Determines how the SetDriveTorque/SetBrakeTorque inputs are combined with the internal torques */
UPROPERTY(EditAnywhere, Category = Wheel)
ETorqueCombineMethod ExternalTorqueCombineMethod;
UPROPERTY(EditAnywhere, Category = Setup)
FRichCurve LateralSlipGraph;
/** Local body direction in which where suspension forces are applied (typically along -Z-axis) */
UPROPERTY(EditAnywhere, Category = Suspension)
FVector SuspensionAxis;
/** Vertical offset from where suspension forces are applied (along Z-axis) */
UPROPERTY(EditAnywhere, Category = Suspension)
FVector SuspensionForceOffset;
/** How far the wheel can go above the resting position */
UPROPERTY(EditAnywhere, Category = Suspension)
float SuspensionMaxRaise;
/** How far the wheel can drop below the resting position */
UPROPERTY(EditAnywhere, Category = Suspension)
float SuspensionMaxDrop;
/** Suspension damping, larger value causes the suspension to come to rest faster [range 0 to 1] */
UPROPERTY(EditAnywhere, Category = Suspension)
float SuspensionDampingRatio;
/**
* Amount wheel load effects wheel friction.
At 0 wheel friction is completely independent of the loading on the wheel (This is artificial as it always assumes even balance between all wheels)
At 1 wheel friction is based on the force pressing wheel into the ground. This is more realistic.
Lower value cures lift off over-steer, generally makes vehicle easier to handle under extreme motions.
*/
UPROPERTY(EditAnywhere, Category = Suspension, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"))
float WheelLoadRatio;
/** Spring Force (N/m) */
UPROPERTY(EditAnywhere, Category = Suspension)
float SpringRate;
/** Spring Preload (N/m) */
UPROPERTY(EditAnywhere, Category = Suspension)
float SpringPreload;
/** Smooth suspension [0-off, 10-max] - Warning might cause momentary visual inter-penetration of the wheel against objects/terrain */
UPROPERTY(EditAnywhere, Category = Suspension, meta = (ClampMin = "0.0", UIMin = "0", ClampMax = "10.0", UIMax = "10"))
int SuspensionSmoothing;
/** Anti-roll effect */
UPROPERTY(EditAnywhere, Category = Suspension, meta = (ClampMin = "0.0", UIMin = "0", ClampMax = "1.0", UIMax = "1"))
float RollbarScaling;
/** Wheel suspension trace type, defaults to ray trace */
UPROPERTY(EditAnywhere, Category = Suspension)
ESweepShape SweepShape;
/** Whether wheel suspension considers simple, complex */
UPROPERTY(EditAnywhere, Category = Suspension)
ESweepType SweepType;
/** max brake torque for this wheel (Nm) */
UPROPERTY(EditAnywhere, Category = Brakes)
float MaxBrakeTorque;
/**
* Max handbrake brake torque for this wheel (Nm). A handbrake should have a stronger brake torque
* than the brake. This will be ignored for wheels that are not affected by the handbrake.
*/
UPROPERTY(EditAnywhere, Category = Brakes)
float MaxHandBrakeTorque;
// Our index in the vehicle's (and setup's) wheels array
UPROPERTY(transient)
int32 WheelIndex;
// Worldspace location of this wheel
UPROPERTY(transient)
FVector Location;
// Worldspace location of this wheel last frame
UPROPERTY(transient)
FVector OldLocation;
// Current velocity of the wheel center (change in location over time)
UPROPERTY(Category = "Wheel Position", EditAnywhere, BlueprintReadWrite)
FVector Position = FVector::ZeroVector;
FVector Velocity;
};

View File

@ -10,112 +10,112 @@
#include "Logging/MessageLog.h"
UWheeledVehicleMovementComponentNW::UWheeledVehicleMovementComponentNW(const FObjectInitializer& ObjectInitializer) :
Super(ObjectInitializer)
Super(ObjectInitializer)
{
/*
FVehicleEngineConfig DefEngineData;
DefEngineData.InitDefaults();
EngineSetup.MOI = DefEngineData.EngineRevUpMOI;
EngineSetup.MaxRPM = DefEngineData.MaxRPM;
//
-- We need to investigate about this --
EngineSetup.DampingRateFullThrottle = DefEngineData.mDampingRateFullThrottle;
EngineSetup.DampingRateZeroThrottleClutchEngaged = DefEngineData.mDampingRateZeroThrottleClutchEngaged;
EngineSetup.DampingRateZeroThrottleClutchDisengaged = DefEngineData.mDampingRateZeroThrottleClutchDisengaged;
/*
FVehicleEngineConfig DefEngineData;
DefEngineData.InitDefaults();
EngineSetup.MOI = DefEngineData.EngineRevUpMOI;
EngineSetup.MaxRPM = DefEngineData.MaxRPM;
//
-- We need to investigate about this --
EngineSetup.DampingRateFullThrottle = DefEngineData.mDampingRateFullThrottle;
EngineSetup.DampingRateZeroThrottleClutchEngaged = DefEngineData.mDampingRateZeroThrottleClutchEngaged;
EngineSetup.DampingRateZeroThrottleClutchDisengaged = DefEngineData.mDampingRateZeroThrottleClutchDisengaged;
// Convert from Chaos curve to ours
FRichCurve* TorqueCurveData = EngineSetup.TorqueCurve.GetRichCurve();
for (uint32 KeyIdx = 0; KeyIdx < DefEngineData.TorqueCurve.getNbDataPairs(); ++KeyIdx)
{
float Input = DefEngineData.TorqueCurve.getX(KeyIdx) * EngineSetup.MaxRPM;
float Output = DefEngineData.TorqueCurve.getY(KeyIdx) * DefEngineData.MaxTorque;
TorqueCurveData->AddKey(Input, Output);
}
// Convert from Chaos curve to ours
FRichCurve* TorqueCurveData = EngineSetup.TorqueCurve.GetRichCurve();
for (uint32 KeyIdx = 0; KeyIdx < DefEngineData.TorqueCurve.getNbDataPairs(); ++KeyIdx)
{
float Input = DefEngineData.TorqueCurve.getX(KeyIdx) * EngineSetup.MaxRPM;
float Output = DefEngineData.TorqueCurve.getY(KeyIdx) * DefEngineData.MaxTorque;
TorqueCurveData->AddKey(Input, Output);
}
FVehicleTransmissionConfig TransmissionData;
TransmissionSetup.GearSwitchTime = DefGearSetup.mSwitchTime;
TransmissionSetup.ReverseGearRatio = DefGearSetup.mRatios[PxVehicleGearsData::eREVERSE];
TransmissionSetup.FinalRatio = DefGearSetup.mFinalRatio;
FVehicleTransmissionConfig TransmissionData;
TransmissionSetup.GearChangeTime = DefGearSetup.mSwitchTime;
TransmissionSetup.ReverseGearRatio = DefGearSetup.mRatios[PxVehicleGearsData::eREVERSE];
TransmissionSetup.FinalRatio = DefGearSetup.mFinalRatio;
PxVehicleAutoBoxData DefAutoBoxSetup;
TransmissionSetup.NeutralGearUpRatio = DefAutoBoxSetup.mUpRatios[PxVehicleGearsData::eNEUTRAL];
TransmissionSetup.GearAutoBoxLatency = DefAutoBoxSetup.getLatency();
TransmissionSetup.bUseGearAutoBox = true;
PxVehicleAutoBoxData DefAutoBoxSetup;
TransmissionSetup.NeutralGearUpRatio = DefAutoBoxSetup.mUpRatios[PxVehicleGearsData::eNEUTRAL];
TransmissionSetup.GearAutoBoxLatency = DefAutoBoxSetup.getLatency();
TransmissionSetup.bUseAutomaticGears = true;
for (uint32 i = PxVehicleGearsData::eFIRST; i < DefGearSetup.mNbRatios; ++i)
{
FVehicleNWGearData GearData;
GearData.DownRatio = DefAutoBoxSetup.mDownRatios[i];
GearData.UpRatio = DefAutoBoxSetup.mUpRatios[i];
GearData.Ratio = DefGearSetup.mRatios[i];
TransmissionSetup.ForwardGears.Add(GearData);
}
for (uint32 i = PxVehicleGearsData::eFIRST; i < DefGearSetup.mNbRatios; ++i)
{
FVehicleNWGearData GearData;
GearData.DownRatio = DefAutoBoxSetup.mDownRatios[i];
GearData.UpRatio = DefAutoBoxSetup.mUpRatios[i];
GearData.Ratio = DefGearSetup.mRatios[i];
TransmissionSetup.ForwardGearRatios.Add(GearData);
}
*/
*/
// Init steering speed curve
//FRichCurve* SteeringCurveData = SteeringCurve.GetRichCurve();
//SteeringCurveData->AddKey(0.0f, 1.0f);
//SteeringCurveData->AddKey(20.0f, 0.9f);
//SteeringCurveData->AddKey(60.0f, 0.8f);
//SteeringCurveData->AddKey(120.0f, 0.7f);
// Init steering speed curve
//FRichCurve* SteeringCurveData = SteeringCurve.GetRichCurve();
//SteeringCurveData->AddKey(0.0f, 1.0f);
//SteeringCurveData->AddKey(20.0f, 0.9f);
//SteeringCurveData->AddKey(60.0f, 0.8f);
//SteeringCurveData->AddKey(120.0f, 0.7f);
// Initialize WheelSetups array with 4 wheels, this can be modified via editor later
const int32 NbrWheels = 4;
WheelSetups.SetNum(NbrWheels);
//DifferentialSetup.SetNum(NbrWheels);
// Initialize WheelSetups array with 4 wheels, this can be modified via editor later
const int32 NbrWheels = 4;
WheelSetups.SetNum(NbrWheels);
//DifferentialSetup.SetNum(NbrWheels);
IdleBrakeInput = 10;
IdleBrakeInput = 10;
}
#if WITH_EDITOR
void UWheeledVehicleMovementComponentNW::PostEditChangeProperty(struct FPropertyChangedEvent& PropertyChangedEvent)
{
Super::PostEditChangeProperty(PropertyChangedEvent);
/*
const FName PropertyName = PropertyChangedEvent.Property ? PropertyChangedEvent.Property->GetFName() : NAME_None;
Super::PostEditChangeProperty(PropertyChangedEvent);
/*
const FName PropertyName = PropertyChangedEvent.Property ? PropertyChangedEvent.Property->GetFName() : NAME_None;
if (PropertyName == TEXT("DownRatio"))
{
for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGears.Num(); ++GearIdx)
{
FVehicleNWGearData& GearData = TransmissionSetup.ForwardGears[GearIdx];
GearData.DownRatio = FMath::Min(GearData.DownRatio, GearData.UpRatio);
}
}
else if (PropertyName == TEXT("UpRatio"))
{
for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGears.Num(); ++GearIdx)
{
FVehicleNWGearData& GearData = TransmissionSetup.ForwardGears[GearIdx];
GearData.UpRatio = FMath::Max(GearData.DownRatio, GearData.UpRatio);
}
}
else if (PropertyName == TEXT("SteeringCurve"))
{
//make sure values are capped between 0 and 1
TArray<FRichCurveKey> SteerKeys = SteeringCurve.GetRichCurve()->GetCopyOfKeys();
for (int32 KeyIdx = 0; KeyIdx < SteerKeys.Num(); ++KeyIdx)
{
float NewValue = FMath::Clamp(SteerKeys[KeyIdx].Value, 0.0f, 1.0f);
SteeringCurve.GetRichCurve()->UpdateOrAddKey(SteerKeys[KeyIdx].Time, NewValue);
}
}
*/
if (PropertyName == TEXT("DownRatio"))
{
for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGearRatios.Num(); ++GearIdx)
{
FVehicleNWGearData& GearData = TransmissionSetup.ForwardGearRatios[GearIdx];
GearData.DownRatio = FMath::Min(GearData.DownRatio, GearData.UpRatio);
}
}
else if (PropertyName == TEXT("UpRatio"))
{
for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGearRatios.Num(); ++GearIdx)
{
FVehicleNWGearData& GearData = TransmissionSetup.ForwardGearRatios[GearIdx];
GearData.UpRatio = FMath::Max(GearData.DownRatio, GearData.UpRatio);
}
}
else if (PropertyName == TEXT("SteeringCurve"))
{
//make sure values are capped between 0 and 1
TArray<FRichCurveKey> SteerKeys = SteeringCurve.GetRichCurve()->GetCopyOfKeys();
for (int32 KeyIdx = 0; KeyIdx < SteerKeys.Num(); ++KeyIdx)
{
float NewValue = FMath::Clamp(SteerKeys[KeyIdx].Value, 0.0f, 1.0f);
SteeringCurve.GetRichCurve()->UpdateOrAddKey(SteerKeys[KeyIdx].Time, NewValue);
}
}
*/
}
#endif
float FVehicleNWEngineData::FindPeakTorque() const
{
// Find max torque
float PeakTorque = 0.0f;
TArray<FRichCurveKey> TorqueKeys = TorqueCurve.GetRichCurveConst()->GetCopyOfKeys();
for (int32 KeyIdx = 0; KeyIdx < TorqueKeys.Num(); ++KeyIdx)
{
FRichCurveKey& Key = TorqueKeys[KeyIdx];
PeakTorque = FMath::Max(PeakTorque, Key.Value);
}
// Find max torque
float PeakTorque = 0.0f;
TArray<FRichCurveKey> TorqueKeys = TorqueCurve.GetRichCurveConst()->GetCopyOfKeys();
for (int32 KeyIdx = 0; KeyIdx < TorqueKeys.Num(); ++KeyIdx)
{
FRichCurveKey& Key = TorqueKeys[KeyIdx];
PeakTorque = FMath::Max(PeakTorque, Key.Value);
}
return PeakTorque;
return PeakTorque;
}

View File

@ -12,129 +12,129 @@
USTRUCT()
struct FVehicleNWWheelDifferentialData
{
GENERATED_USTRUCT_BODY()
GENERATED_USTRUCT_BODY()
/** If True, torque is applied to this wheel */
UPROPERTY(EditAnywhere, Category = Setup)
bool bDriven;
/** If True, torque is applied to this wheel */
UPROPERTY(EditAnywhere, Category = Setup)
bool bDriven;
FVehicleNWWheelDifferentialData()
: bDriven(true)
{ }
FVehicleNWWheelDifferentialData()
: bDriven(true)
{ }
};
USTRUCT()
struct FVehicleNWEngineData
{
GENERATED_USTRUCT_BODY()
GENERATED_USTRUCT_BODY()
/** Torque (Nm) at a given RPM*/
UPROPERTY(EditAnywhere, Category = Setup)
FRuntimeFloatCurve TorqueCurve;
/** Torque (Nm) at a given RPM*/
UPROPERTY(EditAnywhere, Category = Setup)
FRuntimeFloatCurve TorqueCurve;
/** Maximum revolutions per minute of the engine */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.01", UIMin = "0.01"))
float MaxRPM = 0.0F;
/** Maximum revolutions per minute of the engine */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.01", UIMin = "0.01"))
float MaxRPM = 0.0F;
/** Moment of inertia of the engine around the axis of rotation (Kgm^2). */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.01", UIMin = "0.01"))
float MOI = 0.0F;
/** Moment of inertia of the engine around the axis of rotation (Kgm^2). */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.01", UIMin = "0.01"))
float MOI = 0.0F;
/** Damping rate of engine when full throttle is applied (Kgm^2/s) */
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float DampingRateFullThrottle = 0.0F;
/** Damping rate of engine when full throttle is applied (Kgm^2/s) */
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float DampingRateFullThrottle = 0.0F;
/** Damping rate of engine in at zero throttle when the clutch is engaged (Kgm^2/s)*/
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float DampingRateZeroThrottleClutchEngaged = 0.0F;
/** Damping rate of engine in at zero throttle when the clutch is engaged (Kgm^2/s)*/
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float DampingRateZeroThrottleClutchEngaged = 0.0F;
/** Damping rate of engine in at zero throttle when the clutch is disengaged (in neutral gear) (Kgm^2/s)*/
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float DampingRateZeroThrottleClutchDisengaged = 0.0F;
/** Damping rate of engine in at zero throttle when the clutch is disengaged (in neutral gear) (Kgm^2/s)*/
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float DampingRateZeroThrottleClutchDisengaged = 0.0F;
/** Find the peak torque produced by the TorqueCurve */
float FindPeakTorque() const;
/** Find the peak torque produced by the TorqueCurve */
float FindPeakTorque() const;
};
USTRUCT()
struct FVehicleNWGearData
{
GENERATED_USTRUCT_BODY()
GENERATED_USTRUCT_BODY()
/** Determines the amount of torque multiplication*/
UPROPERTY(EditAnywhere, Category = Setup)
float Ratio = 0.0F;
/** Determines the amount of torque multiplication*/
UPROPERTY(EditAnywhere, Category = Setup)
float Ratio = 0.0F;
/** Value of engineRevs/maxEngineRevs that is low enough to gear down*/
UPROPERTY(EditAnywhere, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"), Category = Setup)
float DownRatio = 0.0F;
/** Value of engineRevs/maxEngineRevs that is low enough to gear down*/
UPROPERTY(EditAnywhere, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"), Category = Setup)
float DownRatio = 0.0F;
/** Value of engineRevs/maxEngineRevs that is high enough to gear up*/
UPROPERTY(EditAnywhere, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"), Category = Setup)
float UpRatio = 0.0F;
/** Value of engineRevs/maxEngineRevs that is high enough to gear up*/
UPROPERTY(EditAnywhere, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"), Category = Setup)
float UpRatio = 0.0F;
};
USTRUCT()
struct FVehicleNWTransmissionData
{
GENERATED_USTRUCT_BODY()
/** Whether to use automatic transmission */
UPROPERTY(EditAnywhere, Category = VehicleSetup, meta = (DisplayName = "Automatic Transmission"))
bool bUseGearAutoBox = false;
GENERATED_USTRUCT_BODY()
/** Whether to use automatic transmission */
UPROPERTY(EditAnywhere, Category = VehicleSetup, meta = (DisplayName = "Automatic Transmission"))
bool bUseAutomaticGears = false;
/** Time it takes to switch gears (seconds) */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.0", UIMin = "0.0"))
float GearSwitchTime = 0.0F;
/** Time it takes to switch gears (seconds) */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.0", UIMin = "0.0"))
float GearChangeTime = 0.0F;
/** Minimum time it takes the automatic transmission to initiate a gear change (seconds)*/
UPROPERTY(EditAnywhere, Category = Setup, meta = (editcondition = "bUseGearAutoBox", ClampMin = "0.0", UIMin = "0.0"))
float GearAutoBoxLatency = 0.0F;
/** Minimum time it takes the automatic transmission to initiate a gear change (seconds)*/
UPROPERTY(EditAnywhere, Category = Setup, meta = (editcondition = "bUseAutomaticGears", ClampMin = "0.0", UIMin = "0.0"))
float GearAutoBoxLatency = 0.0F;
/** The final gear ratio multiplies the transmission gear ratios.*/
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup)
float FinalRatio = 0.0F;
/** The final gear ratio multiplies the transmission gear ratios.*/
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup)
float FinalRatio = 0.0F;
/** Forward gear ratios (up to 30) */
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay)
TArray<FVehicleNWGearData> ForwardGears;
/** Forward gear ratios (up to 30) */
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay)
TArray<FVehicleNWGearData> ForwardGearRatios;
/** Reverse gear ratio */
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup)
float ReverseGearRatio = 0.0F;
/** Reverse gear ratio */
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup)
float ReverseGearRatio = 0.0F;
/** Value of engineRevs/maxEngineRevs that is high enough to increment gear*/
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"))
float NeutralGearUpRatio = 0.0F;
/** Value of engineRevs/maxEngineRevs that is high enough to increment gear*/
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup, meta = (ClampMin = "0.0", UIMin = "0.0", ClampMax = "1.0", UIMax = "1.0"))
float NeutralGearUpRatio = 0.0F;
/** Strength of clutch (Kgm^2/s)*/
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float ClutchStrength = 0.0F;
/** Strength of clutch (Kgm^2/s)*/
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay, meta = (ClampMin = "0.0", UIMin = "0.0"))
float ClutchStrength = 0.0F;
};
UCLASS(ClassGroup = (Physics), meta = (BlueprintSpawnableComponent), hidecategories = (PlanarMovement, "Components|Movement|Planar", Activation, "Components|Activation"))
class CARLA_API UWheeledVehicleMovementComponentNW :
public UChaosWheeledVehicleMovementComponent
public UChaosWheeledVehicleMovementComponent
{
GENERATED_UCLASS_BODY()
GENERATED_UCLASS_BODY()
/** Engine */
//UPROPERTY(EditAnywhere, Category = MechanicalSetup)
//FVehicleNWEngineData EngineSetupEXT;
/** Engine */
//UPROPERTY(EditAnywhere, Category = MechanicalSetup)
//FVehicleNWEngineData EngineSetupEXT;
/** Differential */
//UPROPERTY(EditAnywhere, Category = MechanicalSetup)
//TArray<FVehicleNWWheelDifferentialData> DifferentialSetupEXT;
/** Differential */
//UPROPERTY(EditAnywhere, Category = MechanicalSetup)
//TArray<FVehicleNWWheelDifferentialData> DifferentialSetupEXT;
/** Transmission data */
//UPROPERTY(EditAnywhere, Category = MechanicalSetup)
//FVehicleNWTransmissionData TransmissionSetupEXT;
/** Transmission data */
//UPROPERTY(EditAnywhere, Category = MechanicalSetup)
//FVehicleNWTransmissionData TransmissionSetupEXT;
/** Maximum steering versus forward speed (km/h) */
//UPROPERTY(EditAnywhere, Category = SteeringSetup)
//FRuntimeFloatCurve SteeringCurve;
/** Maximum steering versus forward speed (km/h) */
//UPROPERTY(EditAnywhere, Category = SteeringSetup)
//FRuntimeFloatCurve SteeringCurve;
#if WITH_EDITOR
virtual void PostEditChangeProperty(struct FPropertyChangedEvent& PropertyChangedEvent) override;
virtual void PostEditChangeProperty(struct FPropertyChangedEvent& PropertyChangedEvent) override;
#endif
protected:

View File

@ -1,33 +1,41 @@
message("${CARLA_SOURCE_DIR} ${CARLA_TARGET_PACKAGE_PATH} ${CARLA_BINARY_DIR}")
file(COPY_FILE ${CARLA_SOURCE_DIR}/LICENSE ${CARLA_TARGET_PACKAGE_PATH}/LICENSE)
file(COPY_FILE ${CARLA_SOURCE_DIR}/CHANGELOG.md ${CARLA_TARGET_PACKAGE_PATH}/CHANGELOG)
file(COPY_FILE ${CARLA_SOURCE_DIR}/Docs/release_readme.md ${CARLA_TARGET_PACKAGE_PATH}/README)
make_directory(${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/dist)
file(GLOB PYTHON_WHL_FILES ${CARLA_BINARY_DIR}/PythonAPI/dist/carla-*.whl)
file(COPY ${PYTHON_WHL_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/dist/)
file(COPY_FILE ${CARLA_SOURCE_DIR}/Docs/python_api.md ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/python_api.md)
file(COPY ${CARLA_SOURCE_DIR}/PythonAPI/carla/agents/ DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/agents/)
file(COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/carla/scene_layout.py ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/scene_layout.py)
file(COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/carla/requirements.txt ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/requirements.txt)
file (COPY_FILE ${CARLA_SOURCE_DIR}/LICENSE ${CARLA_TARGET_PACKAGE_PATH}/LICENSE)
file (COPY_FILE ${CARLA_SOURCE_DIR}/CHANGELOG.md ${CARLA_TARGET_PACKAGE_PATH}/CHANGELOG)
file (COPY_FILE ${CARLA_SOURCE_DIR}/Docs/release_readme.md ${CARLA_TARGET_PACKAGE_PATH}/README)
if (WIN32)
set (EXE_EXT .exe)
else ()
set (EXE_EXT)
endif ()
make_directory (${CARLA_TARGET_PACKAGE_PATH}/Tools)
# @TODO Temporary hack:
file (COPY_FILE ${CARLA_BINARY_DIR}/_deps/recastnavigation-build/RecastBuilder/RecastBuilder${EXE_EXT} ${CARLA_TARGET_PACKAGE_PATH}/Tools/RecastBuilder${EXE_EXT})
make_directory(${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/)
file(GLOB PYTHON_EXAMPLE_FILES ${CARLA_SOURCE_DIR}/PythonAPI/examples/*.py)
file(COPY ${PYTHON_EXAMPLE_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/)
make_directory(${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/rss/)
file(GLOB PYTHON_EXAMPLE_RSS_FILES ${CARLA_SOURCE_DIR}/PythonAPI/examples/rss/*.py)
file(COPY ${PYTHON_EXAMPLE_RSS_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/rss/)
file(COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/examples/requirements.txt ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/requirements.txt)
make_directory (${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/dist)
file (GLOB PYTHON_WHL_FILES ${CARLA_BINARY_DIR}/PythonAPI/dist/carla-*.whl)
file (COPY ${PYTHON_WHL_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/dist/)
file (COPY_FILE ${CARLA_SOURCE_DIR}/Docs/python_api.md ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/python_api.md)
file (COPY ${CARLA_SOURCE_DIR}/PythonAPI/carla/agents/ DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/agents/)
file (COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/carla/scene_layout.py ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/scene_layout.py)
file (COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/carla/requirements.txt ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/carla/requirements.txt)
make_directory(${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/)
file(GLOB PYTHON_UTIL_FILES ${CARLA_SOURCE_DIR}/PythonAPI/util/*.py)
file(COPY ${PYTHON_UTIL_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/)
file(COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/util/requirements.txt ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/requirements.txt)
file(COPY ${CARLA_SOURCE_DIR}/PythonAPI/util/opendrive/ DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/opendrive/)
make_directory (${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/)
file (GLOB PYTHON_EXAMPLE_FILES ${CARLA_SOURCE_DIR}/PythonAPI/examples/*.py)
file (COPY ${PYTHON_EXAMPLE_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/)
make_directory (${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/rss/)
file (GLOB PYTHON_EXAMPLE_RSS_FILES ${CARLA_SOURCE_DIR}/PythonAPI/examples/rss/*.py)
file (COPY ${PYTHON_EXAMPLE_RSS_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/rss/)
file (COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/examples/requirements.txt ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/examples/requirements.txt)
file(COPY ${CARLA_SOURCE_DIR}/Co-Simulation/ DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/Co-Simulation/)
make_directory (${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/)
file (GLOB PYTHON_UTIL_FILES ${CARLA_SOURCE_DIR}/PythonAPI/util/*.py)
file (COPY ${PYTHON_UTIL_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/)
file (COPY_FILE ${CARLA_SOURCE_DIR}/PythonAPI/util/requirements.txt ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/requirements.txt)
file (COPY ${CARLA_SOURCE_DIR}/PythonAPI/util/opendrive/ DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/PythonAPI/util/opendrive/)
make_directory(${CARLA_TARGET_PACKAGE_PATH}/HDMaps/)
file(GLOB PYTHON_HDMAP_FILES ${CARLA_SOURCE_DIR}/Unreal/CarlaUnreal/Content/Carla/HDMaps/*.pcd)
file(COPY ${PYTHON_HDMAP_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/HDMaps/)
file(COPY_FILE ${CARLA_SOURCE_DIR}/Unreal/CarlaUnreal/Content/Carla/HDMaps/Readme.md ${CARLA_TARGET_PACKAGE_PATH}/HDMaps/README)
file (COPY ${CARLA_SOURCE_DIR}/Co-Simulation/ DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/Co-Simulation/)
make_directory (${CARLA_TARGET_PACKAGE_PATH}/HDMaps/)
file (GLOB PYTHON_HDMAP_FILES ${CARLA_SOURCE_DIR}/Unreal/CarlaUnreal/Content/Carla/HDMaps/*.pcd)
file (COPY ${PYTHON_HDMAP_FILES} DESTINATION ${CARLA_TARGET_PACKAGE_PATH}/HDMaps/)
file (COPY_FILE ${CARLA_SOURCE_DIR}/Unreal/CarlaUnreal/Content/Carla/HDMaps/Readme.md ${CARLA_TARGET_PACKAGE_PATH}/HDMaps/README)