Update VehiclePhysicsControl fields for UE5-Chaos (#8141)

* Add VehiclePhysicsControl progress...

* Update parameter names.

* Minor fixes.

* Update python initializer.

* More VehiclePhysicsControl changes.

* Fix minor UE errors.

* Update Vehicle and WheelPhysicsControl.

* Various fixes.

* Add missing linebreak.

* Fix indentation.

* Make FVehiclePhysicsControl UPROPERTYs uniform.

* Fix indentation again...

* Fix indentation, yet again...
This commit is contained in:
MarcelPiNacy-CVC 2024-09-17 17:55:19 +02:00 committed by GitHub
parent 0db777202c
commit e326742a67
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
19 changed files with 1943 additions and 1529 deletions

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -6,101 +6,255 @@
#pragma once #pragma once
#include "carla/geom/Vector2D.h"
#include "carla/geom/Vector3D.h" #include "carla/geom/Vector3D.h"
#include "carla/geom/Location.h"
#include "carla/MsgPack.h" #include "carla/MsgPack.h"
namespace carla { namespace carla {
namespace rpc { namespace rpc {
class WheelPhysicsControl { struct WheelPhysicsControl {
public:
WheelPhysicsControl() = default; uint8_t axle_type = 0; // @TODO INTRODUCE ENUM
geom::Vector3D offset = geom::Vector3D(0, 0, 0);
WheelPhysicsControl( float wheel_radius = 30.0f;
float in_tire_friction, float wheel_width = 30.0f;
float in_max_steer_angle, float wheel_mass = 30.0f;
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) {}
float tire_friction = 3.0f;
float max_steer_angle = 70.0f;
float radius = 30.0f;
float cornering_stiffness = 1000.0f; float cornering_stiffness = 1000.0f;
bool abs = false; float friction_force_multiplier = 3.0f;
bool traction_control = false; 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_brake_torque = 1500.0f;
float max_handbrake_torque = 3000.0f; float max_hand_brake_torque = 3000.0f;
geom::Vector3D position = {0.0f, 0.0f, 0.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);
bool operator!=(const WheelPhysicsControl &rhs) const { inline bool operator==(const WheelPhysicsControl& rhs) const {
return const bool cmp[] =
tire_friction != rhs.tire_friction || {
max_steer_angle != rhs.max_steer_angle || axle_type == rhs.axle_type,
radius != rhs.radius || offset == rhs.offset,
cornering_stiffness != rhs.cornering_stiffness || wheel_radius == rhs.wheel_radius,
abs != rhs.abs || wheel_width == rhs.wheel_width,
traction_control != rhs.traction_control || wheel_mass == rhs.wheel_mass,
max_brake_torque != rhs.max_brake_torque || cornering_stiffness == rhs.cornering_stiffness,
max_handbrake_torque != rhs.max_handbrake_torque || friction_force_multiplier == rhs.friction_force_multiplier,
position != rhs.position; 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());
} }
bool operator==(const WheelPhysicsControl &rhs) const { inline bool operator!=(const WheelPhysicsControl& rhs) const {
return !(*this != rhs); return !(*this == rhs);
} }
#ifdef LIBCARLA_INCLUDED_FROM_UE4 #ifdef LIBCARLA_INCLUDED_FROM_UE4
WheelPhysicsControl(const FWheelPhysicsControl &Wheel) static WheelPhysicsControl FromFWheelPhysicsControl(
: tire_friction(Wheel.FrictionForceMultiplier), const FWheelPhysicsControl& Wheel)
max_steer_angle(Wheel.MaxSteerAngle), {
radius(Wheel.Radius), WheelPhysicsControl Out = { };
cornering_stiffness(Wheel.CorneringStiffness), Out.axle_type = (uint8_t)Wheel.AxleType;
abs(Wheel.bABSEnabled), Out.offset = geom::Vector3D(
traction_control(Wheel.bTractionControlEnabled), Wheel.Offset.X,
max_brake_torque(Wheel.MaxBrakeTorque), Wheel.Offset.Y,
max_handbrake_torque(Wheel.MaxHandBrakeTorque), Wheel.Offset.Z);
position(Wheel.Position.X, Wheel.Position.Y, Wheel.Position.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 { operator FWheelPhysicsControl() const {
FWheelPhysicsControl Wheel; FWheelPhysicsControl Wheel;
Wheel.FrictionForceMultiplier = tire_friction; Wheel.AxleType = (EAxleType)axle_type;
Wheel.MaxSteerAngle = max_steer_angle; Wheel.Offset = FVector(offset.x, offset.y, offset.z);
Wheel.Radius = radius; Wheel.WheelRadius = wheel_radius;
Wheel.WheelWidth = wheel_width;
Wheel.WheelMass = wheel_mass;
Wheel.CorneringStiffness = cornering_stiffness; Wheel.CorneringStiffness = cornering_stiffness;
Wheel.bABSEnabled = abs; Wheel.FrictionForceMultiplier = friction_force_multiplier;
Wheel.bTractionControlEnabled = traction_control; 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.MaxBrakeTorque = max_brake_torque;
Wheel.MaxHandBrakeTorque = max_handbrake_torque; Wheel.MaxHandBrakeTorque = max_hand_brake_torque;
Wheel.Position = {position.x, position.y, position.z}; Wheel.WheelIndex = wheel_index;
Wheel.Location = location;
Wheel.OldLocation = old_location;
Wheel.Velocity = velocity;
return Wheel; return Wheel;
} }
#endif #endif
MSGPACK_DEFINE_ARRAY(tire_friction, MSGPACK_DEFINE_ARRAY(
max_steer_angle, axle_type,
radius, offset,
wheel_radius,
wheel_width,
wheel_mass,
cornering_stiffness, cornering_stiffness,
abs, friction_force_multiplier,
traction_control, 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_brake_torque,
max_handbrake_torque, max_hand_brake_torque,
position) wheel_index,
location,
old_location,
velocity)
}; };
} }
} }

View File

@ -480,26 +480,36 @@ namespace rpc {
inline std::ostream &operator<<(std::ostream &out, const VehiclePhysicsControl &control) { inline std::ostream &operator<<(std::ostream &out, const VehiclePhysicsControl &control) {
out << "VehiclePhysicsControl(torque_curve=" << control.torque_curve out << "VehiclePhysicsControl(torque_curve=" << control.torque_curve
<< ", max_torque=" << std::to_string(control.max_torque) << ", max_torque=" << control.max_torque
<< ", max_rpm=" << std::to_string(control.max_rpm) << ", max_rpm=" << control.max_rpm
<< ", moi=" << std::to_string(control.moi) << ", idle_rpm=" << control.idle_rpm
<< ", rev_down_rate=" << std::to_string(control.rev_down_rate) << ", brake_effect=" << control.brake_effect
<< ", differential_type=" << std::to_string(control.differential_type) << ", rev_up_moi=" << control.rev_up_moi
<< ", front_rear_split=" << std::to_string(control.front_rear_split) << ", rev_down_rate=" << control.rev_down_rate
<< ", use_gear_autobox=" << boolalpha(control.use_gear_autobox) << ", differential_type=" << control.differential_type
<< ", gear_switch_time=" << std::to_string(control.gear_switch_time) << ", front_rear_split=" << control.front_rear_split
<< ", final_ratio=" << std::to_string(control.final_ratio) << ", use_automatic_gears=" << control.use_automatic_gears
<< ", forward_gears=" << control.forward_gears << ", gear_change_time=" << control.gear_change_time
<< ", reverse_gears=" << control.reverse_gears << ", final_ratio=" << control.final_ratio
<< ", change_up_rpm=" << std::to_string(control.change_up_rpm) << ", forward_gear_ratios=" << control.forward_gear_ratios
<< ", change_down_rpm=" << std::to_string(control.change_down_rpm) << ", reverse_gear_ratios=" << control.reverse_gear_ratios
<< ", transmission_efficiency=" << std::to_string(control.transmission_efficiency) << ", change_up_rpm=" << control.change_up_rpm
<< ", mass=" << std::to_string(control.mass) << ", change_down_rpm=" << control.change_down_rpm
<< ", drag_coefficient=" << std::to_string(control.drag_coefficient) << ", transmission_efficiency=" << control.transmission_efficiency
<< ", mass=" << control.mass
<< ", drag_coefficient=" << control.drag_coefficient
<< ", center_of_mass=" << control.center_of_mass << ", center_of_mass=" << control.center_of_mass
<< ", steering_curve=" << control.steering_curve << ", 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 << ", wheels=" << control.wheels
<< ", use_sweep_wheel_collision=" << control.use_sweep_wheel_collision << ')'; << ", use_sweep_wheel_collision=" << control.use_sweep_wheel_collision
<< ")";
return out; return out;
} }

View File

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

View File

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

View File

@ -21,6 +21,29 @@
#include <Carla/Vehicle/CarlaWheeledVehicle.h> #include <Carla/Vehicle/CarlaWheeledVehicle.h>
template <typename V>
requires (
std::remove_reference_t<V>::Dim <= 3)
static std::string FormatVectorLike(V&& v)
{
constexpr auto Dim = std::remove_reference_t<V>::Dim;
if constexpr (Dim == 1)
{
const auto& [x] = v;
return std::format("({})", x);
}
else if constexpr (Dim == 2)
{
const auto& [x, y] = v;
return std::format("({}, {})", x, y);
}
else if constexpr (Dim == 3)
{
const auto& [x, y, z] = v;
return std::format("({}, {}, {})", x, y, z);
}
}
inline bool CarlaRecorderQuery::ReadHeader(void) inline bool CarlaRecorderQuery::ReadHeader(void)
{ {
if (File.eof()) if (File.eof())
@ -39,7 +62,7 @@ inline void CarlaRecorderQuery::SkipPacket(void)
File.seekg(Header.Size, std::ios::cur); File.seekg(Header.Size, std::ios::cur);
} }
inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream &Info) inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream& Info)
{ {
// read Info // read Info
RecInfo.Read(File); RecInfo.Read(File);
@ -54,7 +77,7 @@ inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream &Info)
// show general Info // show general Info
Info << "Version: " << RecInfo.Version << std::endl; Info << "Version: " << RecInfo.Version << std::endl;
Info << "Map: " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl; Info << "Map: " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl;
tm *TimeInfo = localtime(&RecInfo.Date); tm* TimeInfo = localtime(&RecInfo.Date);
char DateStr[100]; char DateStr[100];
strftime(DateStr, sizeof(DateStr), "%x %X", TimeInfo); strftime(DateStr, sizeof(DateStr), "%x %X", TimeInfo);
Info << "Date: " << DateStr << std::endl << std::endl; Info << "Date: " << DateStr << std::endl << std::endl;
@ -81,7 +104,7 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
bool bFramePrinted = false; bool bFramePrinted = false;
// lambda for repeating task // lambda for repeating task
auto PrintFrame = [this](std::stringstream &Info) auto PrintFrame = [this](std::stringstream& Info)
{ {
Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n"; Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n";
}; };
@ -129,7 +152,7 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
" (" << " (" <<
static_cast<int>(EventAdd.Type) << ") at (" << EventAdd.Location.X << ", " << static_cast<int>(EventAdd.Type) << ") at (" << EventAdd.Location.X << ", " <<
EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl; EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl;
for (auto &Att : EventAdd.Description.Attributes) for (auto& Att : EventAdd.Description.Attributes)
{ {
Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl; Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl;
} }
@ -506,69 +529,100 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
bFramePrinted = true; bFramePrinted = true;
} }
Info << " Physics Control events: " << Total << std::endl; Info << " Physics Control events: " << Total << '\n';
for (i = 0; i < Total; ++i) for (i = 0; i < Total; ++i)
{ {
PhysicsControl.Read(File); PhysicsControl.Read(File);
carla::rpc::VehiclePhysicsControl Control(PhysicsControl.VehiclePhysicsControl); auto Control = carla::rpc::VehiclePhysicsControl::FromFVehiclePhysicsControl(
Info << " Id: " << PhysicsControl.DatabaseId << std::endl PhysicsControl.VehiclePhysicsControl);
<< " max_torque = " << Control.max_torque << std::endl Info << " Id: " << PhysicsControl.DatabaseId << '\n'
<< " max_rpm = " << Control.max_rpm << std::endl << " max_torque = " << Control.max_torque << '\n'
<< " MOI = " << Control.moi << std::endl << " max_rpm = " << Control.max_rpm << '\n'
<< " rev_down_rate = " << Control.rev_down_rate << std::endl << " MOI = " << Control.rev_up_moi << '\n'
<< " differential_type = " << Control.differential_type << std::endl << " rev_down_rate = " << Control.rev_down_rate << '\n'
<< " front_rear_split = " << Control.front_rear_split << std::endl << " differential_type = " << Control.differential_type << '\n'
<< " use_gear_auto_box = " << (Control.use_gear_autobox ? "true" : "false") << std::endl << " front_rear_split = " << Control.front_rear_split << '\n'
<< " gear_switch_time = " << Control.gear_switch_time << std::endl << " use_gear_auto_box = " << (Control.use_automatic_gears ? "true" : "false") << '\n'
<< " final_ratio = " << Control.final_ratio << std::endl << " gear_change_time = " << Control.gear_change_time << '\n'
<< " change_up_rpm = " << Control.change_up_rpm << std::endl << " final_ratio = " << Control.final_ratio << '\n'
<< " change_down_rpm = " << Control.change_down_rpm << std::endl << " change_up_rpm = " << Control.change_up_rpm << '\n'
<< " transmission_efficiency = " << Control.transmission_efficiency << std::endl << " change_down_rpm = " << Control.change_down_rpm << '\n'
<< " mass = " << Control.mass << std::endl << " transmission_efficiency = " << Control.transmission_efficiency << '\n'
<< " drag_coefficient = " << Control.drag_coefficient << std::endl << " mass = " << Control.mass << '\n'
<< " center_of_mass = " << "(" << Control.center_of_mass.x << ", " << Control.center_of_mass.y << ", " << Control.center_of_mass.z << ")" << std::endl; << " drag_coefficient = " << Control.drag_coefficient << '\n'
<< " center_of_mass = " << "(" << Control.center_of_mass.x << ", " << Control.center_of_mass.y << ", " << Control.center_of_mass.z << ")" << '\n';
Info << " torque_curve ="; Info << " torque_curve =";
for (auto& vec : Control.torque_curve) for (auto& vec : Control.torque_curve)
{ {
Info << " (" << vec.x << ", " << vec.y << ")"; Info << " (" << vec.x << ", " << vec.y << ")";
} }
Info << std::endl; Info << '\n';
Info << " steering_curve ="; Info << " steering_curve =";
for (auto& vec : Control.steering_curve) for (auto& vec : Control.steering_curve)
{ {
Info << " (" << vec.x << ", " << vec.y << ")"; Info << " (" << vec.x << ", " << vec.y << ")";
} }
Info << std::endl; Info << '\n';
Info << " forward_gears:" << std::endl; Info << " forward_gear_ratios:" << '\n';
uint32_t count = 0; uint32_t count = 0;
for (auto& Gear : Control.forward_gears) for (auto& Gear : Control.forward_gear_ratios)
{ {
Info << " gear " << count << ": ratio " << Gear << std::endl; Info << " gear " << count << ": ratio " << Gear << '\n';
++count; ++count;
} }
Info << " reverse_gears:" << std::endl; Info << " reverse_gear_ratios:" << '\n';
count = 0; count = 0;
for (auto& Gear : Control.reverse_gears) for (auto& Gear : Control.reverse_gear_ratios)
{ {
Info << " gear " << count << ": ratio " << Gear << std::endl; Info << " gear " << count << ": ratio " << Gear << '\n';
++count; ++count;
} }
Info << " wheels:" << std::endl; Info << " wheels:";
count = 0; Index = 0;
for (auto& Wheel : Control.wheels) for (auto& Wheel : Control.wheels)
{ {
Info << " wheel " << count << ": tire_friction " << Wheel.tire_friction Info << "\nwheel #" << Index << ":\n"
<< " max_steer_angle " << Wheel.max_steer_angle " axle_type: " << axle_type <<
<< " radius " << Wheel.radius " offset: " << FormatVectorLike(offset) <<
<< " cornering_stiffness " << Wheel.cornering_stiffness " wheel_radius: " << wheel_radius <<
<< " abs " << Wheel.abs " wheel_width: " << wheel_width <<
<< " traction_control " << Wheel.traction_control " wheel_mass: " << wheel_mass <<
<< " max_brake_torque " << Wheel.max_brake_torque " cornering_stiffness: " << cornering_stiffness <<
<< " max_handbrake_torque " << Wheel.max_handbrake_torque " friction_force_multiplier: " << friction_force_multiplier <<
<< " position " << "(" << Wheel.position.x << ", " << Wheel.position.y << ", " << Wheel.position.z << ")" " side_slip_modifier: " << side_slip_modifier <<
<< std::endl; " slip_threshold: " << slip_threshold <<
++count; " skid_threshold: " << skid_threshold <<
" max_steer_angle: " << max_steer_angle <<
" affected_by_steering: " << affected_by_steering <<
" affected_by_brake: " << affected_by_brake <<
" affected_by_handbrake: " << affected_by_handbrake <<
" affected_by_engine: " << affected_by_engine <<
" abs_enabled: " << abs_enabled <<
" traction_control_enabled: " << traction_control_enabled <<
" max_wheelspin_rotation: " << max_wheelspin_rotation <<
" external_torque_combine_method: " << external_torque_combine_method <<
" lateral_slip_graph: " << lateral_slip_graph <<
" suspension_axis: " << FormatVectorLike(suspension_axis) <<
" suspension_force_offset: " << FormatVectorLike(suspension_force_offset) <<
" suspension_max_raise: " << suspension_max_raise <<
" suspension_max_drop: " << suspension_max_drop <<
" suspension_damping_ratio: " << suspension_damping_ratio <<
" wheel_load_ratio: " << wheel_load_ratio <<
" spring_rate: " << spring_rate <<
" spring_preload: " << spring_preload <<
" suspension_smoothing: " << suspension_smoothing <<
" rollbar_scaling: " << rollbar_scaling <<
" sweep_shape: " << sweep_shape <<
" sweep_type: " << sweep_type <<
" max_brake_torque: " << max_brake_torque <<
" max_hand_brake_torque: " << max_hand_brake_torque <<
" wheel_index: " << wheel_index <<
" location: " << FormatVectorLike(location) <<
" old_location: " << FormatVectorLike(old_location) <<
" velocity: " << FormatVectorLike(velocity);
++Index;
} }
Info << std::endl;
} }
} }
else else
@ -616,7 +670,7 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
WalkerBones.Clear(); WalkerBones.Clear();
WalkerBones.Read(File); WalkerBones.Read(File);
Info << " Id: " << WalkerBones.DatabaseId << "\n"; Info << " Id: " << WalkerBones.DatabaseId << "\n";
for (const auto &Bone : WalkerBones.Bones) for (const auto& Bone : WalkerBones.Bones)
{ {
Info << " Bone: \"" << TCHAR_TO_UTF8(*Bone.Name) << "\" relative: " << "Loc(" Info << " Bone: \"" << TCHAR_TO_UTF8(*Bone.Name) << "\" relative: " << "Loc("
<< Bone.Location.X << ", " << Bone.Location.Y << ", " << Bone.Location.Z << ") Rot(" << Bone.Location.X << ", " << Bone.Location.Y << ", " << Bone.Location.Z << ") Rot("
@ -724,7 +778,7 @@ std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Categ
{ {
// add // add
EventAdd.Read(File); EventAdd.Read(File);
Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id }; Actors[EventAdd.DatabaseId] = ReplayerActorInfo{ EventAdd.Type, EventAdd.Description.Id };
} }
break; break;
@ -892,7 +946,7 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
{ {
// add // add
EventAdd.Read(File); EventAdd.Read(File);
Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id, FVector(0, 0, 0), 0.0, 0.0 }; Actors[EventAdd.DatabaseId] = ReplayerActorInfo{ EventAdd.Type, EventAdd.Description.Id, FVector(0, 0, 0), 0.0, 0.0 };
} }
break; break;
@ -920,7 +974,7 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
case static_cast<char>(CarlaRecorderPacketId::Position): case static_cast<char>(CarlaRecorderPacketId::Position):
// read all positions // read all positions
ReadValue<uint16_t>(File, Total); ReadValue<uint16_t>(File, Total);
for (i=0; i<Total; ++i) for (i = 0; i < Total; ++i)
{ {
Position.Read(File); Position.Read(File);
// check if actor moved less than a distance // check if actor moved less than a distance
@ -968,7 +1022,7 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
} }
// show actors stopped that were not moving again // show actors stopped that were not moving again
for (auto &Actor : Actors) for (auto& Actor : Actors)
{ {
// check to show info // check to show info
if (Actor.second.Duration >= MinTime) if (Actor.second.Duration >= MinTime)
@ -984,7 +1038,7 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
} }
// show the result // show the result
for (auto &Result : Results) for (auto& Result : Results)
{ {
Info << Result.second; Info << Result.second;
} }

