Compare commits

..

No commits in common. "ff9b1671b15ef0a94fff057d9841864891f41129" and "5a57779261a51c63ed095e6dcbb94f66c14fdada" have entirely different histories.

17 changed files with 1495 additions and 2545 deletions

3090
Cargo.lock generated

File diff suppressed because it is too large Load Diff

View File

@ -7,15 +7,15 @@ edition = "2021"
rand = "0.8"
# bevy_polyline = "0.4"
noise = { git = "https://github.com/Razaekel/noise-rs" }
hexasphere = "8"
wgpu = "0.19"
bevy-inspector-egui = "0.24"
hexasphere = "7"
wgpu = "0.15"
bevy-inspector-egui = "0.18"
[features]
inspector = []
[dependencies.bevy]
version = "0.13"
version = "0.10"
default-features = false
features = [
"bevy_gilrs",
@ -27,12 +27,11 @@ features = [
"bevy_text",
"bevy_gltf",
"bevy_sprite",
"tonemapping_luts"
]
[dependencies.bevy_rapier3d]
features = ["debug-render-3d"]
version = "0.26"
version = "0.21"
# Maybe also enable only a small amount of optimization for our code:
[profile.dev]

View File

@ -4,7 +4,6 @@ use bevy::{
prelude::{Component, ReflectResource, Resource, Vec3},
reflect::Reflect,
};
use bevy_rapier3d::dynamics::Velocity;
#[derive(Debug, Resource)]
pub(crate) struct ActionDebugInstant(pub Instant);
@ -27,8 +26,20 @@ impl ActionDebugInstant {
}
}
#[derive(Debug, Component, Default)]
pub struct PreviousVelocity(pub Velocity);
#[derive(Debug, Component)]
pub(super) struct Tunneling {
pub frames: usize,
pub dir: Vec3,
}
impl Default for Tunneling {
fn default() -> Self {
Tunneling {
frames: 15,
dir: Vec3::ZERO,
}
}
}
#[derive(Debug, Resource, Reflect)]
#[reflect(Resource)]

View File

