ready to enable input
This commit is contained in:
parent
85fe12bd3f
commit
ecfa9b5864
10 changed files with 165 additions and 283 deletions
|
@ -37,7 +37,7 @@ impl Default for MovementSettings {
|
||||||
fn default() -> Self {
|
fn default() -> Self {
|
||||||
Self {
|
Self {
|
||||||
accel: 20.0,
|
accel: 20.0,
|
||||||
gravity: 4.8,
|
gravity: 9.8,
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -53,9 +53,9 @@ pub struct CatControllerSettings {
|
||||||
impl Default for CatControllerSettings {
|
impl Default for CatControllerSettings {
|
||||||
fn default() -> Self {
|
fn default() -> Self {
|
||||||
Self {
|
Self {
|
||||||
kp: 80.0,
|
kp: 1200.0,
|
||||||
kd: 10.0,
|
kd: 10.0,
|
||||||
ki: 0.4,
|
ki: 50.0,
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
use avian3d::prelude::{PhysicsPlugins, SubstepCount};
|
use avian3d::prelude::{PhysicsPlugins, SubstepCount};
|
||||||
use bevy::{
|
use bevy::{
|
||||||
app::Update,
|
app::FixedUpdate,
|
||||||
diagnostic::FrameTimeDiagnosticsPlugin,
|
diagnostic::FrameTimeDiagnosticsPlugin,
|
||||||
ecs::reflect::ReflectResource,
|
ecs::reflect::ReflectResource,
|
||||||
prelude::{App, IntoSystemConfigs, Plugin, Resource},
|
prelude::{App, IntoSystemConfigs, Plugin, Resource},
|
||||||
|
@ -29,18 +29,10 @@ impl Plugin for CyberActionPlugin {
|
||||||
.register_type::<CyberLean>()
|
.register_type::<CyberLean>()
|
||||||
.register_type::<CatControllerSettings>()
|
.register_type::<CatControllerSettings>()
|
||||||
.add_plugins((PhysicsPlugins::default(), FrameTimeDiagnosticsPlugin))
|
.add_plugins((PhysicsPlugins::default(), FrameTimeDiagnosticsPlugin))
|
||||||
.insert_resource(SubstepCount(6))
|
.insert_resource(SubstepCount(12))
|
||||||
.add_systems(
|
.add_systems(
|
||||||
Update,
|
FixedUpdate,
|
||||||
(
|
(set_gravity, calculate_lean, apply_lean).chain(),
|
||||||
set_gravity,
|
|
||||||
clear_forces,
|
|
||||||
calculate_lean,
|
|
||||||
apply_lean,
|
|
||||||
//#[cfg(feature = "inspector")]
|
|
||||||
debug_bodies,
|
|
||||||
)
|
|
||||||
.chain(),
|
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,18 +1,16 @@
|
||||||
use std::f32::consts::{FRAC_PI_3, FRAC_PI_4};
|
use std::f32::consts::{FRAC_PI_3, FRAC_PI_4};
|
||||||
|
|
||||||
use avian3d::{
|
use avian3d::{
|
||||||
collision::Collisions,
|
|
||||||
dynamics::solver::xpbd::AngularConstraint,
|
dynamics::solver::xpbd::AngularConstraint,
|
||||||
prelude::{
|
prelude::{ExternalTorque, FixedJoint, Gravity, LinearVelocity, RigidBodyQuery},
|
||||||
ColliderMassProperties, Collision, ExternalForce, ExternalTorque, Gravity, LinearVelocity,
|
|
||||||
PrismaticJoint, RigidBodyQuery,
|
|
||||||
},
|
|
||||||
};
|
};
|
||||||
use bevy::prelude::{EventReader, Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without};
|
#[cfg(feature = "inspector")]
|
||||||
|
use bevy::prelude::Gizmos;
|
||||||
|
use bevy::prelude::{Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without};
|
||||||
|
|
||||||
use super::{CatControllerSettings, CatControllerState, CyberLean, MovementSettings};
|
use super::{CatControllerSettings, CatControllerState, CyberLean, MovementSettings};
|
||||||
use crate::{
|
use crate::{
|
||||||
bike::{CyberBikeBody, CyberFork, CyberSpring, CyberSteering, CyberWheel, WheelConfig},
|
bike::{CyberBikeBody, CyberFork, CyberSteering, CyberWheel},
|
||||||
input::InputState,
|
input::InputState,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -39,7 +37,6 @@ fn rotate_point(pt: &Vec3, rot: &Quat) -> Vec3 {
|
||||||
/// The gravity vector points from the cyberbike to the center of the planet.
|
/// The gravity vector points from the cyberbike to the center of the planet.
|
||||||
pub(super) fn set_gravity(
|
pub(super) fn set_gravity(
|
||||||
xform: Query<&Transform, With<CyberBikeBody>>,
|
xform: Query<&Transform, With<CyberBikeBody>>,
|
||||||
|
|
||||||
settings: Res<MovementSettings>,
|
settings: Res<MovementSettings>,
|
||||||
mut gravity: ResMut<Gravity>,
|
mut gravity: ResMut<Gravity>,
|
||||||
) {
|
) {
|
||||||
|
@ -47,42 +44,6 @@ pub(super) fn set_gravity(
|
||||||
*gravity = Gravity(xform.translation.normalize() * -settings.gravity);
|
*gravity = Gravity(xform.translation.normalize() * -settings.gravity);
|
||||||
}
|
}
|
||||||
|
|
||||||
pub(super) fn clear_forces(
|
|
||||||
mut forces: Query<(Option<&mut ExternalForce>, Option<&mut ExternalTorque>)>,
|
|
||||||
) {
|
|
||||||
for (force, torque) in forces.iter_mut() {
|
|
||||||
if let Some(mut force) = force {
|
|
||||||
force.clear();
|
|
||||||
}
|
|
||||||
if let Some(mut torque) = torque {
|
|
||||||
torque.clear();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
pub(super) fn suspension(
|
|
||||||
movment_settings: Res<MovementSettings>,
|
|
||||||
wheel_config: Res<WheelConfig>,
|
|
||||||
time: Res<Time>,
|
|
||||||
mass: Query<&ColliderMassProperties, With<CyberBikeBody>>,
|
|
||||||
mut axels: Query<(&mut ExternalForce, &CyberSpring, &Transform)>,
|
|
||||||
) {
|
|
||||||
let mass = if let Ok(mass) = mass.get_single() {
|
|
||||||
mass.mass.0
|
|
||||||
} else {
|
|
||||||
1.0
|
|
||||||
};
|
|
||||||
let dt = time.delta_seconds();
|
|
||||||
let gravity = movment_settings.gravity;
|
|
||||||
let mag = -wheel_config.stiffness * mass * gravity * dt;
|
|
||||||
for (mut force, spring, xform) in axels.iter_mut() {
|
|
||||||
let spring = mag * spring.0;
|
|
||||||
let spring = xform.translation + spring;
|
|
||||||
bevy::log::info!("suspension force: {spring:?}");
|
|
||||||
let _ = force.apply_force(spring);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/// The desired lean angle, given steering input and speed.
|
/// The desired lean angle, given steering input and speed.
|
||||||
pub(super) fn calculate_lean(
|
pub(super) fn calculate_lean(
|
||||||
bike_state: Query<(&LinearVelocity, &Transform), With<CyberBikeBody>>,
|
bike_state: Query<(&LinearVelocity, &Transform), With<CyberBikeBody>>,
|
||||||
|
@ -102,7 +63,7 @@ pub(super) fn calculate_lean(
|
||||||
let v2_r = v_squared / radius;
|
let v2_r = v_squared / radius;
|
||||||
let tan_theta = (v2_r / gravity).clamp(-FRAC_PI_3, FRAC_PI_3);
|
let tan_theta = (v2_r / gravity).clamp(-FRAC_PI_3, FRAC_PI_3);
|
||||||
|
|
||||||
if tan_theta.is_finite() && !tan_theta.is_subnormal() {
|
if tan_theta.is_normal() {
|
||||||
lean.lean = tan_theta.atan().clamp(-FRAC_PI_4, FRAC_PI_4);
|
lean.lean = tan_theta.atan().clamp(-FRAC_PI_4, FRAC_PI_4);
|
||||||
} else {
|
} else {
|
||||||
lean.lean = 0.0;
|
lean.lean = 0.0;
|
||||||
|
@ -115,6 +76,7 @@ pub(super) fn apply_lean(
|
||||||
time: Res<Time>,
|
time: Res<Time>,
|
||||||
settings: Res<CatControllerSettings>,
|
settings: Res<CatControllerSettings>,
|
||||||
lean: Res<CyberLean>,
|
lean: Res<CyberLean>,
|
||||||
|
#[cfg(feature = "inspector")] mut gizmos: Gizmos,
|
||||||
) {
|
) {
|
||||||
let (xform, mut torque, mut control_vars) = bike_query.single_mut();
|
let (xform, mut torque, mut control_vars) = bike_query.single_mut();
|
||||||
let world_up = xform.translation.normalize();
|
let world_up = xform.translation.normalize();
|
||||||
|
@ -131,8 +93,15 @@ pub(super) fn apply_lean(
|
||||||
let (derivative, integral) = control_vars.update_roll(roll_error, time.delta_seconds());
|
let (derivative, integral) = control_vars.update_roll(roll_error, time.delta_seconds());
|
||||||
let mag =
|
let mag =
|
||||||
(settings.kp * roll_error) + (settings.ki * integral) + (settings.kd * derivative);
|
(settings.kp * roll_error) + (settings.ki * integral) + (settings.kd * derivative);
|
||||||
if mag.is_finite() {
|
if mag.is_normal() {
|
||||||
torque.apply_torque(*xform.back() * mag);
|
let tork = mag * *xform.back();
|
||||||
|
torque.apply_torque(tork);
|
||||||
|
#[cfg(feature = "inspector")]
|
||||||
|
gizmos.arrow(
|
||||||
|
xform.translation + Vec3::Y,
|
||||||
|
xform.translation + tork + Vec3::Y,
|
||||||
|
bevy::color::Color::WHITE,
|
||||||
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -142,94 +111,35 @@ pub(super) fn apply_inputs(
|
||||||
settings: Res<MovementSettings>,
|
settings: Res<MovementSettings>,
|
||||||
input: Res<InputState>,
|
input: Res<InputState>,
|
||||||
time: Res<Time>,
|
time: Res<Time>,
|
||||||
fork: Query<&PrismaticJoint, With<CyberFork>>,
|
fork: Query<(&FixedJoint, &CyberFork), With<CyberSteering>>,
|
||||||
mut axle: Query<(RigidBodyQuery, &Transform), With<CyberSteering>>,
|
mut hub: Query<(RigidBodyQuery, &Transform), With<CyberSteering>>,
|
||||||
mut braking_query: Query<&mut ExternalTorque, With<CyberWheel>>,
|
mut braking_query: Query<(&Transform, &mut ExternalTorque), With<CyberWheel>>,
|
||||||
mut body_query: Query<
|
mut body_query: Query<RigidBodyQuery, (With<CyberBikeBody>, Without<CyberSteering>)>,
|
||||||
(
|
|
||||||
RigidBodyQuery,
|
|
||||||
&Transform,
|
|
||||||
&ColliderMassProperties,
|
|
||||||
&mut ExternalForce,
|
|
||||||
),
|
|
||||||
(With<CyberBikeBody>, Without<CyberSteering>),
|
|
||||||
>,
|
|
||||||
) {
|
) {
|
||||||
let Ok((mut bike, xform, mass, mut forces)) = body_query.get_single_mut() else {
|
let Ok(mut bike) = body_query.get_single_mut() else {
|
||||||
bevy::log::debug!("no bike body found");
|
bevy::log::debug!("no bike body found");
|
||||||
return;
|
return;
|
||||||
};
|
};
|
||||||
let dt = time.delta_seconds();
|
let dt = time.delta_seconds();
|
||||||
|
|
||||||
// thrust
|
|
||||||
let thrust = xform.forward() * input.throttle * settings.accel;
|
|
||||||
let point = xform.translation + *xform.back();
|
|
||||||
|
|
||||||
//let _ = *forces.apply_force_at_point(dt * thrust, point,
|
|
||||||
// mass.center_of_mass.0);
|
|
||||||
|
|
||||||
// brake + thrust
|
// brake + thrust
|
||||||
for mut motor in braking_query.iter_mut() {
|
for (xform, mut motor) in braking_query.iter_mut() {
|
||||||
let factor = if input.brake {
|
let factor = input.throttle * settings.accel;
|
||||||
500.00
|
|
||||||
} else {
|
let target = dt * factor;
|
||||||
input.throttle * settings.accel
|
let torque = target * *xform.right();
|
||||||
};
|
|
||||||
let speed = if input.brake { 0.0 } else { -70.0 };
|
|
||||||
let target = dt * factor * speed;
|
|
||||||
let torque = target * Vec3::X;
|
|
||||||
motor.apply_torque(torque);
|
motor.apply_torque(torque);
|
||||||
}
|
}
|
||||||
|
|
||||||
// steering
|
// steering
|
||||||
let _angle = yaw_to_angle(input.yaw);
|
let _angle = yaw_to_angle(input.yaw);
|
||||||
let (mut axle, xform) = axle.single_mut();
|
let (mut axle, xform) = hub.single_mut();
|
||||||
|
|
||||||
let cur_rot = xform.rotation;
|
let cur_rot = xform.rotation;
|
||||||
let fork = fork.single();
|
let (fork, CyberFork(axis)) = fork.single();
|
||||||
let axis = fork.free_axis.normalize();
|
let new = Quat::from_axis_angle(*axis, _angle);
|
||||||
let new = Quat::from_axis_angle(axis, _angle);
|
|
||||||
let diff = (new - cur_rot).to_scaled_axis();
|
let diff = (new - cur_rot).to_scaled_axis();
|
||||||
let mut compliance = 1.0;
|
let mut lagrange = 1.0;
|
||||||
|
|
||||||
fork.align_orientation(&mut axle, &mut bike, diff, &mut compliance, 1.0, dt);
|
fork.align_orientation(&mut axle, &mut bike, diff, &mut lagrange, 0.0, dt);
|
||||||
}
|
}
|
||||||
|
|
||||||
//#[cfg(feature = "inspector")]
|
|
||||||
mod inspector {
|
|
||||||
use bevy::prelude::Entity;
|
|
||||||
|
|
||||||
use super::*;
|
|
||||||
pub(crate) fn debug_bodies(
|
|
||||||
bodies: Query<(Entity, RigidBodyQuery)>,
|
|
||||||
mut collisions: EventReader<Collision>,
|
|
||||||
) {
|
|
||||||
let bodies: Vec<_> = bodies.iter().collect();
|
|
||||||
for i in 0..(bodies.len()) {
|
|
||||||
let (ent, ref rb) = bodies[i];
|
|
||||||
let cur_pos = rb.current_position();
|
|
||||||
let mut max = 0.0f32;
|
|
||||||
let mut min = f32::MAX;
|
|
||||||
for j in 0..(bodies.len()) {
|
|
||||||
if j == i {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
let (_, ref other) = bodies[j];
|
|
||||||
let dist = (cur_pos - other.current_position()).length();
|
|
||||||
max = max.max(dist);
|
|
||||||
min = min.min(dist);
|
|
||||||
}
|
|
||||||
let line = format!("{ent:?} at {cur_pos:?} -- min: {min}, max: {max}");
|
|
||||||
bevy::log::info!(line);
|
|
||||||
}
|
|
||||||
for Collision(contacts) in collisions.read() {
|
|
||||||
bevy::log::info!(
|
|
||||||
"Entities {:?} and {:?} are colliding",
|
|
||||||
contacts.entity1,
|
|
||||||
contacts.entity2,
|
|
||||||
);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
//#[cfg(feature = "inspector")]
|
|
||||||
pub(super) use inspector::debug_bodies;
|
|
||||||
|
|
|
@ -1,5 +1,6 @@
|
||||||
use avian3d::prelude::*;
|
use avian3d::prelude::*;
|
||||||
use bevy::{
|
use bevy::{
|
||||||
|
core::Name,
|
||||||
prelude::{AssetServer, BuildChildren, Commands, Quat, Res, SpatialBundle, Transform, Vec3},
|
prelude::{AssetServer, BuildChildren, Commands, Quat, Res, SpatialBundle, Transform, Vec3},
|
||||||
scene::SceneBundle,
|
scene::SceneBundle,
|
||||||
};
|
};
|
||||||
|
@ -42,6 +43,7 @@ pub(super) fn spawn_cyberbike(
|
||||||
let bike = commands
|
let bike = commands
|
||||||
.spawn(SpatialBundle::from_transform(xform))
|
.spawn(SpatialBundle::from_transform(xform))
|
||||||
.insert((
|
.insert((
|
||||||
|
Name::new("bike body"),
|
||||||
RigidBody::Dynamic,
|
RigidBody::Dynamic,
|
||||||
body_collider,
|
body_collider,
|
||||||
bike_collision_group,
|
bike_collision_group,
|
||||||
|
@ -50,13 +52,12 @@ pub(super) fn spawn_cyberbike(
|
||||||
SleepingDisabled,
|
SleepingDisabled,
|
||||||
CyberBikeBody,
|
CyberBikeBody,
|
||||||
CatControllerState::default(),
|
CatControllerState::default(),
|
||||||
ColliderDensity(0.06),
|
ColliderDensity(20.0),
|
||||||
LinearDamping(0.1),
|
LinearDamping(0.1),
|
||||||
AngularDamping(2.0),
|
AngularDamping(2.0),
|
||||||
LinearVelocity::ZERO,
|
LinearVelocity::ZERO,
|
||||||
AngularVelocity::ZERO,
|
AngularVelocity::ZERO,
|
||||||
ExternalForce::ZERO,
|
ExternalTorque::ZERO.with_persistence(false),
|
||||||
ExternalTorque::ZERO,
|
|
||||||
))
|
))
|
||||||
.with_children(|rider| {
|
.with_children(|rider| {
|
||||||
rider.spawn(SceneBundle {
|
rider.spawn(SceneBundle {
|
||||||
|
|
|
@ -14,10 +14,7 @@ pub struct CyberSteering;
|
||||||
pub struct CyberWheel;
|
pub struct CyberWheel;
|
||||||
|
|
||||||
#[derive(Clone, Debug, Component)]
|
#[derive(Clone, Debug, Component)]
|
||||||
pub struct CyberSpring(pub Vec3);
|
pub struct CyberFork(pub Vec3);
|
||||||
|
|
||||||
#[derive(Clone, Debug, Component)]
|
|
||||||
pub struct CyberFork;
|
|
||||||
|
|
||||||
#[derive(Resource, Reflect)]
|
#[derive(Resource, Reflect)]
|
||||||
#[reflect(Resource)]
|
#[reflect(Resource)]
|
||||||
|
@ -40,15 +37,15 @@ impl Default for WheelConfig {
|
||||||
Self {
|
Self {
|
||||||
front_forward: 0.8,
|
front_forward: 0.8,
|
||||||
rear_back: 1.0,
|
rear_back: 1.0,
|
||||||
y: -0.1,
|
y: -0.5,
|
||||||
limits: [-0.5, 0.1],
|
limits: [-0.5, 0.1],
|
||||||
stiffness: 3.0,
|
stiffness: 3.0,
|
||||||
damping: 8.0,
|
damping: 8.0,
|
||||||
radius: 0.25,
|
radius: 0.40,
|
||||||
thickness: 0.11,
|
thickness: 0.15,
|
||||||
friction: 1.2,
|
friction: 0.9,
|
||||||
restitution: 0.95,
|
restitution: 0.5,
|
||||||
density: 0.05,
|
density: 30.0,
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
use avian3d::prelude::*;
|
use avian3d::prelude::*;
|
||||||
use bevy::prelude::{Torus as Tire, *};
|
use bevy::prelude::*;
|
||||||
|
|
||||||
use super::{CyberFork, CyberSpring, CyberSteering, CyberWheel, Meshterial, WheelConfig};
|
use super::{CyberFork, CyberSteering, CyberWheel, Meshterial, WheelConfig};
|
||||||
use crate::ColliderGroups;
|
use crate::ColliderGroups;
|
||||||
|
|
||||||
pub fn spawn_wheels(
|
pub fn spawn_wheels(
|
||||||
|
@ -11,21 +11,11 @@ pub fn spawn_wheels(
|
||||||
conf: &WheelConfig,
|
conf: &WheelConfig,
|
||||||
meshterials: &mut Meshterial,
|
meshterials: &mut Meshterial,
|
||||||
) {
|
) {
|
||||||
let wheels_collision_group =
|
|
||||||
CollisionLayers::new(ColliderGroups::Wheels, ColliderGroups::Planet);
|
|
||||||
let wheel_y = conf.y;
|
let wheel_y = conf.y;
|
||||||
let not_sleeping = SleepingDisabled;
|
|
||||||
let ccd = SweptCcd::LINEAR.include_dynamic(false);
|
|
||||||
let limits = conf.limits;
|
|
||||||
let (meshes, materials) = meshterials;
|
let (meshes, materials) = meshterials;
|
||||||
let rake_vec: Vec3 = Vec3::new(0.0, 1.0, 0.57).normalize(); // about 30 degrees of rake
|
let rake_vec: Vec3 = Vec3::new(0.0, 1.0, 0.57).normalize(); // about 30 degrees of rake
|
||||||
|
|
||||||
let friction = Friction {
|
|
||||||
dynamic_coefficient: conf.friction,
|
|
||||||
static_coefficient: conf.friction,
|
|
||||||
combine_rule: CoefficientCombine::Average,
|
|
||||||
};
|
|
||||||
|
|
||||||
let mut wheel_poses = Vec::with_capacity(2);
|
let mut wheel_poses = Vec::with_capacity(2);
|
||||||
|
|
||||||
// front
|
// front
|
||||||
|
@ -44,105 +34,34 @@ pub fn spawn_wheels(
|
||||||
wheel_poses.push((offset, None));
|
wheel_poses.push((offset, None));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
let (mesh, collider) = gen_tire(conf);
|
||||||
for (offset, steering) in wheel_poses {
|
for (offset, steering) in wheel_poses {
|
||||||
let (mesh, collider) = gen_tires(conf);
|
let hub = wheels_helper(
|
||||||
|
commands,
|
||||||
|
meshes,
|
||||||
|
materials,
|
||||||
|
offset + xform.translation,
|
||||||
|
mesh.clone(),
|
||||||
|
collider.clone(),
|
||||||
|
conf,
|
||||||
|
);
|
||||||
|
|
||||||
let material = StandardMaterial {
|
let fork = commands
|
||||||
base_color: Color::linear_rgba(0.01, 0.01, 0.01, 1.0),
|
.spawn(FixedJoint::new(hub, bike).with_local_anchor_2(offset))
|
||||||
alpha_mode: AlphaMode::Opaque,
|
|
||||||
perceptual_roughness: 0.5,
|
|
||||||
..Default::default()
|
|
||||||
};
|
|
||||||
|
|
||||||
let pbr_bundle = PbrBundle {
|
|
||||||
material: materials.add(material),
|
|
||||||
mesh: meshes.add(mesh),
|
|
||||||
..Default::default()
|
|
||||||
};
|
|
||||||
|
|
||||||
let suspension_axis = if steering.is_some() {
|
|
||||||
rake_vec
|
|
||||||
} else {
|
|
||||||
Vec3::Y
|
|
||||||
};
|
|
||||||
|
|
||||||
let wheel = commands
|
|
||||||
.spawn(pbr_bundle)
|
|
||||||
.insert((
|
|
||||||
collider,
|
|
||||||
ccd,
|
|
||||||
not_sleeping,
|
|
||||||
wheels_collision_group,
|
|
||||||
friction,
|
|
||||||
CyberWheel,
|
|
||||||
ExternalForce::default(),
|
|
||||||
Restitution::new(conf.restitution),
|
|
||||||
SpatialBundle::default(),
|
|
||||||
RigidBody::Dynamic,
|
|
||||||
ColliderDensity(0.1),
|
|
||||||
CollisionMargin(0.1),
|
|
||||||
AngularVelocity::ZERO,
|
|
||||||
ExternalTorque::ZERO,
|
|
||||||
))
|
|
||||||
.insert(SpatialBundle::from_transform(
|
|
||||||
xform.with_translation(xform.translation + offset),
|
|
||||||
))
|
|
||||||
.id();
|
.id();
|
||||||
|
if let Some(steering) = steering {
|
||||||
let spring = CyberSpring(suspension_axis);
|
let axis = CyberFork(rake_vec);
|
||||||
let axle = if let Some(steering) = steering {
|
commands.entity(fork).insert((steering, axis));
|
||||||
commands.spawn((
|
commands.entity(hub).insert(steering);
|
||||||
RigidBody::Dynamic,
|
|
||||||
ExternalForce::ZERO,
|
|
||||||
steering,
|
|
||||||
spring,
|
|
||||||
MassPropertiesBundle::new_computed(&Collider::sphere(0.1), 0.1),
|
|
||||||
))
|
|
||||||
} else {
|
|
||||||
commands.spawn((
|
|
||||||
RigidBody::Dynamic,
|
|
||||||
ExternalForce::ZERO,
|
|
||||||
spring,
|
|
||||||
MassPropertiesBundle::new_computed(&Collider::sphere(0.1), 0.1),
|
|
||||||
))
|
|
||||||
}
|
}
|
||||||
.insert(SpatialBundle::from_transform(
|
|
||||||
xform.with_translation(xform.translation + offset),
|
|
||||||
))
|
|
||||||
.id();
|
|
||||||
bevy::log::info!("axle RB: {axle:?}");
|
|
||||||
let axel_joint = RevoluteJoint::new(axle, wheel).with_aligned_axis(Vec3::NEG_X);
|
|
||||||
commands.spawn(axel_joint);
|
|
||||||
|
|
||||||
// suspension and steering:
|
|
||||||
if steering.is_some() {
|
|
||||||
let joint = PrismaticJoint::new(axle, bike)
|
|
||||||
.with_free_axis(suspension_axis)
|
|
||||||
.with_local_anchor_1(Vec3::new(0.0, 0.0, 0.1))
|
|
||||||
.with_local_anchor_2(offset)
|
|
||||||
.with_limits(limits[0], limits[1]);
|
|
||||||
commands.spawn((joint, CyberFork));
|
|
||||||
} else {
|
|
||||||
let joint = PrismaticJoint::new(axle, bike)
|
|
||||||
.with_free_axis(suspension_axis)
|
|
||||||
.with_local_anchor_2(offset)
|
|
||||||
.with_limits(limits[0], limits[1]);
|
|
||||||
commands.spawn(joint);
|
|
||||||
};
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// do mesh shit
|
fn gen_tire(conf: &WheelConfig) -> (Mesh, Collider) {
|
||||||
fn gen_tires(conf: &WheelConfig) -> (Mesh, Collider) {
|
let outer_radius = conf.radius;
|
||||||
let wheel_rad = conf.radius;
|
let inner_radius = conf.radius - conf.thickness;
|
||||||
let tire_thickness = conf.thickness;
|
let mut tire_mesh: Mesh = Torus::new(inner_radius, outer_radius).into();
|
||||||
let tire = Tire {
|
let tire_verts = tire_mesh
|
||||||
minor_radius: tire_thickness,
|
|
||||||
major_radius: wheel_rad,
|
|
||||||
};
|
|
||||||
|
|
||||||
let mut mesh = Mesh::from(tire);
|
|
||||||
let tire_verts = mesh
|
|
||||||
.attribute(Mesh::ATTRIBUTE_POSITION)
|
.attribute(Mesh::ATTRIBUTE_POSITION)
|
||||||
.unwrap()
|
.unwrap()
|
||||||
.as_float3()
|
.as_float3()
|
||||||
|
@ -156,15 +75,70 @@ fn gen_tires(conf: &WheelConfig) -> (Mesh, Collider) {
|
||||||
p.to_array()
|
p.to_array()
|
||||||
})
|
})
|
||||||
.collect::<Vec<[f32; 3]>>();
|
.collect::<Vec<[f32; 3]>>();
|
||||||
mesh.remove_attribute(Mesh::ATTRIBUTE_POSITION);
|
tire_mesh.remove_attribute(Mesh::ATTRIBUTE_POSITION);
|
||||||
mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, tire_verts);
|
tire_mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, tire_verts);
|
||||||
|
|
||||||
let mut idxs = Vec::new();
|
let collider = Collider::convex_hull_from_mesh(&tire_mesh).unwrap();
|
||||||
let indices = mesh.indices().unwrap().iter().collect::<Vec<_>>();
|
|
||||||
for idx in indices.as_slice().chunks_exact(3) {
|
|
||||||
idxs.push([idx[0] as u32, idx[1] as u32, idx[2] as u32]);
|
|
||||||
}
|
|
||||||
let wheel_collider = Collider::trimesh_from_mesh(&mesh).unwrap();
|
|
||||||
|
|
||||||
(mesh, wheel_collider)
|
(tire_mesh, collider)
|
||||||
|
}
|
||||||
|
|
||||||
|
fn wheels_helper(
|
||||||
|
commands: &mut Commands,
|
||||||
|
meshes: &mut ResMut<Assets<Mesh>>,
|
||||||
|
materials: &mut ResMut<Assets<StandardMaterial>>,
|
||||||
|
position: Vec3,
|
||||||
|
tire_mesh: Mesh,
|
||||||
|
collider: Collider,
|
||||||
|
conf: &WheelConfig,
|
||||||
|
) -> Entity {
|
||||||
|
let wheel_material = &StandardMaterial {
|
||||||
|
base_color: Color::srgb(0.01, 0.01, 0.01),
|
||||||
|
alpha_mode: AlphaMode::Opaque,
|
||||||
|
perceptual_roughness: 0.5,
|
||||||
|
..Default::default()
|
||||||
|
};
|
||||||
|
|
||||||
|
let xform = Transform::from_translation(position);
|
||||||
|
let hub_mesh: Mesh = Sphere::new(0.1).into();
|
||||||
|
|
||||||
|
let hub = commands
|
||||||
|
.spawn((
|
||||||
|
Name::new("hub"),
|
||||||
|
RigidBody::Dynamic,
|
||||||
|
MassPropertiesBundle::new_computed(&Collider::sphere(0.1), 200.0),
|
||||||
|
PbrBundle {
|
||||||
|
mesh: meshes.add(hub_mesh),
|
||||||
|
material: materials.add(wheel_material.clone()),
|
||||||
|
transform: xform,
|
||||||
|
..Default::default()
|
||||||
|
},
|
||||||
|
))
|
||||||
|
.id();
|
||||||
|
|
||||||
|
let tire = commands
|
||||||
|
.spawn((
|
||||||
|
Name::new("tire"),
|
||||||
|
PbrBundle {
|
||||||
|
mesh: meshes.add(tire_mesh),
|
||||||
|
material: materials.add(wheel_material.clone()),
|
||||||
|
transform: xform,
|
||||||
|
..Default::default()
|
||||||
|
},
|
||||||
|
CyberWheel,
|
||||||
|
RigidBody::Dynamic,
|
||||||
|
collider,
|
||||||
|
Friction::new(conf.friction),
|
||||||
|
Restitution::new(conf.restitution),
|
||||||
|
ColliderDensity(conf.density),
|
||||||
|
CollisionLayers::new(ColliderGroups::Wheels, ColliderGroups::Planet),
|
||||||
|
ExternalTorque::ZERO.with_persistence(false),
|
||||||
|
CollisionMargin(0.05),
|
||||||
|
SweptCcd::NON_LINEAR,
|
||||||
|
))
|
||||||
|
.id();
|
||||||
|
|
||||||
|
// connect hubs and tires to make wheels
|
||||||
|
commands.spawn(RevoluteJoint::new(hub, tire).with_aligned_axis(Vec3::X));
|
||||||
|
hub
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
use bevy::prelude::*;
|
use bevy::prelude::*;
|
||||||
|
|
||||||
use crate::{bike::CyberBikeBody, input::InputState};
|
use crate::{bike::CyberBikeBody, input::InputState, ui::setup_ui};
|
||||||
|
|
||||||
// 85 degrees in radians
|
// 85 degrees in radians
|
||||||
const MAX_PITCH: f32 = 1.48353;
|
const MAX_PITCH: f32 = 1.48353;
|
||||||
|
@ -38,7 +38,7 @@ impl CyberCameras {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
fn setup_cybercams(mut commands: Commands) {
|
fn setup_cybercams(mut commands: Commands, asset_server: Res<AssetServer>) {
|
||||||
let hero_projection = PerspectiveProjection {
|
let hero_projection = PerspectiveProjection {
|
||||||
fov: std::f32::consts::FRAC_PI_3,
|
fov: std::f32::consts::FRAC_PI_3,
|
||||||
..Default::default()
|
..Default::default()
|
||||||
|
@ -55,6 +55,8 @@ fn setup_cybercams(mut commands: Commands) {
|
||||||
commands
|
commands
|
||||||
.spawn(Camera3dBundle::default())
|
.spawn(Camera3dBundle::default())
|
||||||
.insert(CyberCameras::Debug);
|
.insert(CyberCameras::Debug);
|
||||||
|
|
||||||
|
setup_ui(commands, asset_server, id);
|
||||||
}
|
}
|
||||||
|
|
||||||
fn follow_cyberbike(
|
fn follow_cyberbike(
|
||||||
|
@ -85,7 +87,7 @@ fn follow_cyberbike(
|
||||||
cam_xform.rotate(Quat::from_axis_angle(*axis, angle));
|
cam_xform.rotate(Quat::from_axis_angle(*axis, angle));
|
||||||
}
|
}
|
||||||
CyberCameras::Debug => {
|
CyberCameras::Debug => {
|
||||||
let mut ncx = bike_xform.to_owned();
|
let mut ncx = Transform::from_translation(bike_xform.translation);
|
||||||
ncx.rotate(Quat::from_axis_angle(up, offset.rot.to_radians()));
|
ncx.rotate(Quat::from_axis_angle(up, offset.rot.to_radians()));
|
||||||
ncx.translation += ncx.forward() * offset.dist;
|
ncx.translation += ncx.forward() * offset.dist;
|
||||||
ncx.translation += ncx.up() * offset.alt;
|
ncx.translation += ncx.up() * offset.alt;
|
||||||
|
@ -98,12 +100,15 @@ fn follow_cyberbike(
|
||||||
|
|
||||||
fn update_active_camera(
|
fn update_active_camera(
|
||||||
state: Res<State<CyberCameras>>,
|
state: Res<State<CyberCameras>>,
|
||||||
mut query: Query<(&mut Camera, &CyberCameras)>,
|
mut cameras: Query<(Entity, &mut Camera, &CyberCameras)>,
|
||||||
|
mut target: Query<&mut TargetCamera>,
|
||||||
) {
|
) {
|
||||||
|
let mut target = target.single_mut();
|
||||||
// find the camera with the current state, set it as the ActiveCamera
|
// find the camera with the current state, set it as the ActiveCamera
|
||||||
query.iter_mut().for_each(|(mut cam, cyber)| {
|
cameras.iter_mut().for_each(|(ent, mut cam, cyber)| {
|
||||||
if cyber.eq(&state.get()) {
|
if cyber.eq(state.get()) {
|
||||||
cam.is_active = true;
|
cam.is_active = true;
|
||||||
|
*target = TargetCamera(ent);
|
||||||
} else {
|
} else {
|
||||||
cam.is_active = false;
|
cam.is_active = false;
|
||||||
}
|
}
|
||||||
|
|
|
@ -2,7 +2,7 @@ use bevy::{pbr::CascadeShadowConfigBuilder, prelude::*};
|
||||||
|
|
||||||
use crate::planet::PLANET_RADIUS;
|
use crate::planet::PLANET_RADIUS;
|
||||||
|
|
||||||
pub const LIGHT_RANGE: f32 = 90.0;
|
pub const LIGHT_RANGE: f32 = 900.0;
|
||||||
|
|
||||||
static BLUE: Color = Color::linear_rgb(0.0, 0.0, 1.0);
|
static BLUE: Color = Color::linear_rgb(0.0, 0.0, 1.0);
|
||||||
static PINK: Color = Color::linear_rgb(199.0 / 255.0, 21.0 / 255.0, 113.0 / 255.0);
|
static PINK: Color = Color::linear_rgb(199.0 / 255.0, 21.0 / 255.0, 113.0 / 255.0);
|
||||||
|
@ -13,7 +13,7 @@ fn spawn_static_lights(
|
||||||
mut materials: ResMut<Assets<StandardMaterial>>,
|
mut materials: ResMut<Assets<StandardMaterial>>,
|
||||||
) {
|
) {
|
||||||
let pink_light = PointLight {
|
let pink_light = PointLight {
|
||||||
intensity: 1_00.0,
|
intensity: 1_000_000.0,
|
||||||
range: LIGHT_RANGE,
|
range: LIGHT_RANGE,
|
||||||
color: PINK,
|
color: PINK,
|
||||||
radius: 1.0,
|
radius: 1.0,
|
||||||
|
@ -22,7 +22,7 @@ fn spawn_static_lights(
|
||||||
};
|
};
|
||||||
|
|
||||||
let blue_light = PointLight {
|
let blue_light = PointLight {
|
||||||
intensity: 1_000.0,
|
intensity: 1_000_000.0,
|
||||||
range: LIGHT_RANGE,
|
range: LIGHT_RANGE,
|
||||||
color: BLUE,
|
color: BLUE,
|
||||||
radius: 1.0,
|
radius: 1.0,
|
||||||
|
@ -32,7 +32,7 @@ fn spawn_static_lights(
|
||||||
|
|
||||||
commands.insert_resource(AmbientLight {
|
commands.insert_resource(AmbientLight {
|
||||||
color: Color::WHITE,
|
color: Color::WHITE,
|
||||||
brightness: 10_000.0,
|
brightness: 8_000.0,
|
||||||
});
|
});
|
||||||
|
|
||||||
let _cascade_shadow_config = CascadeShadowConfigBuilder {
|
let _cascade_shadow_config = CascadeShadowConfigBuilder {
|
||||||
|
|
|
@ -25,8 +25,9 @@ fn spawn_planet(
|
||||||
let pcollide = (
|
let pcollide = (
|
||||||
shape,
|
shape,
|
||||||
Friction {
|
Friction {
|
||||||
static_coefficient: 1.2,
|
static_coefficient: 0.8,
|
||||||
..Default::default()
|
dynamic_coefficient: 0.5,
|
||||||
|
combine_rule: CoefficientCombine::Average,
|
||||||
},
|
},
|
||||||
Restitution::new(0.8),
|
Restitution::new(0.8),
|
||||||
);
|
);
|
||||||
|
@ -136,7 +137,6 @@ fn gen_planet(radius: f32) -> (Mesh, Collider) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
dbg!(&colors.len());
|
|
||||||
mesh.insert_attribute(Mesh::ATTRIBUTE_COLOR, colors);
|
mesh.insert_attribute(Mesh::ATTRIBUTE_COLOR, colors);
|
||||||
|
|
||||||
(mesh, collider)
|
(mesh, collider)
|
||||||
|
|
17
src/ui.rs
17
src/ui.rs
|
@ -1,9 +1,9 @@
|
||||||
use avian3d::prelude::LinearVelocity;
|
use avian3d::prelude::LinearVelocity;
|
||||||
use bevy::{
|
use bevy::{
|
||||||
app::{Startup, Update},
|
app::Update,
|
||||||
prelude::{
|
prelude::{
|
||||||
AlignSelf, App, AssetServer, Color, Commands, Component, Plugin, Query, Res, Style, Text,
|
AlignSelf, App, AssetServer, Color, Commands, Component, Entity, Plugin, Query, Res, Style,
|
||||||
TextBundle, TextSection, TextStyle, With,
|
Text, TextBundle, TextSection, TextStyle, With,
|
||||||
},
|
},
|
||||||
ui::TargetCamera,
|
ui::TargetCamera,
|
||||||
};
|
};
|
||||||
|
@ -13,7 +13,11 @@ use crate::bike::CyberBikeBody;
|
||||||
#[derive(Component)]
|
#[derive(Component)]
|
||||||
struct UpText;
|
struct UpText;
|
||||||
|
|
||||||
fn setup_ui(mut commands: Commands, asset_server: Res<AssetServer>) {
|
pub(crate) fn setup_ui(
|
||||||
|
mut commands: Commands,
|
||||||
|
asset_server: Res<AssetServer>,
|
||||||
|
target_camera: Entity,
|
||||||
|
) {
|
||||||
commands
|
commands
|
||||||
.spawn(TextBundle {
|
.spawn(TextBundle {
|
||||||
style: Style {
|
style: Style {
|
||||||
|
@ -35,7 +39,7 @@ fn setup_ui(mut commands: Commands, asset_server: Res<AssetServer>) {
|
||||||
},
|
},
|
||||||
..Default::default()
|
..Default::default()
|
||||||
})
|
})
|
||||||
.insert(UpText);
|
.insert((UpText, TargetCamera(target_camera)));
|
||||||
}
|
}
|
||||||
|
|
||||||
fn update_ui(
|
fn update_ui(
|
||||||
|
@ -52,7 +56,6 @@ pub struct CyberUIPlugin;
|
||||||
|
|
||||||
impl Plugin for CyberUIPlugin {
|
impl Plugin for CyberUIPlugin {
|
||||||
fn build(&self, app: &mut App) {
|
fn build(&self, app: &mut App) {
|
||||||
app.add_systems(Startup, setup_ui)
|
app.add_systems(Update, update_ui);
|
||||||
.add_systems(Update, update_ui);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in a new issue