View File

@ -27,7 +27,7 @@ FActorDefinition ACollisionSensor::GetSensorDefinition()
TEXT("collision")); TEXT("collision"));
} }
void ACollisionSensor::SetOwner(AActor *NewOwner) void ACollisionSensor::SetOwner(AActor* NewOwner)
{ {
Super::SetOwner(NewOwner); Super::SetOwner(NewOwner);
@ -40,10 +40,10 @@ void ACollisionSensor::SetOwner(AActor *NewOwner)
} }
void ACollisionSensor::OnCollisionEvent( void ACollisionSensor::OnCollisionEvent(
AActor *Actor, AActor* Actor,
AActor *OtherActor, AActor* OtherActor,
FVector NormalImpulse, FVector NormalImpulse,
const FHitResult &Hit) const FHitResult& Hit)
{ {
if (Actor == nullptr || OtherActor == nullptr) if (Actor == nullptr || OtherActor == nullptr)
{ {
@ -64,7 +64,7 @@ void ACollisionSensor::OnCollisionEvent(
CollisionRegistry.end()); CollisionRegistry.end());
// check if this collision has been procesed already in this frame // 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 && if (std::get<0>(Collision) == CurrentFrame &&
std::get<1>(Collision) == Actor && std::get<1>(Collision) == Actor &&
@ -86,29 +86,43 @@ void ACollisionSensor::OnCollisionEvent(
(float)NormalImpulse.Y, (float)NormalImpulse.Y,
(float)NormalImpulse.Z)); (float)NormalImpulse.Z));
// record the collision event // record the collision event
if (CurrentEpisode.GetRecorder()->IsEnabled()){ if (CurrentEpisode.GetRecorder()->IsEnabled()) {
CurrentEpisode.GetRecorder()->AddCollision(Actor, OtherActor); CurrentEpisode.GetRecorder()->AddCollision(Actor, OtherActor);
} }
CollisionRegistry.emplace_back(CurrentFrame, Actor, OtherActor); CollisionRegistry.emplace_back(CurrentFrame, Actor, OtherActor);
// ROS2 // ROS2
#if defined(WITH_ROS2) #if defined(WITH_ROS2)
auto ROS2 = carla::ros2::ROS2::GetInstance(); auto ROS2 = carla::ros2::ROS2::GetInstance();
if (ROS2->IsEnabled()) if (ROS2->IsEnabled())
{ {
TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send"); TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send");
auto StreamId = carla::streaming::detail::token_type(GetToken()).get_stream_id(); 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(); AActor* ParentActor = GetAttachParentActor();
if (ParentActor) if (ParentActor)
{ {
FTransform LocalTransformRelativeToParent = GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform()); 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 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

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

View File

@ -74,7 +74,7 @@ void ACarlaWheeledVehicle::BeginPlay()
{ {
UPrimitiveComponent* DoorComponent = Cast<UPrimitiveComponent>( UPrimitiveComponent* DoorComponent = Cast<UPrimitiveComponent>(
GetDefaultSubobjectByName(ConstraintComponent->ComponentName1.ComponentName)); GetDefaultSubobjectByName(ConstraintComponent->ComponentName1.ComponentName));
if(DoorComponent) if (DoorComponent)
{ {
UE_LOG(LogCarla, Log, TEXT("Door name: %s"), *(DoorComponent->GetName())); UE_LOG(LogCarla, Log, TEXT("Door name: %s"), *(DoorComponent->GetName()));
FTransform ComponentWorldTransform = DoorComponent->GetComponentTransform(); FTransform ComponentWorldTransform = DoorComponent->GetComponentTransform();
@ -132,11 +132,11 @@ void ACarlaWheeledVehicle::BeginPlay()
// Check if it overlaps with a Friction trigger, if so, update the friction // Check if it overlaps with a Friction trigger, if so, update the friction
// scale. // scale.
TArray<AActor *> OverlapActors; TArray<AActor*> OverlapActors;
GetOverlappingActors(OverlapActors, AFrictionTrigger::StaticClass()); 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) if (FrictionTrigger)
{ {
FrictionScale = FrictionTrigger->Friction; FrictionScale = FrictionTrigger->Friction;
@ -147,7 +147,7 @@ void ACarlaWheeledVehicle::BeginPlay()
TArray<FChaosWheelSetup> NewWheelSetups = MovementComponent->WheelSetups; TArray<FChaosWheelSetup> NewWheelSetups = MovementComponent->WheelSetups;
for (const FChaosWheelSetup& WheelSetup : NewWheelSetups) for (const FChaosWheelSetup& WheelSetup : NewWheelSetups)
{ {
UChaosVehicleWheel *Wheel = WheelSetup.WheelClass.GetDefaultObject(); UChaosVehicleWheel* Wheel = WheelSetup.WheelClass.GetDefaultObject();
check(Wheel != nullptr); check(Wheel != nullptr);
} }
@ -171,9 +171,9 @@ bool ACarlaWheeledVehicle::IsInVehicleRange(const FVector& Location) const
void ACarlaWheeledVehicle::UpdateDetectionBox() void ACarlaWheeledVehicle::UpdateDetectionBox()
{ {
const FTransform GlobalTransform = GetActorTransform(); const FTransform GlobalTransform = GetActorTransform();
const FVector Vec { DetectionSize, DetectionSize, DetectionSize }; const FVector Vec{ DetectionSize, DetectionSize, DetectionSize };
FBox Box = FBox(-Vec, Vec); 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); FoliageBoundingBox = Box.TransformBy(NonScaledTransform);
} }
@ -333,7 +333,7 @@ TArray<float> ACarlaWheeledVehicle::GetWheelsFrictionScale()
{ {
check(Movement != nullptr); check(Movement != nullptr);
for (auto &Wheel : Movement->Wheels) for (auto& Wheel : Movement->Wheels)
{ {
WheelsFrictionScale.Add(Wheel->FrictionForceMultiplier); WheelsFrictionScale.Add(Wheel->FrictionForceMultiplier);
} }
@ -342,7 +342,7 @@ TArray<float> ACarlaWheeledVehicle::GetWheelsFrictionScale()
return WheelsFrictionScale; return WheelsFrictionScale;
} }
void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float> &WheelsFrictionScale) void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float>& WheelsFrictionScale)
{ {
UChaosWheeledVehicleMovementComponent* Movement = GetChaosWheeledVehicleMovementComponent(); UChaosWheeledVehicleMovementComponent* Movement = GetChaosWheeledVehicleMovementComponent();
if (Movement) if (Movement)
@ -359,72 +359,99 @@ void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float> &WheelsFrictionS
FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const
{ {
FVehiclePhysicsControl PhysicsControl; FVehiclePhysicsControl PhysicsControl = { };
UChaosWheeledVehicleMovementComponent* VehicleMovComponent = GetChaosWheeledVehicleMovementComponent(); auto VehicleMovComponentPtr = GetChaosWheeledVehicleMovementComponent();
check(VehicleMovComponent != nullptr); check(VehicleMovComponentPtr != nullptr);
auto& VehicleMovComponent = *VehicleMovComponentPtr;
// Engine Setup auto& EngineSetup = VehicleMovComponent.EngineSetup;
PhysicsControl.TorqueCurve = VehicleMovComponent->EngineSetup.TorqueCurve.EditorCurveData; auto RCurve = EngineSetup.TorqueCurve.GetRichCurve();
PhysicsControl.MaxTorque = VehicleMovComponent->EngineSetup.MaxTorque; check(RCurve != nullptr);
PhysicsControl.MaxRPM = VehicleMovComponent->EngineSetup.MaxRPM; PhysicsControl.TorqueCurve = *RCurve;
PhysicsControl.MOI = VehicleMovComponent->EngineSetup.EngineRevUpMOI; PhysicsControl.MaxTorque = EngineSetup.MaxTorque;
PhysicsControl.RevDownRate = VehicleMovComponent->EngineSetup.EngineRevDownRate; PhysicsControl.MaxRPM = EngineSetup.MaxRPM;
PhysicsControl.IdleRPM = EngineSetup.EngineIdleRPM;
// Differential Setup PhysicsControl.BrakeEffect = EngineSetup.EngineBrakeEffect;
PhysicsControl.DifferentialType = static_cast<uint8>(VehicleMovComponent->DifferentialSetup.DifferentialType); PhysicsControl.RevUpMOI = EngineSetup.EngineRevUpMOI;
PhysicsControl.FrontRearSplit = VehicleMovComponent->DifferentialSetup.FrontRearSplit; PhysicsControl.RevDownRate = EngineSetup.EngineRevDownRate;
auto& DifferentialSetup = VehicleMovComponent.DifferentialSetup;
// Transmission Setup PhysicsControl.DifferentialType = (uint8_t)DifferentialSetup.DifferentialType;
PhysicsControl.bUseGearAutoBox = VehicleMovComponent->TransmissionSetup.bUseAutomaticGears; PhysicsControl.FrontRearSplit = DifferentialSetup.FrontRearSplit;
PhysicsControl.FinalRatio = VehicleMovComponent->TransmissionSetup.FinalRatio; auto& TransmissionSetup = VehicleMovComponent.TransmissionSetup;
PhysicsControl.ForwardGears = VehicleMovComponent->TransmissionSetup.ForwardGearRatios; PhysicsControl.bUseAutomaticGears = TransmissionSetup.bUseAutomaticGears;
PhysicsControl.ReverseGears = VehicleMovComponent->TransmissionSetup.ReverseGearRatios; PhysicsControl.GearChangeTime = TransmissionSetup.GearChangeTime;
PhysicsControl.ChangeUpRPM = VehicleMovComponent->TransmissionSetup.ChangeUpRPM; PhysicsControl.FinalRatio = TransmissionSetup.FinalRatio;
PhysicsControl.ChangeDownRPM = VehicleMovComponent->TransmissionSetup.ChangeDownRPM; PhysicsControl.ForwardGearRatios = TransmissionSetup.ForwardGearRatios;
PhysicsControl.GearSwitchTime = VehicleMovComponent->TransmissionSetup.GearChangeTime; PhysicsControl.ReverseGearRatios = TransmissionSetup.ReverseGearRatios;
PhysicsControl.TransmissionEfficiency = VehicleMovComponent->TransmissionSetup.TransmissionEfficiency; PhysicsControl.ChangeUpRPM = TransmissionSetup.ChangeUpRPM;
PhysicsControl.ChangeDownRPM = TransmissionSetup.ChangeDownRPM;
// VehicleMovComponent Setup PhysicsControl.TransmissionEfficiency = TransmissionSetup.TransmissionEfficiency;
PhysicsControl.Mass = VehicleMovComponent->Mass; PhysicsControl.Mass = VehicleMovComponent.Mass;
PhysicsControl.DragCoefficient = VehicleMovComponent->DragCoefficient; PhysicsControl.DragCoefficient = VehicleMovComponent.DragCoefficient;
auto PrimitiveComponentPtr = Cast<UPrimitiveComponent>(VehicleMovComponent.UpdatedComponent);
// Center of mass offset (Center of mass is always zero vector in local check(PrimitiveComponentPtr != nullptr);
// position) PhysicsControl.CenterOfMass = PrimitiveComponentPtr->GetCenterOfMass();
UPrimitiveComponent *UpdatedPrimitive = Cast<UPrimitiveComponent>(VehicleMovComponent->UpdatedComponent); PhysicsControl.ChassisWidth = VehicleMovComponent.ChassisWidth;
check(UpdatedPrimitive != nullptr); PhysicsControl.ChassisHeight = VehicleMovComponent.ChassisHeight;
PhysicsControl.DownforceCoefficient = VehicleMovComponent.DownforceCoefficient;
PhysicsControl.CenterOfMass = UpdatedPrimitive->GetCenterOfMass(); PhysicsControl.DragArea = VehicleMovComponent.DragArea;
PhysicsControl.InertiaTensorScale = VehicleMovComponent.InertiaTensorScale;
// Transmission Setup PhysicsControl.SleepThreshold = VehicleMovComponent.SleepThreshold;
PhysicsControl.SteeringCurve = VehicleMovComponent->SteeringSetup.SteeringCurve.EditorCurveData; PhysicsControl.SleepSlopeLimit = VehicleMovComponent.SleepSlopeLimit;
RCurve = VehicleMovComponent.SteeringSetup.SteeringCurve.GetRichCurve();
check(RCurve != nullptr);
PhysicsControl.SteeringCurve = *RCurve;
PhysicsControl.UseSweepWheelCollision = false;
// Wheels Setup // Wheels Setup
TArray<FWheelPhysicsControl> Wheels; PhysicsControl.Wheels.SetNum(VehicleMovComponent.WheelSetups.Num());
for (int32 i = 0; i < PhysicsControl.Wheels.Num(); ++i)
for (int32 i = 0; i < VehicleMovComponent->WheelSetups.Num(); ++i)
{ {
FWheelPhysicsControl PhysicsWheel; auto& In = *VehicleMovComponent.Wheels[i];
PhysicsWheel.Radius = VehicleMovComponent->Wheels[i]->WheelRadius; auto& Out = PhysicsControl.Wheels[i];
PhysicsWheel.FrictionForceMultiplier = VehicleMovComponent->Wheels[i]->FrictionForceMultiplier; Out.AxleType = In.AxleType;
PhysicsWheel.MaxSteerAngle = VehicleMovComponent->Wheels[i]->MaxSteerAngle; Out.Offset = In.Offset;
PhysicsWheel.MaxBrakeTorque = VehicleMovComponent->Wheels[i]->MaxBrakeTorque; Out.WheelRadius = In.WheelRadius;
PhysicsWheel.MaxHandBrakeTorque = VehicleMovComponent->Wheels[i]->MaxHandBrakeTorque; Out.WheelWidth = In.WheelWidth;
PhysicsWheel.Position = VehicleMovComponent->Wheels[i]->Location; Out.WheelMass = In.WheelMass;
PhysicsWheel.CorneringStiffness = VehicleMovComponent->Wheels[i]->CorneringStiffness; Out.CorneringStiffness = In.CorneringStiffness;
PhysicsWheel.bABSEnabled = VehicleMovComponent->Wheels[i]->bABSEnabled; Out.FrictionForceMultiplier = In.FrictionForceMultiplier;
PhysicsWheel.bTractionControlEnabled = VehicleMovComponent->Wheels[i]->bTractionControlEnabled; Out.SideSlipModifier = In.SideSlipModifier;
Out.SlipThreshold = In.SlipThreshold;
if(VehicleMovComponent->Wheels[i]->SweepShape == ESweepShape::Spherecast) Out.SkidThreshold = In.SkidThreshold;
{ Out.MaxSteerAngle = In.MaxSteerAngle;
// 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. 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; PhysicsControl.UseSweepWheelCollision = true;
} }
Wheels.Add(PhysicsWheel);
}
PhysicsControl.Wheels = Wheels;
return PhysicsControl; return PhysicsControl;
} }
@ -438,81 +465,117 @@ void ACarlaWheeledVehicle::RestoreVehiclePhysicsControl()
ApplyVehiclePhysicsControl(LastPhysicsControl); ApplyVehiclePhysicsControl(LastPhysicsControl);
} }
void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsControl &PhysicsControl) void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(
const FVehiclePhysicsControl& PhysicsControl)
{ {
LastPhysicsControl = PhysicsControl; LastPhysicsControl = PhysicsControl;
UChaosWheeledVehicleMovementComponent* VehicleMovComponent = GetChaosWheeledVehicleMovementComponent(); auto VehicleMovComponentPtr = GetChaosWheeledVehicleMovementComponent();
check(VehicleMovComponent != nullptr); check(VehicleMovComponentPtr != nullptr);
auto& VehicleMovComponent = *VehicleMovComponentPtr;
// Engine Setup auto& EngineSetup = VehicleMovComponent.EngineSetup;
VehicleMovComponent->EngineSetup.TorqueCurve.EditorCurveData = PhysicsControl.TorqueCurve; EngineSetup.TorqueCurve.EditorCurveData = PhysicsControl.TorqueCurve;
VehicleMovComponent->EngineSetup.MaxTorque = PhysicsControl.MaxTorque; EngineSetup.MaxTorque = PhysicsControl.MaxTorque;
VehicleMovComponent->EngineSetup.MaxRPM = PhysicsControl.MaxRPM; EngineSetup.MaxRPM = PhysicsControl.MaxRPM;
VehicleMovComponent->EngineSetup.EngineRevUpMOI = PhysicsControl.MOI; EngineSetup.EngineIdleRPM = PhysicsControl.IdleRPM;
VehicleMovComponent->EngineSetup.EngineRevDownRate = PhysicsControl.RevDownRate; EngineSetup.EngineBrakeEffect = PhysicsControl.BrakeEffect;
EngineSetup.EngineRevUpMOI = PhysicsControl.RevUpMOI;
// Differential Setup EngineSetup.EngineRevDownRate = PhysicsControl.RevDownRate;
VehicleMovComponent->DifferentialSetup.DifferentialType = static_cast<EVehicleDifferential>(PhysicsControl.DifferentialType); auto& DifferentialSetup = VehicleMovComponent.DifferentialSetup;
VehicleMovComponent->DifferentialSetup.FrontRearSplit = PhysicsControl.FrontRearSplit; DifferentialSetup.DifferentialType = (EVehicleDifferential)PhysicsControl.DifferentialType;
DifferentialSetup.FrontRearSplit = PhysicsControl.FrontRearSplit;
// Transmission Setup auto& TransmissionSetup = VehicleMovComponent.TransmissionSetup;
VehicleMovComponent->TransmissionSetup.bUseAutomaticGears = PhysicsControl.bUseGearAutoBox; TransmissionSetup.bUseAutomaticGears = PhysicsControl.bUseAutomaticGears;
VehicleMovComponent->TransmissionSetup.FinalRatio = PhysicsControl.FinalRatio; TransmissionSetup.GearChangeTime = PhysicsControl.GearChangeTime;
VehicleMovComponent->TransmissionSetup.ForwardGearRatios = PhysicsControl.ForwardGears; TransmissionSetup.FinalRatio = PhysicsControl.FinalRatio;
VehicleMovComponent->TransmissionSetup.ReverseGearRatios = PhysicsControl.ReverseGears; TransmissionSetup.ForwardGearRatios = PhysicsControl.ForwardGearRatios;
VehicleMovComponent->TransmissionSetup.ChangeUpRPM = PhysicsControl.ChangeUpRPM; TransmissionSetup.ReverseGearRatios = PhysicsControl.ReverseGearRatios;
VehicleMovComponent->TransmissionSetup.ChangeDownRPM = PhysicsControl.ChangeDownRPM; TransmissionSetup.ChangeUpRPM = PhysicsControl.ChangeUpRPM;
VehicleMovComponent->TransmissionSetup.GearChangeTime = PhysicsControl.GearSwitchTime; TransmissionSetup.ChangeDownRPM = PhysicsControl.ChangeDownRPM;
VehicleMovComponent->TransmissionSetup.TransmissionEfficiency = PhysicsControl.TransmissionEfficiency; TransmissionSetup.TransmissionEfficiency = PhysicsControl.TransmissionEfficiency;
VehicleMovComponent.Mass = PhysicsControl.Mass;
// Vehicle Setup VehicleMovComponent.DragCoefficient = PhysicsControl.DragCoefficient;
VehicleMovComponent->Mass = PhysicsControl.Mass; auto PrimitiveComponentPtr = Cast<UPrimitiveComponent>(VehicleMovComponent.UpdatedComponent);
VehicleMovComponent->DragCoefficient = PhysicsControl.DragCoefficient; check(PrimitiveComponentPtr != nullptr);
auto& PrimitiveComponent = *PrimitiveComponentPtr;
// Center of mass PrimitiveComponent.SetCenterOfMass(PhysicsControl.CenterOfMass);
UPrimitiveComponent *UpdatedPrimitive = Cast<UPrimitiveComponent>(VehicleMovComponent->UpdatedComponent); VehicleMovComponent.ChassisWidth = PhysicsControl.ChassisWidth;
check(UpdatedPrimitive != nullptr); VehicleMovComponent.ChassisHeight = PhysicsControl.ChassisHeight;
VehicleMovComponent.DownforceCoefficient = PhysicsControl.DownforceCoefficient;
UpdatedPrimitive->BodyInstance.COMNudge = PhysicsControl.CenterOfMass; VehicleMovComponent.DragArea = PhysicsControl.DragArea;
VehicleMovComponent.InertiaTensorScale = PhysicsControl.InertiaTensorScale;
// Transmission Setup VehicleMovComponent.SleepThreshold = PhysicsControl.SleepThreshold;
VehicleMovComponent->SteeringSetup.SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve; VehicleMovComponent.SleepSlopeLimit = PhysicsControl.SleepSlopeLimit;
auto& SteeringSetup = VehicleMovComponent.SteeringSetup;
SteeringSetup.SteeringCurve.EditorCurveData = PhysicsControl.SteeringCurve;
// Wheels Setup // Wheels Setup
const int PhysicsWheelsNum = PhysicsControl.Wheels.Num(); auto WheelCount = PhysicsControl.Wheels.Num();
// TODO:: What about bikes or NW vehicles? // @TODO: What about bikes or NW vehicles?
if (PhysicsWheelsNum != 4) if (WheelCount != 4)
{ {
UE_LOG(LogCarla, Error, TEXT("Number of WheelPhysicsControl is not 4.")); UE_LOG(LogCarla, Error, TEXT("Number of WheelPhysicsControl is not 4."));
return; return;
} }
// Change, if required, the collision mode for wheels for (auto& WheelSetup : VehicleMovComponent.WheelSetups)
TArray<FChaosWheelSetup> NewWheelSetups = VehicleMovComponent->WheelSetups; check(WheelSetup.WheelClass != nullptr);
for (int32 i = 0; i < PhysicsWheelsNum; ++i)
{
UChaosVehicleWheel *Wheel = NewWheelSetups[i].WheelClass.GetDefaultObject();
check(Wheel != nullptr);
}
VehicleMovComponent->WheelSetups = NewWheelSetups;
for (int32 i = 0; i < PhysicsWheelsNum; ++i) for (int32 i = 0; i < WheelCount; ++i)
{ {
VehicleMovComponent->SetWheelRadius(i, PhysicsControl.Wheels[i].Radius); auto& In = PhysicsControl.Wheels[i];
VehicleMovComponent->SetWheelFrictionMultiplier(i, PhysicsControl.Wheels[i].FrictionForceMultiplier); auto OutPtr = VehicleMovComponent.Wheels[i];
VehicleMovComponent->SetWheelMaxSteerAngle(i, PhysicsControl.Wheels[i].MaxSteerAngle); check(OutPtr != nullptr);
VehicleMovComponent->SetWheelMaxBrakeTorque(i, PhysicsControl.Wheels[i].MaxBrakeTorque); auto& Out = *OutPtr;
VehicleMovComponent->SetWheelHandbrakeTorque(i, PhysicsControl.Wheels[i].MaxHandBrakeTorque);
VehicleMovComponent->SetABSEnabled(i, PhysicsControl.Wheels[i].bABSEnabled); Out.AxleType = In.AxleType;
VehicleMovComponent->SetTractionControlEnabled(i, PhysicsControl.Wheels[i].bTractionControlEnabled); Out.Offset = In.Offset;
VehicleMovComponent->Wheels[i]->CorneringStiffness = PhysicsControl.Wheels[i].CorneringStiffness; VehicleMovComponent.SetWheelRadius(i, In.WheelRadius);
VehicleMovComponent->Wheels[i]->SweepShape = PhysicsControl.UseSweepWheelCollision ? ESweepShape::Spherecast : ESweepShape::Raycast; 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(); ResetConstraints();
auto * Recorder = UCarlaStatics::GetRecorder(GetWorld()); auto* Recorder = UCarlaStatics::GetRecorder(GetWorld());
if (Recorder && Recorder->IsEnabled()) if (Recorder && Recorder->IsEnabled())
{ {
Recorder->AddPhysicsControl(*this); Recorder->AddPhysicsControl(*this);
@ -522,7 +585,7 @@ void ACarlaWheeledVehicle::ApplyVehiclePhysicsControl(const FVehiclePhysicsContr
AckermannController.UpdateVehiclePhysics(this); AckermannController.UpdateVehiclePhysics(this);
} }
void ACarlaWheeledVehicle::ApplyVehicleControl(const FVehicleControl &Control, EVehicleInputPriority Priority) void ACarlaWheeledVehicle::ApplyVehicleControl(const FVehicleControl& Control, EVehicleInputPriority Priority)
{ {
if (bAckermannControlActive) { if (bAckermannControlActive) {
AckermannController.Reset(); AckermannController.Reset();
@ -536,14 +599,14 @@ void ACarlaWheeledVehicle::ApplyVehicleControl(const FVehicleControl &Control, E
} }
} }
void ACarlaWheeledVehicle::ApplyVehicleAckermannControl(const FVehicleAckermannControl &AckermannControl, EVehicleInputPriority Priority) void ACarlaWheeledVehicle::ApplyVehicleAckermannControl(const FVehicleAckermannControl& AckermannControl, EVehicleInputPriority Priority)
{ {
bAckermannControlActive = true; bAckermannControlActive = true;
LastAppliedAckermannControl = AckermannControl; LastAppliedAckermannControl = AckermannControl;
AckermannController.SetTargetPoint(AckermannControl); AckermannController.SetTargetPoint(AckermannControl);
} }
void ACarlaWheeledVehicle::ActivateVelocityControl(const FVector &Velocity) void ACarlaWheeledVehicle::ActivateVelocityControl(const FVector& Velocity)
{ {
VelocityControl->Activate(Velocity); VelocityControl->Activate(Velocity);
} }
@ -583,7 +646,7 @@ void ACarlaWheeledVehicle::ShowDebugTelemetry(bool Enabled)
*/ */
} }
void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightState) void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState& LightState)
{ {
if (LightState.Position != InputControl.LightState.Position || if (LightState.Position != InputControl.LightState.Position ||
LightState.LowBeam != InputControl.LightState.LowBeam || LightState.LowBeam != InputControl.LightState.LowBeam ||
@ -602,7 +665,7 @@ void ACarlaWheeledVehicle::SetVehicleLightState(const FVehicleLightState &LightS
} }
} }
void ACarlaWheeledVehicle::SetFailureState(const carla::rpc::VehicleFailureState &InFailureState) void ACarlaWheeledVehicle::SetFailureState(const carla::rpc::VehicleFailureState& InFailureState)
{ {
FailureState = InFailureState; FailureState = InFailureState;
} }
@ -621,7 +684,7 @@ void ACarlaWheeledVehicle::SetWheelSteerDirection(EVehicleWheelLocation WheelLoc
if (bPhysicsEnabled == false) if (bPhysicsEnabled == false)
{ {
check((uint8)WheelLocation >= 0) check((uint8)WheelLocation >= 0)
UVehicleAnimationInstance *VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance()); UVehicleAnimationInstance* VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
check(VehicleAnim != nullptr) check(VehicleAnim != nullptr)
// ToDo We need to investigate about this // ToDo We need to investigate about this
//VehicleAnim->GetWheelAnimData()SetWheelRotYaw((uint8)WheelLocation, AngleInDeg); //VehicleAnim->GetWheelAnimData()SetWheelRotYaw((uint8)WheelLocation, AngleInDeg);
@ -636,7 +699,7 @@ float ACarlaWheeledVehicle::GetWheelSteerAngle(EVehicleWheelLocation WheelLocati
#if 0 // @CARLAUE5 // ToDo We need to investigate about this #if 0 // @CARLAUE5 // ToDo We need to investigate about this
check((uint8)WheelLocation >= 0) check((uint8)WheelLocation >= 0)
UVehicleAnimationInstance *VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance()); UVehicleAnimationInstance* VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
check(VehicleAnim != nullptr) check(VehicleAnim != nullptr)
check(VehicleAnim->GetWheeledVehicleMovementComponent() != nullptr) check(VehicleAnim->GetWheeledVehicleMovementComponent() != nullptr)
@ -654,7 +717,7 @@ float ACarlaWheeledVehicle::GetWheelSteerAngle(EVehicleWheelLocation WheelLocati
} }
void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) { void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) {
if(!GetCarlaMovementComponent<UDefaultMovementComponent>()) if (!GetCarlaMovementComponent<UDefaultMovementComponent>())
{ {
return; return;
} }
@ -664,7 +727,7 @@ void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) {
{ {
check(Movement != nullptr); check(Movement != nullptr);
if(bPhysicsEnabled == enabled) if (bPhysicsEnabled == enabled)
return; return;
SetActorEnableCollision(true); SetActorEnableCollision(true);
@ -673,7 +736,7 @@ void ACarlaWheeledVehicle::SetSimulatePhysics(bool enabled) {
RootPrimitive->SetSimulatePhysics(enabled); RootPrimitive->SetSimulatePhysics(enabled);
RootPrimitive->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics); RootPrimitive->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
UVehicleAnimationInstance *VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance()); UVehicleAnimationInstance* VehicleAnim = Cast<UVehicleAnimationInstance>(GetMesh()->GetAnimInstance());
check(VehicleAnim != nullptr) check(VehicleAnim != nullptr)
if (enabled) if (enabled)
@ -798,7 +861,7 @@ void ACarlaWheeledVehicle::CloseDoorPhys(const EVehicleDoor DoorIdx)
void ACarlaWheeledVehicle::RecordDoorChange(const EVehicleDoor DoorIdx, bool bIsOpen) void ACarlaWheeledVehicle::RecordDoorChange(const EVehicleDoor DoorIdx, bool bIsOpen)
{ {
auto * Recorder = UCarlaStatics::GetRecorder(GetWorld()); auto* Recorder = UCarlaStatics::GetRecorder(GetWorld());
if (Recorder && Recorder->IsEnabled()) if (Recorder && Recorder->IsEnabled())
{ {
Recorder->AddVehicleDoor(*this, DoorIdx, bIsOpen); Recorder->AddVehicleDoor(*this, DoorIdx, bIsOpen);
@ -826,14 +889,14 @@ void ACarlaWheeledVehicle::ApplyRolloverBehavior()
} }
// In case the vehicle recovers, reset the rollover tracker // 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; RolloverBehaviorTracker = 0;
FailureState = carla::rpc::VehicleFailureState::None; FailureState = carla::rpc::VehicleFailureState::None;
} }
} }
void ACarlaWheeledVehicle::CheckRollover(const float roll, const std::pair<float, float> threshold_roll){ void ACarlaWheeledVehicle::CheckRollover(const float roll, const std::pair<float, float> threshold_roll) {
if (threshold_roll.first < roll && roll < threshold_roll.second){ if (threshold_roll.first < roll && roll < threshold_roll.second) {
auto Root = Cast<UPrimitiveComponent>(GetRootComponent()); auto Root = Cast<UPrimitiveComponent>(GetRootComponent());
auto AngularVelocity = Root->GetPhysicsAngularVelocityInDegrees(); auto AngularVelocity = Root->GetPhysicsAngularVelocityInDegrees();
Root->SetPhysicsAngularVelocityInDegrees((1 - RolloverBehaviorForce) * AngularVelocity); 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 // Make sure the vehicle hasn't recovered since the timer started
if (RolloverBehaviorTracker >= 4) { if (RolloverBehaviorTracker >= 4) {
FailureState = carla::rpc::VehicleFailureState::Rollover; FailureState = carla::rpc::VehicleFailureState::Rollover;
} }
} }
carla::rpc::VehicleFailureState ACarlaWheeledVehicle::GetFailureState() const{ carla::rpc::VehicleFailureState ACarlaWheeledVehicle::GetFailureState() const {
return FailureState; return FailureState;
} }
@ -889,7 +952,7 @@ FRotator ACarlaWheeledVehicle::GetPhysicsConstraintAngle(
} }
void ACarlaWheeledVehicle::SetPhysicsConstraintAngle( void ACarlaWheeledVehicle::SetPhysicsConstraintAngle(
UPhysicsConstraintComponent* Component, const FRotator &NewAngle) UPhysicsConstraintComponent* Component, const FRotator& NewAngle)
{ {
Component->ConstraintInstance.AngularRotationOffset = NewAngle; Component->ConstraintInstance.AngularRotationOffset = NewAngle;
} }

View File

@ -23,13 +23,19 @@ struct CARLA_API FVehiclePhysicsControl
FRichCurve TorqueCurve; FRichCurve TorqueCurve;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float MaxTorque = 300.0f;; float MaxTorque = 300.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float MaxRPM = 5000.0f; float MaxRPM = 5000.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) 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) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float RevDownRate = 600.0f; float RevDownRate = 600.0f;
@ -44,19 +50,19 @@ struct CARLA_API FVehiclePhysicsControl
// Transmission Setup // Transmission Setup
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
bool bUseGearAutoBox = true; bool bUseAutomaticGears = true;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float GearSwitchTime = 0.5f; float GearChangeTime = 0.5f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float FinalRatio = 4.0f; float FinalRatio = 4.0f;
UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite) 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) 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) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
float ChangeUpRPM = 4500.0f; float ChangeUpRPM = 4500.0f;
@ -78,12 +84,55 @@ struct CARLA_API FVehiclePhysicsControl
FRichCurve SteeringCurve; FRichCurve SteeringCurve;
// Center Of Mass // Center Of Mass
UPROPERTY(Category = "Vehicle Center Of Mass", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
FVector CenterOfMass = FVector::ZeroVector; 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 // Wheels Setup
TArray<FWheelPhysicsControl> Wheels; TArray<FWheelPhysicsControl> Wheels;
UPROPERTY(Category = "Vehicle Wheels Configuration", EditAnywhere, BlueprintReadWrite) UPROPERTY(Category = "Vehicle Engine Physics Control", EditAnywhere, BlueprintReadWrite)
bool UseSweepWheelCollision = false; bool UseSweepWheelCollision = false;
}; };

View File

@ -5,7 +5,7 @@
// For a copy, see <https://opensource.org/licenses/MIT>. // For a copy, see <https://opensource.org/licenses/MIT>.
#pragma once #pragma once
#include "ChaosVehicleWheel.h"
#include "WheelPhysicsControl.generated.h" #include "WheelPhysicsControl.generated.h"
USTRUCT(BlueprintType) USTRUCT(BlueprintType)
@ -13,30 +13,166 @@ struct CARLA_API FWheelPhysicsControl
{ {
GENERATED_BODY() GENERATED_BODY()
UPROPERTY(Category = "Wheel Tire Friction", EditAnywhere, BlueprintReadWrite) /** 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 */
float FrictionForceMultiplier = 3.5f; 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) /** Radius of the wheel */
float Radius = 30.0f; UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.01", UIMin = "0.01"))
float WheelRadius;
UPROPERTY(Category = "Tyre Cornering Ability", EditAnywhere, BlueprintReadWrite) /** Width of the wheel */
float CorneringStiffness = 1000.0f; UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.01", UIMin = "0.01"))
float WheelWidth;
UPROPERTY(Category = "Advanced Braking System Enabled", EditAnywhere, BlueprintReadWrite) /** Mass of the wheel Kg */
bool bABSEnabled = false; UPROPERTY(EditAnywhere, Category = Wheel, meta = (ClampMin = "0.01", UIMin = "0.01"))
float WheelMass;
UPROPERTY(Category = "Straight Line Traction Control Enabled", EditAnywhere, BlueprintReadWrite) /** Tyre Cornering Ability */
bool bTractionControlEnabled = false; UPROPERTY(EditAnywhere, Category = Wheel)
float CorneringStiffness;
UPROPERTY(Category = "Wheel Max Brake Torque (Nm)", EditAnywhere, BlueprintReadWrite) /** Friction Force Multiplier */
float MaxBrakeTorque = 1500.0f; UPROPERTY(EditAnywhere, Category = Wheel)
float FrictionForceMultiplier;
UPROPERTY(Category = "Wheel Max Handbrake Torque (Nm)", EditAnywhere, BlueprintReadWrite) /** Wheel Lateral Skid Grip Loss, lower number less grip on skid */
float MaxHandBrakeTorque = 3000.0f; 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) UPROPERTY(Category = "Wheel Position", EditAnywhere, BlueprintReadWrite)
FVector Position = FVector::ZeroVector; FVector Velocity;
}; };

