Compare commits

...

3 Commits

Author SHA1 Message Date
Joe Ardent ecfa9b5864 ready to enable input 2024-07-25 15:49:10 -07:00
Joe Ardent 85fe12bd3f checkpoint 2024-07-22 14:35:05 -07:00
Joe Ardent dd65741d7b checkpoint 2024-07-18 14:55:09 -07:00
13 changed files with 195 additions and 261 deletions

View File

@ -37,7 +37,7 @@ impl Default for MovementSettings {
fn default() -> Self {
Self {
accel: 20.0,
gravity: 4.8,
gravity: 9.8,
}
}
}
@ -53,9 +53,9 @@ pub struct CatControllerSettings {
impl Default for CatControllerSettings {
fn default() -> Self {
Self {
kp: 80.0,
kp: 1200.0,
kd: 10.0,
ki: 0.4,
ki: 50.0,
}
}
}

View File

@ -1,6 +1,6 @@
use avian3d::prelude::{PhysicsPlugins, SubstepCount};
use bevy::{
app::Update,
app::FixedUpdate,
diagnostic::FrameTimeDiagnosticsPlugin,
ecs::reflect::ReflectResource,
prelude::{App, IntoSystemConfigs, Plugin, Resource},
@ -29,15 +29,10 @@ impl Plugin for CyberActionPlugin {
.register_type::<CyberLean>()
.register_type::<CatControllerSettings>()
.add_plugins((PhysicsPlugins::default(), FrameTimeDiagnosticsPlugin))
.insert_resource(SubstepCount(24))
.insert_resource(SubstepCount(12))
.add_systems(
Update,
(
gravity,
#[cfg(feature = "inspector")]
debug_bodies,
(cyber_lean, suspension, falling_cat, input_forces).after(clear_forces),
),
FixedUpdate,
(set_gravity, calculate_lean, apply_lean).chain(),
);
}
}

View File

@ -2,18 +2,15 @@ use std::f32::consts::{FRAC_PI_3, FRAC_PI_4};
use avian3d::{
dynamics::solver::xpbd::AngularConstraint,
prelude::{
ColliderMassProperties, ExternalForce, ExternalTorque, Gravity, LinearVelocity,
PrismaticJoint, RigidBodyQuery,
},
prelude::{ExternalTorque, FixedJoint, Gravity, LinearVelocity, RigidBodyQuery},
};
#[cfg(feature = "inspector")]
use bevy::prelude::Entity;
use bevy::prelude::Gizmos;
use bevy::prelude::{Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without};
use super::{CatControllerSettings, CatControllerState, CyberLean, MovementSettings};
use crate::{
bike::{CyberBikeBody, CyberFork, CyberSpring, CyberSteering, CyberWheel, WheelConfig},
bike::{CyberBikeBody, CyberFork, CyberSteering, CyberWheel},
input::InputState,
};
@ -38,47 +35,17 @@ fn rotate_point(pt: &Vec3, rot: &Quat) -> Vec3 {
}
/// The gravity vector points from the cyberbike to the center of the planet.
pub(super) fn gravity(
pub(super) fn set_gravity(
xform: Query<&Transform, With<CyberBikeBody>>,
settings: Res<MovementSettings>,
mut gravity: ResMut<Gravity>,
) {
let xform = xform.single();
*gravity = Gravity(xform.translation.normalize() * -settings.gravity);
// clear all external forces
}
pub(super) fn clear_forces(mut forces: Query<(&mut ExternalForce, &mut ExternalTorque)>) {
for (mut force, mut torque) in forces.iter_mut() {
force.clear();
torque.clear();
}
}
pub(super) fn suspension(
movment_settings: Res<MovementSettings>,
wheel_config: Res<WheelConfig>,
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 gravity = movment_settings.gravity;
let mag = -wheel_config.stiffness * mass * gravity;
for (mut force, spring, xform) in axels.iter_mut() {
let spring = mag * spring.0;
let spring = xform.translation + spring;
let _ = force.apply_force(spring);
}
}
/// The desired lean angle, given steering input and speed.
pub(super) fn cyber_lean(
pub(super) fn calculate_lean(
bike_state: Query<(&LinearVelocity, &Transform), With<CyberBikeBody>>,
wheels: Query<&Transform, With<CyberWheel>>,
input: Res<InputState>,
@ -96,7 +63,7 @@ pub(super) fn cyber_lean(
let v2_r = v_squared / radius;
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);
} else {
lean.lean = 0.0;
@ -104,11 +71,12 @@ pub(super) fn cyber_lean(
}
/// PID-based controller for stabilizing attitude; keeps the cyberbike upright.
pub(super) fn falling_cat(
pub(super) fn apply_lean(
mut bike_query: Query<(&Transform, &mut ExternalTorque, &mut CatControllerState)>,
time: Res<Time>,
settings: Res<CatControllerSettings>,
lean: Res<CyberLean>,
#[cfg(feature = "inspector")] mut gizmos: Gizmos,
) {
let (xform, mut torque, mut control_vars) = bike_query.single_mut();
let world_up = xform.translation.normalize();
@ -125,73 +93,53 @@ pub(super) fn falling_cat(
let (derivative, integral) = control_vars.update_roll(roll_error, time.delta_seconds());
let mag =
(settings.kp * roll_error) + (settings.ki * integral) + (settings.kd * derivative);
if mag.is_finite() {
torque.apply_torque(*xform.back() * mag);
if mag.is_normal() {
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,
);
}
}
}
/// Apply forces to the cyberbike as a result of input.
pub(super) fn input_forces(
pub(super) fn apply_inputs(
settings: Res<MovementSettings>,
input: Res<InputState>,
time: Res<Time>,
fork: Query<&PrismaticJoint, With<CyberFork>>,
mut axle: Query<(RigidBodyQuery, &Transform), With<CyberSteering>>,
mut braking_query: Query<&mut ExternalTorque, With<CyberWheel>>,
mut body_query: Query<
(
RigidBodyQuery,
&Transform,
&ColliderMassProperties,
&mut ExternalForce,
),
(With<CyberBikeBody>, Without<CyberSteering>),
>,
fork: Query<(&FixedJoint, &CyberFork), With<CyberSteering>>,
mut hub: Query<(RigidBodyQuery, &Transform), With<CyberSteering>>,
mut braking_query: Query<(&Transform, &mut ExternalTorque), With<CyberWheel>>,
mut body_query: Query<RigidBodyQuery, (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");
return;
};
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
for mut motor in braking_query.iter_mut() {
let factor = if input.brake {
500.00
} else {
input.throttle * settings.accel
};
let speed = if input.brake { 0.0 } else { -70.0 };
let target = dt * factor * speed;
let torque = target * Vec3::X;
for (xform, mut motor) in braking_query.iter_mut() {
let factor = input.throttle * settings.accel;
let target = dt * factor;
let torque = target * *xform.right();
motor.apply_torque(torque);
}
// steering
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 fork = fork.single();
let axis = fork.free_axis.normalize();
let new = Quat::from_axis_angle(axis, _angle);
let (fork, CyberFork(axis)) = fork.single();
let new = Quat::from_axis_angle(*axis, _angle);
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);
}
#[cfg(feature = "inspector")]
pub(super) fn debug_bodies(bodies: Query<(Entity, RigidBodyQuery)>) {
for (entity, rbq) in bodies.iter().filter(|(_, r)| r.rb.is_dynamic()) {
let line = format!("{entity:?} at {:?}", rbq.current_position());
bevy::log::info!(line);
}
fork.align_orientation(&mut axle, &mut bike, diff, &mut lagrange, 0.0, dt);
}

View File

@ -1,11 +1,12 @@
use avian3d::prelude::*;
use bevy::{
core::Name,
prelude::{AssetServer, BuildChildren, Commands, Quat, Res, SpatialBundle, Transform, Vec3},
scene::SceneBundle,
};
use super::{spawn_wheels, CyberBikeBody, Meshterial, WheelConfig, BIKE_BODY_COLLISION_GROUP};
use crate::{action::CatControllerState, planet::PLANET_RADIUS};
use super::{spawn_wheels, CyberBikeBody, Meshterial, WheelConfig};
use crate::{action::CatControllerState, planet::PLANET_RADIUS, ColliderGroups};
pub(super) fn spawn_cyberbike(
mut commands: Commands,
@ -32,8 +33,8 @@ pub(super) fn spawn_cyberbike(
..Default::default()
};
let (membership, filter) = BIKE_BODY_COLLISION_GROUP;
let bike_collision_group = CollisionLayers::new(membership, filter);
let bike_collision_group =
CollisionLayers::new(ColliderGroups::BikeBody, ColliderGroups::Planet);
let scene = asset_server.load("cb-no-y_up.glb#Scene0");
@ -42,6 +43,7 @@ pub(super) fn spawn_cyberbike(
let bike = commands
.spawn(SpatialBundle::from_transform(xform))
.insert((
Name::new("bike body"),
RigidBody::Dynamic,
body_collider,
bike_collision_group,
@ -50,13 +52,12 @@ pub(super) fn spawn_cyberbike(
SleepingDisabled,
CyberBikeBody,
CatControllerState::default(),
ColliderDensity(0.6),
ColliderDensity(20.0),
LinearDamping(0.1),
AngularDamping(2.0),
LinearVelocity::ZERO,
AngularVelocity::ZERO,
ExternalForce::ZERO,
ExternalTorque::ZERO,
ExternalTorque::ZERO.with_persistence(false),
))
.with_children(|rider| {
rider.spawn(SceneBundle {
@ -66,5 +67,7 @@ pub(super) fn spawn_cyberbike(
})
.id();
bevy::log::info!("bike body: {bike:?}");
spawn_wheels(&mut commands, bike, &xform, &wheel_conf, &mut meshterials);
}

View File

@ -14,10 +14,7 @@ pub struct CyberSteering;
pub struct CyberWheel;
#[derive(Clone, Debug, Component)]
pub struct CyberSpring(pub Vec3);
#[derive(Clone, Debug, Component)]
pub struct CyberFork;
pub struct CyberFork(pub Vec3);
#[derive(Resource, Reflect)]
#[reflect(Resource)]
@ -40,15 +37,15 @@ impl Default for WheelConfig {
Self {
front_forward: 0.8,
rear_back: 1.0,
y: -0.1,
y: -0.5,
limits: [-0.5, 0.1],
stiffness: 3.0,
damping: 8.0,
radius: 0.25,
thickness: 0.11,
friction: 1.2,
restitution: 0.95,
density: 0.05,
radius: 0.40,
thickness: 0.15,
friction: 0.9,
restitution: 0.5,
density: 30.0,
}
}
}

View File

@ -10,8 +10,8 @@ use bevy::{
pub(crate) use self::components::*;
use self::{body::spawn_cyberbike, wheels::spawn_wheels};
pub const BIKE_BODY_COLLISION_GROUP: (u32, u32) = (0b01, 0b01);
pub const BIKE_WHEEL_COLLISION_GROUP: (u32, u32) = (0b10, 0b10);
pub const BIKE_BODY_COLLISION_GROUP: (u32, u32) = (1, 1);
pub const BIKE_WHEEL_COLLISION_GROUP: (u32, u32) = (2, 2);
type Meshterial<'a> = (
ResMut<'a, Assets<Mesh>>,

View File

@ -1,10 +1,8 @@
use avian3d::prelude::*;
use bevy::prelude::{Torus as Tire, *};
use bevy::prelude::*;
use super::{
CyberFork, CyberSpring, CyberSteering, CyberWheel, Meshterial, WheelConfig,
BIKE_WHEEL_COLLISION_GROUP,
};
use super::{CyberFork, CyberSteering, CyberWheel, Meshterial, WheelConfig};
use crate::ColliderGroups;
pub fn spawn_wheels(
commands: &mut Commands,
@ -13,21 +11,11 @@ pub fn spawn_wheels(
conf: &WheelConfig,
meshterials: &mut Meshterial,
) {
let (membership, filter) = BIKE_WHEEL_COLLISION_GROUP;
let wheels_collision_group = CollisionLayers::new(membership, filter);
let wheel_y = conf.y;
let not_sleeping = SleepingDisabled;
let ccd = SweptCcd::NON_LINEAR.include_dynamic(false);
let limits = conf.limits;
let (meshes, materials) = meshterials;
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);
// front
@ -46,107 +34,34 @@ pub fn spawn_wheels(
wheel_poses.push((offset, None));
}
let (mesh, collider) = gen_tire(conf);
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 {
base_color: Color::linear_rgba(0.01, 0.01, 0.01, 1.0),
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),
AngularVelocity::ZERO,
ExternalTorque::ZERO,
))
.insert(SpatialBundle::from_transform(
xform.with_translation(xform.translation + offset),
))
let fork = commands
.spawn(FixedJoint::new(hub, bike).with_local_anchor_2(offset))
.id();
let spring = CyberSpring(suspension_axis);
let axel = if let Some(steering) = steering {
commands.spawn((
RigidBody::Dynamic,
ExternalForce::ZERO,
steering,
spring,
Collider::sphere(0.1),
ColliderDensity(0.1),
CollisionLayers::from_bits(0, 0),
))
} else {
commands.spawn((
RigidBody::Dynamic,
ExternalForce::ZERO,
spring,
Collider::sphere(0.1),
ColliderDensity(0.1),
CollisionLayers::from_bits(0, 0),
))
if let Some(steering) = steering {
let axis = CyberFork(rake_vec);
commands.entity(fork).insert((steering, axis));
commands.entity(hub).insert(steering);
}
.insert(SpatialBundle::from_transform(
xform.with_translation(xform.translation + offset),
))
.id();
let axel_joint = RevoluteJoint::new(axel, wheel).with_aligned_axis(Vec3::NEG_X);
commands.spawn(axel_joint);
// suspension and steering:
if steering.is_some() {
let joint = PrismaticJoint::new(axel, 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(axel, 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_tires(conf: &WheelConfig) -> (Mesh, Collider) {
let wheel_rad = conf.radius;
let tire_thickness = conf.thickness;
let tire = Tire {
minor_radius: tire_thickness,
major_radius: wheel_rad,
};
let mut mesh = Mesh::from(tire);
let tire_verts = mesh
fn gen_tire(conf: &WheelConfig) -> (Mesh, Collider) {
let outer_radius = conf.radius;
let inner_radius = conf.radius - conf.thickness;
let mut tire_mesh: Mesh = Torus::new(inner_radius, outer_radius).into();
let tire_verts = tire_mesh
.attribute(Mesh::ATTRIBUTE_POSITION)
.unwrap()
.as_float3()
@ -160,15 +75,70 @@ fn gen_tires(conf: &WheelConfig) -> (Mesh, Collider) {
p.to_array()
})
.collect::<Vec<[f32; 3]>>();
mesh.remove_attribute(Mesh::ATTRIBUTE_POSITION);
mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, tire_verts);
tire_mesh.remove_attribute(Mesh::ATTRIBUTE_POSITION);
tire_mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, tire_verts);
let mut idxs = Vec::new();
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::convex_decomposition_from_mesh(&mesh).unwrap();
let collider = Collider::convex_hull_from_mesh(&tire_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
}

View File

@ -1,6 +1,6 @@
use bevy::prelude::*;
use crate::{bike::CyberBikeBody, input::InputState};
use crate::{bike::CyberBikeBody, input::InputState, ui::setup_ui};
// 85 degrees in radians
const MAX_PITCH: f32 = 1.48353;
@ -38,22 +38,25 @@ impl CyberCameras {
}
}
fn setup_cybercams(mut commands: Commands) {
fn setup_cybercams(mut commands: Commands, asset_server: Res<AssetServer>) {
let hero_projection = PerspectiveProjection {
fov: std::f32::consts::FRAC_PI_3,
..Default::default()
};
commands
let id = commands
.spawn(Camera3dBundle {
projection: bevy::render::camera::Projection::Perspective(hero_projection),
..Default::default()
})
.insert(CyberCameras::Hero);
.insert(CyberCameras::Hero)
.id();
commands
.spawn(Camera3dBundle::default())
.insert(CyberCameras::Debug);
setup_ui(commands, asset_server, id);
}
fn follow_cyberbike(
@ -84,7 +87,7 @@ fn follow_cyberbike(
cam_xform.rotate(Quat::from_axis_angle(*axis, angle));
}
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.translation += ncx.forward() * offset.dist;
ncx.translation += ncx.up() * offset.alt;
@ -97,12 +100,15 @@ fn follow_cyberbike(
fn update_active_camera(
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
query.iter_mut().for_each(|(mut cam, cyber)| {
if cyber.eq(&state.get()) {
cameras.iter_mut().for_each(|(ent, mut cam, cyber)| {
if cyber.eq(state.get()) {
cam.is_active = true;
*target = TargetCamera(ent);
} else {
cam.is_active = false;
}

View File

@ -2,6 +2,7 @@ use avian3d::debug_render::PhysicsGizmos;
use bevy::{
color::Srgba,
gizmos::AppGizmoBuilder,
math::Vec3,
prelude::{App, Color, GizmoConfig, Plugin},
};
@ -20,6 +21,8 @@ impl Plugin for CyberGlamorPlugin {
PhysicsGizmos {
contact_point_color: Some(Srgba::GREEN.into()),
contact_normal_color: Some(Srgba::WHITE.into()),
hide_meshes: true,
axis_lengths: Some(Vec3::ZERO),
..Default::default()
},
GizmoConfig::default(),

View File

@ -1,3 +1,4 @@
use avian3d::prelude::PhysicsLayer;
use bevy::{
prelude::{Query, Vec3, Window, With},
window::PrimaryWindow,
@ -12,6 +13,13 @@ pub mod lights;
pub mod planet;
pub mod ui;
#[derive(PhysicsLayer)]
pub enum ColliderGroups {
BikeBody,
Wheels,
Planet,
}
pub fn disable_mouse_trap(mut window: Query<&mut Window, With<PrimaryWindow>>) {
let mut window = window.get_single_mut().unwrap();
window.cursor.grab_mode = bevy::window::CursorGrabMode::None;

View File

@ -2,7 +2,7 @@ use bevy::{pbr::CascadeShadowConfigBuilder, prelude::*};
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 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>>,
) {
let pink_light = PointLight {
intensity: 1_00.0,
intensity: 1_000_000.0,
range: LIGHT_RANGE,
color: PINK,
radius: 1.0,
@ -22,7 +22,7 @@ fn spawn_static_lights(
};
let blue_light = PointLight {
intensity: 1_000.0,
intensity: 1_000_000.0,
range: LIGHT_RANGE,
color: BLUE,
radius: 1.0,
@ -32,7 +32,7 @@ fn spawn_static_lights(
commands.insert_resource(AmbientLight {
color: Color::WHITE,
brightness: 0.2,
brightness: 8_000.0,
});
let _cascade_shadow_config = CascadeShadowConfigBuilder {

View File

@ -25,8 +25,9 @@ fn spawn_planet(
let pcollide = (
shape,
Friction {
static_coefficient: 1.2,
..Default::default()
static_coefficient: 0.8,
dynamic_coefficient: 0.5,
combine_rule: CoefficientCombine::Average,
},
Restitution::new(0.8),
);
@ -41,7 +42,7 @@ fn spawn_planet(
RigidBody::Static,
pcollide,
CyberPlanet,
CollisionLayers::new(u32::MAX, u32::MAX),
CollisionLayers::new(LayerMask::ALL, LayerMask::ALL),
CollisionMargin(0.2),
));
}
@ -136,7 +137,6 @@ fn gen_planet(radius: f32) -> (Mesh, Collider) {
}
}
dbg!(&colors.len());
mesh.insert_attribute(Mesh::ATTRIBUTE_COLOR, colors);
(mesh, collider)

View File

@ -1,10 +1,11 @@
use avian3d::prelude::LinearVelocity;
use bevy::{
app::{Startup, Update},
app::Update,
prelude::{
AlignSelf, App, AssetServer, Color, Commands, Component, Plugin, Query, Res, Style, Text,
TextBundle, TextSection, TextStyle, Transform, With,
AlignSelf, App, AssetServer, Color, Commands, Component, Entity, Plugin, Query, Res, Style,
Text, TextBundle, TextSection, TextStyle, With,
},
ui::TargetCamera,
};
use crate::bike::CyberBikeBody;
@ -12,7 +13,11 @@ use crate::bike::CyberBikeBody;
#[derive(Component)]
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
.spawn(TextBundle {
style: Style {
@ -34,16 +39,16 @@ fn setup_ui(mut commands: Commands, asset_server: Res<AssetServer>) {
},
..Default::default()
})
.insert(UpText);
.insert((UpText, TargetCamera(target_camera)));
}
fn update_ui(
state_query: Query<(&LinearVelocity, &Transform), With<CyberBikeBody>>,
state_query: Query<&LinearVelocity, With<CyberBikeBody>>,
mut text_query: Query<&mut Text, With<UpText>>,
) {
let mut text = text_query.single_mut();
let (velocity, xform) = state_query.single();
let speed = velocity.dot(*xform.forward());
let velocity = state_query.single();
let speed = velocity.0.length();
text.sections[0].value = format!("spd: {:.2}", speed);
}
@ -51,7 +56,6 @@ pub struct CyberUIPlugin;
impl Plugin for CyberUIPlugin {
fn build(&self, app: &mut App) {
app.add_systems(Startup, setup_ui)
.add_systems(Update, update_ui);
app.add_systems(Update, update_ui);
}
}