@ -1,7 +1,7 @@
use bevy::{
diagnostic::FrameTimeDiagnosticsPlugin,
ecs::reflect::ReflectResource,
prelude::{App, IntoSystemConfigs, Plugin, Resource, Startup, Update},
prelude::{App, IntoSystemConfigs, Plugin, Resource},
reflect::Reflect,
};
use bevy_rapier3d::prelude::{NoUserData, RapierPhysicsPlugin};
@ -28,18 +28,18 @@ impl Plugin for CyberActionPlugin {
.init_resource::<CyberLean>()
.register_type::<CyberLean>()
.register_type::<CatControllerSettings>()
.add_plugins(RapierPhysicsPlugin::<NoUserData>::default())
.add_systems(Startup, physics_init)
.add_plugins(FrameTimeDiagnosticsPlugin)
.add_plugin(RapierPhysicsPlugin::<NoUserData>::default())
.add_startup_system(timestep_setup)
.add_plugin(FrameTimeDiagnosticsPlugin::default())
.add_systems(
Update,
(
reset_body_force,
reset_wheel_forces,
gravity,
cyber_lean,
falling_cat,
input_forces,
drag,
tunnel_out,
surface_fix,
)
.chain(),
);

View File

@ -1,217 +1,21 @@
use std::f32::consts::{FRAC_PI_3, FRAC_PI_4};
use bevy::prelude::{
Commands, Entity, Local, Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without,
Commands, Entity, Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without,
};
use bevy_rapier3d::{
dynamics::MassProperties,
prelude::{
use bevy_rapier3d::prelude::{
CollisionGroups, ExternalForce, Group, MultibodyJoint, QueryFilter, RapierConfiguration,
RapierContext, ReadMassProperties, TimestepMode, Velocity,
},
};
#[cfg(feature = "inspector")]
use super::ActionDebugInstant;
use super::{
CatControllerSettings, CatControllerState, CyberLean, MovementSettings, PreviousVelocity,
};
use super::{CatControllerSettings, CatControllerState, CyberLean, MovementSettings, Tunneling};
use crate::{
bike::{CyberBikeBody, CyberSteering, CyberWheel, WheelConfig, BIKE_WHEEL_COLLISION_GROUP},
input::InputState,
};
pub(super) fn physics_init(
mut config: ResMut<RapierConfiguration>,
settings: Res<MovementSettings>,
) {
config.timestep_mode = TimestepMode::Variable {
max_dt: 1.0 / 60.0,
time_scale: 1.0,
substeps: 3,
};
config.gravity = Vec3::NEG_Y * settings.gravity;
}
pub(super) fn reset_body_force(
mut query: Query<&mut ExternalForce, With<CyberBikeBody>>,
#[cfg(feature = "inspector")] mut debug_instant: ResMut<ActionDebugInstant>,
) {
let mut body_force = query.single_mut();
#[cfg(feature = "inspector")]
{
if debug_instant.elapsed().as_millis() > 1000 {
//dbg!(&body_force);
debug_instant.reset();
}
}
body_force.force = Vec3::ZERO;
body_force.torque = Vec3::ZERO;
}
pub(super) fn reset_wheel_forces(mut query: Query<&mut ExternalForce, With<CyberWheel>>) {
for mut force in query.iter_mut() {
force.force = Vec3::ZERO;
force.torque = Vec3::ZERO;
}
}
/// The desired lean angle, given steering input and speed.
pub(super) fn cyber_lean(
bike_state: Query<(&Velocity, &Transform), With<CyberBikeBody>>,
wheels: Query<&Transform, With<CyberWheel>>,
input: Res<InputState>,
gravity_settings: Res<MovementSettings>,
mut lean: ResMut<CyberLean>,
) {
let (velocity, xform) = bike_state.single();
let vel = velocity.linvel.dot(*xform.forward());
let v_squared = vel.powi(2);
let steering_angle = yaw_to_angle(input.yaw);
let wheels: Vec<_> = wheels.iter().map(|w| w.translation).collect();
let wheel_base = (wheels[0] - wheels[1]).length();
let radius = wheel_base / steering_angle.tan();
let gravity = gravity_settings.gravity;
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() {
lean.lean = tan_theta.atan().clamp(-FRAC_PI_4, FRAC_PI_4);
} else {
lean.lean = 0.0;
}
}
/// PID-based controller for stabilizing attitude; keeps the cyberbike upright.
pub(super) fn falling_cat(
mut bike_query: Query<(
&Transform,
&Velocity,
&mut ExternalForce,
&mut CatControllerState,
)>,
time: Res<Time>,
settings: Res<CatControllerSettings>,
lean: Res<CyberLean>,
mut count: Local<usize>,
) {
let (xform, vel, mut forces, mut control_vars) = bike_query.single_mut();
let world_up = Vec3::Y; //xform.translation.normalize();
let rot = Quat::from_axis_angle(*xform.back(), lean.lean);
let target_up = rotate_point(&world_up, &rot).normalize();
let bike_right = xform.right();
let roll_error = bike_right.dot(target_up);
let pitch_error = world_up.dot(*xform.back());
if *count < 30 {
if *count == 0 {
//dbg!(&xform.translation);
//dbg!(&vel.linvel);
}
*count += 1;
} else {
*count = 0;
}
// only try to correct roll if we're not totally vertical
if pitch_error.abs() < 0.95 {
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() {
forces.torque += xform.back() * mag;
}
}
}
pub(super) fn wheel_forces(
mut wheels_query: Query<
(
&Transform,
&Velocity,
&mut PreviousVelocity,
Option<&CyberSteering>,
),
With<CyberWheel>,
>,
mut body_query: Query<
(
&Transform,
&Velocity,
&mut PreviousVelocity,
&ReadMassProperties,
),
With<CyberBikeBody>,
>,
wheel_config: Res<WheelConfig>,
rapier_config: Res<RapierConfiguration>,
context: Res<RapierContext>,
settings: Res<MovementSettings>,
input: Res<InputState>,
) {
let (body_xform, body_vel, mut body_pvel, body_mass) = body_query.single_mut();
let gvec = rapier_config.gravity;
// body kinematics
let body_lin_accel = body_vel.linvel - body_pvel.0.linvel;
let body_ang_accel = body_vel.angvel - body_pvel.0.angvel;
let mut body_forward = body_vel
.linvel
.try_normalize()
.unwrap_or_else(|| body_xform.forward().normalize());
// we're just projecting onto the ground, so nuke the Y.
body_forward.y = 0.0;
let body_half_mass = body_mass.mass * 0.5;
let g = gvec * settings.gravity * body_half_mass;
// inputs
let steering_angle = yaw_to_angle(input.yaw);
let throttle = input.throttle * settings.accel;
for (xform, vel, mut pvel, steering) in wheels_query.iter_mut() {
if let Some((_, projected)) =
context.project_point(xform.translation, true, QueryFilter::only_fixed())
{
let normal = -(projected.point - xform.translation);
let len = normal.length();
let normal = normal.normalize();
if len < wheel_config.radius {
// we're in contact
// do gravity's share
// do linear acceleration's share
// do friction's share
// do thrust's share
// do steering's share
}
}
}
body_pvel.0 = *body_vel;
}
/// General velocity-based drag-force calculation; does not take orientation
/// into account.
pub(super) fn drag(mut query: Query<(&Velocity, &mut ExternalForce), With<CyberBikeBody>>) {
let (vels, mut forces) = query.single_mut();
if let Some(vel) = vels.linvel.try_normalize() {
let v2 = vels.linvel.length_squared();
forces.force -= vel * (v2 * 0.02);
}
}
// helpers
fn yaw_to_angle(yaw: f32) -> f32 {
let v = yaw.powi(5) * FRAC_PI_4;
if v.is_normal() {
@ -231,3 +35,211 @@ fn rotate_point(pt: &Vec3, rot: &Quat) -> Vec3 {
// why does this need to be inverted???
-Vec3::from_array([rot_qpt.x, rot_qpt.y, rot_qpt.z])
}
pub(super) fn timestep_setup(mut config: ResMut<RapierConfiguration>) {
let ts = TimestepMode::Fixed {
dt: 1.0 / 60.0,
substeps: 2,
};
config.timestep_mode = ts;
}
/// The gravity vector points from the cyberbike to the center of the planet.
pub(super) fn gravity(
mut query: Query<(&Transform, &mut ExternalForce), With<CyberBikeBody>>,
settings: Res<MovementSettings>,
mut rapier_config: ResMut<RapierConfiguration>,
#[cfg(feature = "inspector")] mut debug_instant: ResMut<ActionDebugInstant>,
) {
let (xform, mut forces) = query.single_mut();
#[cfg(feature = "inspectorb")]
{
if debug_instant.elapsed().as_millis() > 6000 {
dbg!(&forces);
debug_instant.reset();
}
}
rapier_config.gravity = xform.translation.normalize() * -settings.gravity;
forces.force = Vec3::ZERO;
forces.torque = Vec3::ZERO;
}
/// The desired lean angle, given steering input and speed.
pub(super) fn cyber_lean(
bike_state: Query<(&Velocity, &Transform), With<CyberBikeBody>>,
wheels: Query<&Transform, With<CyberWheel>>,
input: Res<InputState>,
gravity_settings: Res<MovementSettings>,
mut lean: ResMut<CyberLean>,
) {
let (velocity, xform) = bike_state.single();
let vel = velocity.linvel.dot(xform.forward());
let v_squared = vel.powi(2);
let steering_angle = yaw_to_angle(input.yaw);
let wheels: Vec<_> = wheels.iter().map(|w| w.translation).collect();
let wheel_base = (wheels[0] - wheels[1]).length();
let radius = wheel_base / steering_angle.tan();
let gravity = gravity_settings.gravity;
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() {
lean.lean = tan_theta.atan().clamp(-FRAC_PI_4, FRAC_PI_4);
} else {
lean.lean = 0.0;
}
}
/// PID-based controller for stabilizing attitude; keeps the cyberbike upright.
pub(super) fn falling_cat(
mut bike_query: Query<(&Transform, &mut ExternalForce, &mut CatControllerState)>,
time: Res<Time>,
settings: Res<CatControllerSettings>,
lean: Res<CyberLean>,
) {
let (xform, mut forces, mut control_vars) = bike_query.single_mut();
let world_up = xform.translation.normalize();
let rot = Quat::from_axis_angle(xform.back(), lean.lean);
let target_up = rotate_point(&world_up, &rot).normalize();
let bike_right = xform.right();
let roll_error = bike_right.dot(target_up);
let pitch_error = world_up.dot(xform.back());
// only try to correct roll if we're not totally vertical
if pitch_error.abs() < 0.95 {
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() {
forces.torque += xform.back() * mag;
}
}
}
/// Apply forces to the cyberbike as a result of input.
pub(super) fn input_forces(
settings: Res<MovementSettings>,
input: Res<InputState>,
mut braking_query: Query<&mut MultibodyJoint, (Without<CyberSteering>, With<CyberWheel>)>,
mut body_query: Query<
(&Transform, &mut ExternalForce),
(With<CyberBikeBody>, Without<CyberSteering>),
>,
mut steering_query: Query<&mut MultibodyJoint, With<CyberSteering>>,
) {
let (xform, mut forces) = body_query.single_mut();
// thrust
let thrust = xform.forward() * input.throttle * settings.accel;
let point = xform.translation + xform.back();
let force = ExternalForce::at_point(thrust, point, xform.translation);
*forces += force;
// 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 };
motor.data = (*motor
.data
.as_revolute_mut()
.unwrap()
.set_motor_max_force(factor)
.set_motor_velocity(speed, factor))
.into();
}
// steering
let angle = yaw_to_angle(input.yaw);
let mut steering = steering_query.single_mut();
steering.data = (*steering
.data
.as_revolute_mut()
.unwrap()
.set_motor_position(-angle, 100.0, 0.5))
.into();
}
/// Don't let the wheels get stuck underneat the planet
pub(super) fn surface_fix(
mut commands: Commands,
mut wheel_query: Query<
(Entity, &Transform, &mut CollisionGroups),
(With<CyberWheel>, Without<Tunneling>),
>,
span_query: Query<&Transform, With<CyberWheel>>,
config: Res<WheelConfig>,
context: Res<RapierContext>,
) {
let mut wheels = Vec::new();
for xform in span_query.iter() {
wheels.push(xform);
}
let span = (wheels[1].translation - wheels[0].translation).normalize();
for (entity, xform, mut cgroups) in wheel_query.iter_mut() {
//let ray_dir = xform.translation.normalize();
let ray_dir = xform.right().cross(span).normalize();
if let Some(hit) = context.cast_ray_and_get_normal(
xform.translation,
ray_dir,
config.radius * 1.1,
false,
QueryFilter::only_fixed(),
) {
cgroups.memberships = Group::NONE;
cgroups.filters = Group::NONE;
commands.entity(entity).insert(Tunneling {
frames: 3,
dir: hit.1.normal,
});
}
}
}
pub(super) fn tunnel_out(
mut commands: Commands,
mut wheel_query: Query<
(
Entity,
&mut Tunneling,
&mut ExternalForce,
&mut CollisionGroups,
),
With<CyberWheel>,
>,
mprops: Query<&ReadMassProperties, With<CyberBikeBody>>,
settings: Res<MovementSettings>,
) {
let mprops = mprops.single();
for (entity, mut tunneling, mut force, mut cgroups) in wheel_query.iter_mut() {
if tunneling.frames == 0 {
commands.entity(entity).remove::<Tunneling>();
force.force = Vec3::ZERO;
(cgroups.memberships, cgroups.filters) = BIKE_WHEEL_COLLISION_GROUP;
continue;
}
tunneling.frames -= 1;
force.force = tunneling.dir * settings.gravity * 1.5 * mprops.0.mass;
#[cfg(feature = "inspector")]
dbg!(&tunneling);
}
}
/// General velocity-based drag-force calculation; does not take orientation
/// into account.
pub(super) fn drag(mut query: Query<(&Velocity, &mut ExternalForce), With<CyberBikeBody>>) {
let (vels, mut forces) = query.single_mut();
if let Some(vel) = vels.linvel.try_normalize() {
let v2 = vels.linvel.length_squared();
forces.force -= vel * (v2 * 0.02);
}
}

View File

@ -7,7 +7,7 @@ use bevy_rapier3d::prelude::{
ReadMassProperties, Restitution, RigidBody, Sleeping, TransformInterpolation, Velocity,
};
use super::{spawn_wheels, CyberBikeBody, Meshterial, WheelConfig, BIKE_BODY_COLLISION_GROUP};
use super::{spawn_tires, CyberBikeBody, Meshterial, WheelConfig, BIKE_BODY_COLLISION_GROUP};
use crate::{action::CatControllerState, planet::PLANET_RADIUS};
pub(super) fn spawn_cyberbike(
@ -16,12 +16,13 @@ pub(super) fn spawn_cyberbike(
wheel_conf: Res<WheelConfig>,
mut meshterials: Meshterial,
) {
let altitude = 3.0;
let altitude = PLANET_RADIUS - 10.0;
let mut xform = Transform::from_translation(Vec3::Y * altitude);
let mut xform = Transform::from_translation(Vec3::X * altitude)
.with_rotation(Quat::from_axis_angle(Vec3::Z, -89.0f32.to_radians()));
// let right = xform.right() * 350.0;
// xform.translation += right;
let right = xform.right() * 350.0;
xform.translation += right;
let damping = Damping {
angular_damping: 2.0,
@ -38,7 +39,7 @@ pub(super) fn spawn_cyberbike(
..Default::default()
};
let mass_properties = ColliderMassProperties::Density(1.5);
let mass_properties = ColliderMassProperties::Density(0.9);
let (membership, filter) = BIKE_BODY_COLLISION_GROUP;
let bike_collision_group = CollisionGroups::new(membership, filter);
@ -80,5 +81,5 @@ pub(super) fn spawn_cyberbike(
.insert(CatControllerState::default())
.id();
spawn_wheels(&mut commands, bike, &wheel_conf, &mut meshterials);
spawn_tires(&mut commands, bike, &wheel_conf, &mut meshterials);
}

View File

@ -22,6 +22,7 @@ pub struct WheelConfig {
pub stiffness: f32,
pub damping: f32,
pub radius: f32,
pub thickness: f32,
pub friction: f32,
pub restitution: f32,
pub density: f32,
@ -31,15 +32,16 @@ impl Default for WheelConfig {
fn default() -> Self {
Self {
front_forward: 0.8,
rear_back: 1.0,
rear_back: 1.1,
y: -0.1,
limits: [-0.5, 0.1],
stiffness: 30.0,
stiffness: 50.0,
damping: 8.0,
radius: 0.3,
friction: 0.0,
radius: 0.38,
thickness: 0.2,
friction: 1.2,
restitution: 0.95,
density: 0.05,
density: 0.9,
}
}
}

View File

@ -1,16 +1,17 @@
mod body;
mod components;
//mod controller;
mod wheels;
use bevy::prelude::{App, Assets, Mesh, Plugin, PostStartup, ResMut, StandardMaterial};
use bevy::prelude::{
App, Assets, IntoSystemConfig, Mesh, Plugin, ResMut, StandardMaterial, StartupSet,
};
use bevy_rapier3d::prelude::Group;
pub(crate) use self::components::*;
use self::{body::spawn_cyberbike, wheels::spawn_wheels};
use self::{body::spawn_cyberbike, wheels::spawn_tires};
pub const BIKE_BODY_COLLISION_GROUP: (Group, Group) = (Group::GROUP_1, Group::GROUP_1);
pub const BIKE_WHEEL_COLLISION_GROUP: (Group, Group) = (Group::GROUP_2, Group::GROUP_2);
pub const BIKE_WHEEL_COLLISION_GROUP: (Group, Group) = (Group::GROUP_10, Group::GROUP_10);
type Meshterial<'a> = (
ResMut<'a, Assets<Mesh>>,
@ -22,6 +23,6 @@ impl Plugin for CyberBikePlugin {
fn build(&self, app: &mut App) {
app.insert_resource(WheelConfig::default())
.register_type::<WheelConfig>()
.add_systems(PostStartup, spawn_cyberbike);
.add_startup_system(spawn_cyberbike.in_base_set(StartupSet::PostStartup));
}
}

View File

@ -1,17 +1,13 @@
use bevy::prelude::*;
use bevy_rapier3d::{
dynamics::{FixedJointBuilder, Velocity},
prelude::{
use bevy::prelude::{shape::UVSphere as Tire, *};
use bevy_rapier3d::prelude::{
Ccd, CoefficientCombineRule, Collider, ColliderMassProperties, CollisionGroups, Damping,
ExternalForce, Friction, MultibodyJoint, PrismaticJointBuilder, Restitution,
RevoluteJointBuilder, RigidBody, Sleeping, TransformInterpolation,
},
};
use super::{CyberSteering, CyberWheel, Meshterial, WheelConfig, BIKE_WHEEL_COLLISION_GROUP};
use crate::action::PreviousVelocity;
pub(crate) fn spawn_wheels(
pub fn spawn_tires(
commands: &mut Commands,
bike: Entity,
conf: &WheelConfig,
@ -20,6 +16,8 @@ pub(crate) fn spawn_wheels(
let (membership, filter) = BIKE_WHEEL_COLLISION_GROUP;
let wheels_collision_group = CollisionGroups::new(membership, filter);
let wheel_y = conf.y;
let wheel_rad = conf.radius;
let _tire_thickness = conf.thickness;
let stiffness = conf.stiffness;
let not_sleeping = Sleeping::disabled();
let ccd = Ccd { enabled: true };
@ -27,9 +25,32 @@ pub(crate) fn spawn_wheels(
let (meshes, materials) = meshterials;
let rake_vec: Vec3 = Vec3::new(0.0, 1.0, 0.57).normalize(); // about 30 degrees of rake
let tire = Tire {
radius: wheel_rad,
..Default::default()
};
let material = StandardMaterial {
base_color: Color::Rgba {
red: 0.01,
green: 0.01,
blue: 0.01,
alpha: 1.0,
},
alpha_mode: AlphaMode::Opaque,
perceptual_roughness: 0.5,
..Default::default()
};
let pbr_bundle = PbrBundle {
material: materials.add(material),
mesh: meshes.add(Mesh::from(tire)),
..Default::default()
};
let friction = Friction {
coefficient: conf.friction,
combine_rule: CoefficientCombineRule::Min,
combine_rule: CoefficientCombineRule::Average,
};
let mut wheel_poses = Vec::with_capacity(2);
@ -51,43 +72,35 @@ pub(crate) fn spawn_wheels(
}
for (offset, steering) in wheel_poses {
let (mesh, collider) = gen_tires(conf);
let material = StandardMaterial {
base_color: Color::YELLOW,
alpha_mode: AlphaMode::Opaque,
perceptual_roughness: 0.1,
..Default::default()
};
let pbr_bundle = PbrBundle {
material: materials.add(material),
mesh: meshes.add(mesh),
let wheel_damping = Damping {
linear_damping: 0.8,
..Default::default()
};
let wheel_collider = Collider::ball(wheel_rad);
let mass_props = ColliderMassProperties::Density(conf.density);
let suspension_damping = conf.damping;
let damping = conf.damping;
let suspension_axis = if steering.is_some() {
let prismatic_axis = if steering.is_some() {
rake_vec
} else {
Vec3::Y
};
let suspension_joint_builder = PrismaticJointBuilder::new(suspension_axis)
let prismatic_builder = PrismaticJointBuilder::new(prismatic_axis)
.local_anchor1(offset)
.limits(limits)
.motor_position(limits[0], stiffness, suspension_damping);
let suspension_joint = MultibodyJoint::new(bike, suspension_joint_builder);
.motor_position(limits[0], stiffness, damping);
let prismatic_joint = MultibodyJoint::new(bike, prismatic_builder);
let fork_rb_entity = commands
.spawn(RigidBody::Dynamic)
.insert(suspension_joint)
.insert(prismatic_joint)
.insert(not_sleeping)
.id();
let axel_parent_entity = if let Some(steering) = steering {
let neck_builder = FixedJointBuilder::new().local_anchor1(Vec3::new(0.0, 0.0, 0.1)); // this adds another 0.1m of trail
let neck_builder =
RevoluteJointBuilder::new(rake_vec).local_anchor1(Vec3::new(0.0, -0.08, 0.1)); // this adds another 0.1m of trail
let neck_joint = MultibodyJoint::new(fork_rb_entity, neck_builder);
let neck = commands
.spawn(RigidBody::Dynamic)
@ -100,35 +113,29 @@ pub(crate) fn spawn_wheels(
fork_rb_entity
};
let axel_builder = FixedJointBuilder::new();
let axel_builder = RevoluteJointBuilder::new(Vec3::X);
let axel_joint = MultibodyJoint::new(axel_parent_entity, axel_builder);
// re-orient the joint so that the wheel is correctly oriented
//let real_axel = *axel_joint.data.set_local_axis1(Vec3::X);
//axel_joint.data = real_axel;
commands.spawn(pbr_bundle).insert((
collider,
commands
.spawn(pbr_bundle.clone())
.insert((
wheel_collider,
mass_props,
//wheel_damping,
wheel_damping,
ccd,
not_sleeping,
axel_joint,
wheels_collision_group,
friction,
CyberWheel,
Velocity::default(),
PreviousVelocity::default(),
ExternalForce::default(),
SpatialBundle::default(),
Restitution::new(conf.restitution),
TransformInterpolation::default(),
RigidBody::Dynamic,
));
))
.insert(SpatialBundle::default());
}
}
// do mesh shit
fn gen_tires(conf: &WheelConfig) -> (Mesh, Collider) {
let wheel_rad = conf.radius;
let tire = Sphere::new(wheel_rad);
let mesh = Mesh::from(tire);
let wheel_collider = Collider::ball(wheel_rad);
(mesh, wheel_collider)
}

View File

@ -67,7 +67,7 @@ fn follow_cyberbike(
offset: Res<DebugCamOffset>,
) {
let bike_xform = *query.p0().single();
let up = Vec3::Y; //bike_xform.translation.normalize();
let up = bike_xform.translation.normalize();
for (mut cam_xform, cam_type) in query.p1().iter_mut() {
match *cam_type {
@ -81,7 +81,7 @@ fn follow_cyberbike(
// handle input pitch
let angle = input.pitch.powi(3) * MAX_PITCH;
let axis = cam_xform.right();
cam_xform.rotate(Quat::from_axis_angle(*axis, angle));
cam_xform.rotate(Quat::from_axis_angle(axis, angle));
}
CyberCameras::Debug => {
let mut ncx = bike_xform.to_owned();
@ -101,7 +101,7 @@ fn update_active_camera(
) {
// 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()) {
if cyber.eq(&state.0) {
cam.is_active = true;
} else {
cam.is_active = false;
@ -112,13 +112,13 @@ fn update_active_camera(
fn cycle_cam_state(
state: Res<State<CyberCameras>>,
mut next: ResMut<NextState<CyberCameras>>,
mut keys: ResMut<ButtonInput<KeyCode>>,
mut keys: ResMut<Input<KeyCode>>,
) {
if keys.just_pressed(KeyCode::KeyD) {
let new_state = state.get().next();
if keys.just_pressed(KeyCode::D) {
let new_state = state.0.next();
info!("{:?}", new_state);
next.set(new_state);
keys.reset(KeyCode::KeyD);
keys.reset(KeyCode::D);
}
}
@ -132,10 +132,9 @@ impl Plugin for CyberCamPlugin {
fn common(app: &mut bevy::prelude::App) {
app.insert_resource(DebugCamOffset::default())
.add_systems(Startup, setup_cybercams)
.init_state::<CyberCameras>()
.add_systems(
Update,
(cycle_cam_state, update_active_camera, follow_cyberbike),
);
.add_startup_system(setup_cybercams)
.add_state::<CyberCameras>()
.add_system(cycle_cam_state)
.add_system(update_active_camera)
.add_system(follow_cyberbike);
}

View File

@ -19,17 +19,16 @@ impl Plugin for CyberGlamorPlugin {
let mode = DebugRenderMode::CONTACTS
| DebugRenderMode::SOLVER_CONTACTS
| DebugRenderMode::JOINTS
| DebugRenderMode::COLLIDER_SHAPES
| DebugRenderMode::RIGID_BODY_AXES;
let rplugin = RapierDebugRenderPlugin {
style,
// always_on_top: true,
always_on_top: true,
enabled: true,
mode,
};
app.add_plugins(rplugin);
app.add_plugin(rplugin);
}
}
}

View File

@ -14,22 +14,22 @@ pub(crate) struct InputState {
pub pitch: f32,
}
fn update_debug_cam(mut offset: ResMut<DebugCamOffset>, mut keys: ResMut<ButtonInput<KeyCode>>) {
fn update_debug_cam(mut offset: ResMut<DebugCamOffset>, mut keys: ResMut<Input<KeyCode>>) {
let keyset: HashSet<_> = keys.get_pressed().collect();
let shifted = keyset.contains(&KeyCode::ShiftLeft) || keyset.contains(&KeyCode::ShiftRight);
let shifted = keyset.contains(&KeyCode::LShift) || keyset.contains(&KeyCode::RShift);
for key in keyset {
match key {
KeyCode::ArrowLeft => offset.rot -= 5.0,
KeyCode::ArrowRight => offset.rot += 5.0,
KeyCode::ArrowUp => {
KeyCode::Left => offset.rot -= 5.0,
KeyCode::Right => offset.rot += 5.0,
KeyCode::Up => {
if shifted {
offset.alt += 0.5;
} else {
offset.dist -= 0.5;
}
}
KeyCode::ArrowDown => {
KeyCode::Down => {
if shifted {
offset.alt -= 0.5;
} else {
@ -41,17 +41,16 @@ fn update_debug_cam(mut offset: ResMut<DebugCamOffset>, mut keys: ResMut<ButtonI
}
if keys.get_just_released().len() > 0 {
let unpressed =
keys.just_released(KeyCode::ShiftLeft) || keys.just_released(KeyCode::ShiftRight);
let unpressed = keys.just_released(KeyCode::LShift) || keys.just_released(KeyCode::RShift);
keys.reset_all();
if shifted && !unpressed {
keys.press(KeyCode::ShiftLeft);
keys.press(KeyCode::LShift);
}
}
}
fn update_input(mut events: EventReader<GamepadEvent>, mut istate: ResMut<InputState>) {
for pad_event in events.read() {
for pad_event in events.iter() {
match pad_event {
GamepadEvent::Button(button_event) => {
let GamepadButtonChangedEvent {
@ -93,6 +92,7 @@ pub struct CyberInputPlugin;
impl Plugin for CyberInputPlugin {
fn build(&self, app: &mut App) {
app.init_resource::<InputState>()
.add_systems(Update, (update_input, update_debug_cam));
.add_system(update_input)
.add_system(update_debug_cam);
}
}

View File

@ -1,4 +1,5 @@
use bevy::{
ecs::schedule::SystemSet,
prelude::{Query, Vec3, Window, With},
window::PrimaryWindow,
};
@ -12,6 +13,14 @@ pub mod lights;
pub mod planet;
pub mod ui;
#[derive(Clone, Debug, Hash, PartialEq, Eq, SystemSet)]
pub enum Label {
Geometry,
Glamor,
Input,
Action,
}
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 = 900.0;
pub const LIGHT_RANGE: f32 = 90.0;
fn spawn_static_lights(
mut commands: Commands,
@ -10,37 +10,88 @@ fn spawn_static_lights(
mut materials: ResMut<Assets<StandardMaterial>>,
) {
let pink_light = PointLight {
intensity: 10_00.0,
intensity: 1_00.0,
range: LIGHT_RANGE,
color: Color::WHITE,
radius: 10.0,
color: Color::PINK,
radius: 1.0,
shadows_enabled: true,
..Default::default()
};
let blue_light = PointLight {
intensity: 1_000.0,
range: LIGHT_RANGE,
color: Color::BLUE,
radius: 1.0,
shadows_enabled: true,
..Default::default()
};
commands.insert_resource(AmbientLight {
color: Color::WHITE,
brightness: 100.0,
brightness: 0.2,
});
// let _cascade_shadow_config = CascadeShadowConfigBuilder {
// first_cascade_far_bound: 0.3,
// maximum_distance: 3.0,
// ..default()
// }
// .build();
let _cascade_shadow_config = CascadeShadowConfigBuilder {
first_cascade_far_bound: 0.3,
maximum_distance: 3.0,
..default()
}
.build();
// up light
commands.spawn(PointLightBundle {
transform: Transform::from_xyz(0.0, 100.0, 0.0),
commands
.spawn(PointLightBundle {
transform: Transform::from_xyz(0.0, PLANET_RADIUS + 30.0, 0.0),
point_light: pink_light,
..Default::default()
})
.with_children(|builder| {
builder.spawn(PbrBundle {
mesh: meshes.add(
Mesh::try_from(shape::Icosphere {
radius: 10.0,
subdivisions: 2,
})
.unwrap(),
),
material: materials.add(StandardMaterial {
base_color: Color::BLUE,
emissive: Color::PINK,
..Default::default()
}),
..Default::default()
});
});
// down light
commands
.spawn(PointLightBundle {
transform: Transform::from_xyz(0.0, -PLANET_RADIUS - 30.0, 0.0),
point_light: blue_light,
..Default::default()
})
.with_children(|builder| {
builder.spawn(PbrBundle {
mesh: meshes.add(
Mesh::try_from(shape::Icosphere {
radius: 10.0,
subdivisions: 2,
})
.unwrap(),
),
material: materials.add(StandardMaterial {
base_color: Color::PINK,
emissive: Color::BLUE,
..Default::default()
}),
..Default::default()
});
});
}
pub struct CyberSpaceLightsPlugin;
impl Plugin for CyberSpaceLightsPlugin {
fn build(&self, app: &mut App) {
app.add_systems(Startup, spawn_static_lights);
app.add_startup_system(spawn_static_lights);
}
}

View File

@ -21,20 +21,18 @@ fn main() {
}),
..Default::default()
}))
.add_plugins((
CyberPlanetPlugin,
CyberInputPlugin,
CyberActionPlugin,
CyberCamPlugin,
CyberSpaceLightsPlugin,
CyberUIPlugin,
CyberBikePlugin,
))
.add_systems(Startup, disable_mouse_trap)
.add_systems(Update, bevy::window::close_on_esc);
.add_plugin(CyberPlanetPlugin)
.add_plugin(CyberInputPlugin)
.add_plugin(CyberActionPlugin)
.add_plugin(CyberCamPlugin)
.add_plugin(CyberSpaceLightsPlugin)
.add_plugin(CyberUIPlugin)
.add_plugin(CyberBikePlugin)
.add_startup_system(disable_mouse_trap)
.add_system(bevy::window::close_on_esc);
#[cfg(feature = "inspector")]
app.add_plugins(CyberGlamorPlugin);
app.add_plugin(CyberGlamorPlugin);
app.run();
}

View File

@ -1,8 +1,18 @@
use bevy::{prelude::*, render::color::Color};
use bevy_rapier3d::prelude::*;
// use noise::{HybridMulti, NoiseFn, SuperSimplex};
//use core::slice::SlicePattern;
pub const PLANET_RADIUS: f32 = 2_000.0;
use bevy::{
prelude::{shape::Icosphere, *},
render::{color::Color, mesh::Indices},
};
use bevy_rapier3d::prelude::*;
use hexasphere::shapes::IcoSphere;
use noise::{HybridMulti, NoiseFn, SuperSimplex};
use rand::{Rng, SeedableRng};
use wgpu::PrimitiveTopology;
use crate::Label;
pub const PLANET_RADIUS: f32 = 3_000.0;
pub const PLANET_HUE: f32 = 31.0;
pub const PLANET_SATURATION: f32 = 1.0;
@ -15,14 +25,14 @@ fn spawn_planet(
mut materials: ResMut<Assets<StandardMaterial>>,
) {
//let color = Color::rgb(0.74, 0.5334, 0.176);
let isphere = Icosphere {
radius: PLANET_RADIUS,
subdivisions: 88,
};
let (mesh, shape) = gen_planet(2999.9);
let (mesh, shape) = gen_planet(isphere);
let pbody = (
RigidBody::Fixed,
Ccd { enabled: true },
Transform::from_xyz(0.0, 0.1, 0.0),
);
let pbody = (RigidBody::Fixed, Ccd { enabled: true });
let pcollide = (
shape,
@ -31,19 +41,12 @@ fn spawn_planet(
..Default::default()
},
Restitution::new(0.8),
Transform::from_xyz(0.0, 1.0, 0.0),
// same as the bike body
CollisionGroups::new(Group::GROUP_1, Group::GROUP_1),
);
commands
.spawn(PbrBundle {
mesh: meshes.add(mesh),
material: materials.add(StandardMaterial {
base_color: Color::GREEN,
..Default::default()
}),
transform: Transform::from_xyz(0.0, 0.1, 0.0),
material: materials.add(Color::WHITE.into()),
..Default::default()
})
.insert(pbody)
@ -54,7 +57,7 @@ fn spawn_planet(
pub struct CyberPlanetPlugin;
impl Plugin for CyberPlanetPlugin {
fn build(&self, app: &mut App) {
app.add_systems(Startup, spawn_planet);
app.add_startup_system(spawn_planet);
}
}
@ -62,10 +65,105 @@ impl Plugin for CyberPlanetPlugin {
// utils
//---------------------------------------------------------------------
fn gen_planet(span: f32) -> (Mesh, Collider) {
let mut mesh = Cuboid::new(span, 1.0, span);
fn gen_planet(sphere: Icosphere) -> (Mesh, Collider) {
// straight-up stolen from Bevy's impl of Mesh from Icosphere, so I can do the
// displacement before normals are calculated.
let generated = IcoSphere::new(sphere.subdivisions, |point| {
let inclination = point.y.acos();
let azimuth = point.z.atan2(point.x);
let collider = Collider::cuboid(span / 2.0, 0.5, span / 2.0);
let norm_inclination = inclination / std::f32::consts::PI;
let norm_azimuth = 0.5 - (azimuth / std::f32::consts::TAU);
(mesh.mesh(), collider)
[norm_azimuth, norm_inclination]
});
let noise = HybridMulti::<SuperSimplex>::default();
let (mut min, mut max) = (f32::MAX, f32::MIN);
let noisy_points = generated
.raw_points()
.iter()
.map(|&p| {
let disp = noise.get(p.as_dvec3().into()) as f32 * 0.05;
let pt = p + (p.normalize() * disp);
pt.into()
})
.collect::<Vec<[f32; 3]>>();
let points = noisy_points
.iter()
.map(|&p| (Vec3::from_slice(&p) * sphere.radius).into())
.collect::<Vec<[f32; 3]>>();
for p in &points {
let v = Vec3::new(p[0], p[1], p[2]);
let v = v.length();
min = v.min(min);
max = v.max(max);
}
let uvs = generated.raw_data().to_owned();
let mut indices = Vec::with_capacity(generated.indices_per_main_triangle() * 20);
for i in 0..20 {
generated.get_indices(i, &mut indices);
}
let mut idxs = Vec::new();
for idx in indices.chunks_exact(3) {
idxs.push([idx[0], idx[1], idx[2]]);
}
let indices = Indices::U32(indices);
let shape = Collider::trimesh(points.iter().map(|p| Vect::from_slice(p)).collect(), idxs);
dbg!(&points.len());
let mut mesh = Mesh::new(PrimitiveTopology::TriangleList);
mesh.set_indices(Some(indices));
mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, points);
//mesh.insert_attribute(Mesh::ATTRIBUTE_UV_0, uvs);
mesh.duplicate_vertices();
mesh.compute_flat_normals();
let tri_list = mesh
.attribute(Mesh::ATTRIBUTE_POSITION)
.unwrap()
.as_float3()
.unwrap();
dbg!(&tri_list.len());
let mut rng = rand::rngs::StdRng::seed_from_u64(57);
let mut colors = Vec::new();
for triangle in tri_list.chunks_exact(3) {
let mut lens = 0.0;
for &v in triangle {
let v = Vec3::new(v[0], v[1], v[2]);
lens += v.length();
}
let v = lens / 3.0;
//let l = val_norm(v, min - 500.0, max); //.powi(2);
let l = 0.41;
let jitter = rng.gen_range(-0.0..=360.0f32);
let h = jitter;
let color = Color::hsl(h, PLANET_SATURATION, l).as_linear_rgba_f32();
for _ in 0..3 {
colors.push(color.clone());
}
}
dbg!(&colors.len());
mesh.insert_attribute(Mesh::ATTRIBUTE_COLOR, colors);
(mesh, shape)
}
/// remaps v in low..high to 0..1
fn val_norm(v: f32, low: f32, high: f32) -> f32 {
// q = (p-A)*(D-C)/(B-A) + C, C = 0, D = 1
(v - low) / (high - low)
}

View File

@ -1,12 +1,9 @@
use bevy::{
app::{Startup, Update},
prelude::{
use bevy::prelude::{
AlignSelf, App, AssetServer, Color, Commands, Component, Plugin, Query, Res, Style, Text,
TextBundle, TextSection, TextStyle, Transform, With,
},
};
//#[cfg(feature = "inspector")]
//use bevy_inspector_egui::quick::WorldInspectorPlugin;
#[cfg(feature = "inspector")]
use bevy_inspector_egui::quick::WorldInspectorPlugin;
use bevy_rapier3d::prelude::Velocity;
use crate::bike::CyberBikeBody;
@ -45,7 +42,7 @@ fn update_ui(
) {
let mut text = text_query.single_mut();
let (velocity, xform) = state_query.single();
let speed = velocity.linvel.dot(*xform.forward());
let speed = velocity.linvel.dot(xform.forward());
text.sections[0].value = format!("spd: {:.2}", speed);
}
@ -54,10 +51,8 @@ pub struct CyberUIPlugin;
impl Plugin for CyberUIPlugin {
fn build(&self, app: &mut App) {
#[cfg(feature = "inspector")]
//app.add_plugins(WorldInspectorPlugin::new());
app.add_plugin(WorldInspectorPlugin);
//
app.add_systems(Startup, setup_ui)
.add_systems(Update, update_ui);
app.add_startup_system(setup_ui).add_system(update_ui);
}
}