View File

@ -34,14 +34,14 @@ UWheeledVehicleMovementComponentNW::UWheeledVehicleMovementComponentNW(const FOb
} }
FVehicleTransmissionConfig TransmissionData; FVehicleTransmissionConfig TransmissionData;
TransmissionSetup.GearSwitchTime = DefGearSetup.mSwitchTime; TransmissionSetup.GearChangeTime = DefGearSetup.mSwitchTime;
TransmissionSetup.ReverseGearRatio = DefGearSetup.mRatios[PxVehicleGearsData::eREVERSE]; TransmissionSetup.ReverseGearRatio = DefGearSetup.mRatios[PxVehicleGearsData::eREVERSE];
TransmissionSetup.FinalRatio = DefGearSetup.mFinalRatio; TransmissionSetup.FinalRatio = DefGearSetup.mFinalRatio;
PxVehicleAutoBoxData DefAutoBoxSetup; PxVehicleAutoBoxData DefAutoBoxSetup;
TransmissionSetup.NeutralGearUpRatio = DefAutoBoxSetup.mUpRatios[PxVehicleGearsData::eNEUTRAL]; TransmissionSetup.NeutralGearUpRatio = DefAutoBoxSetup.mUpRatios[PxVehicleGearsData::eNEUTRAL];
TransmissionSetup.GearAutoBoxLatency = DefAutoBoxSetup.getLatency(); TransmissionSetup.GearAutoBoxLatency = DefAutoBoxSetup.getLatency();
TransmissionSetup.bUseGearAutoBox = true; TransmissionSetup.bUseAutomaticGears = true;
for (uint32 i = PxVehicleGearsData::eFIRST; i < DefGearSetup.mNbRatios; ++i) for (uint32 i = PxVehicleGearsData::eFIRST; i < DefGearSetup.mNbRatios; ++i)
{ {
@ -49,7 +49,7 @@ UWheeledVehicleMovementComponentNW::UWheeledVehicleMovementComponentNW(const FOb
GearData.DownRatio = DefAutoBoxSetup.mDownRatios[i]; GearData.DownRatio = DefAutoBoxSetup.mDownRatios[i];
GearData.UpRatio = DefAutoBoxSetup.mUpRatios[i]; GearData.UpRatio = DefAutoBoxSetup.mUpRatios[i];
GearData.Ratio = DefGearSetup.mRatios[i]; GearData.Ratio = DefGearSetup.mRatios[i];
TransmissionSetup.ForwardGears.Add(GearData); TransmissionSetup.ForwardGearRatios.Add(GearData);
} }
*/ */
@ -78,17 +78,17 @@ void UWheeledVehicleMovementComponentNW::PostEditChangeProperty(struct FProperty
if (PropertyName == TEXT("DownRatio")) if (PropertyName == TEXT("DownRatio"))
{ {
for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGears.Num(); ++GearIdx) for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGearRatios.Num(); ++GearIdx)
{ {
FVehicleNWGearData& GearData = TransmissionSetup.ForwardGears[GearIdx]; FVehicleNWGearData& GearData = TransmissionSetup.ForwardGearRatios[GearIdx];
GearData.DownRatio = FMath::Min(GearData.DownRatio, GearData.UpRatio); GearData.DownRatio = FMath::Min(GearData.DownRatio, GearData.UpRatio);
} }
} }
else if (PropertyName == TEXT("UpRatio")) else if (PropertyName == TEXT("UpRatio"))
{ {
for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGears.Num(); ++GearIdx) for (int32 GearIdx = 0; GearIdx < TransmissionSetup.ForwardGearRatios.Num(); ++GearIdx)
{ {
FVehicleNWGearData& GearData = TransmissionSetup.ForwardGears[GearIdx]; FVehicleNWGearData& GearData = TransmissionSetup.ForwardGearRatios[GearIdx];
GearData.UpRatio = FMath::Max(GearData.DownRatio, GearData.UpRatio); GearData.UpRatio = FMath::Max(GearData.DownRatio, GearData.UpRatio);
} }
} }

View File

@ -80,14 +80,14 @@ struct FVehicleNWTransmissionData
GENERATED_USTRUCT_BODY() GENERATED_USTRUCT_BODY()
/** Whether to use automatic transmission */ /** Whether to use automatic transmission */
UPROPERTY(EditAnywhere, Category = VehicleSetup, meta = (DisplayName = "Automatic Transmission")) UPROPERTY(EditAnywhere, Category = VehicleSetup, meta = (DisplayName = "Automatic Transmission"))
bool bUseGearAutoBox = false; bool bUseAutomaticGears = false;
/** Time it takes to switch gears (seconds) */ /** Time it takes to switch gears (seconds) */
UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.0", UIMin = "0.0")) UPROPERTY(EditAnywhere, Category = Setup, meta = (ClampMin = "0.0", UIMin = "0.0"))
float GearSwitchTime = 0.0F; float GearChangeTime = 0.0F;
/** Minimum time it takes the automatic transmission to initiate a gear change (seconds)*/ /** 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")) UPROPERTY(EditAnywhere, Category = Setup, meta = (editcondition = "bUseAutomaticGears", ClampMin = "0.0", UIMin = "0.0"))
float GearAutoBoxLatency = 0.0F; float GearAutoBoxLatency = 0.0F;
/** The final gear ratio multiplies the transmission gear ratios.*/ /** The final gear ratio multiplies the transmission gear ratios.*/
@ -96,7 +96,7 @@ struct FVehicleNWTransmissionData
/** Forward gear ratios (up to 30) */ /** Forward gear ratios (up to 30) */
UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay) UPROPERTY(EditAnywhere, Category = Setup, AdvancedDisplay)
TArray<FVehicleNWGearData> ForwardGears; TArray<FVehicleNWGearData> ForwardGearRatios;
/** Reverse gear ratio */ /** Reverse gear ratio */
UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup) UPROPERTY(EditAnywhere, AdvancedDisplay, Category = Setup)