update deps for switching to Avian3d

This commit is contained in:
Joe Ardent 2024-07-12 15:35:37 -07:00
parent 82f95cf070
commit 4d94f2bfa4
12 changed files with 2394 additions and 1489 deletions

3344
Cargo.lock generated

File diff suppressed because it is too large Load Diff

View File

@ -6,32 +6,22 @@ edition = "2021"
[dependencies] [dependencies]
rand = "0.8" rand = "0.8"
# bevy_polyline = "0.4" # bevy_polyline = "0.4"
noise = { git = "https://github.com/Razaekel/noise-rs" } noise = "0.9"
hexasphere = "8" hexasphere = "14"
wgpu = "0.15" wgpu = "0.20"
bevy-inspector-egui = "0.18" # bevy-inspector-egui = "0.18"
[features] [features]
inspector = [] inspector = []
[dependencies.bevy] [dependencies.bevy]
version = "0.10" version = "0.14"
default-features = false default-features = true
features = [ features = ["bevy_dev_tools"]
"bevy_gilrs",
"bevy_winit",
"png",
"hdr",
"x11",
"bevy_ui",
"bevy_text",
"bevy_gltf",
"bevy_sprite",
]
[dependencies.bevy_rapier3d] [dependencies.avian3d]
features = ["debug-render-3d"] default-features = true
version = "0.21" version = "0.1"
# Maybe also enable only a small amount of optimization for our code: # Maybe also enable only a small amount of optimization for our code:
[profile.dev] [profile.dev]

View File

@ -1,10 +1,11 @@
use avian3d::prelude::*;
use bevy::{ use bevy::{
app::{Startup, Update},
diagnostic::FrameTimeDiagnosticsPlugin, diagnostic::FrameTimeDiagnosticsPlugin,
ecs::reflect::ReflectResource, ecs::reflect::ReflectResource,
prelude::{App, IntoSystemConfigs, Plugin, Resource}, prelude::{App, IntoSystemConfigs, Plugin, Resource},
reflect::Reflect, reflect::Reflect,
}; };
use bevy_rapier3d::prelude::{NoUserData, RapierPhysicsPlugin};
mod components; mod components;
mod systems; mod systems;
@ -28,20 +29,14 @@ impl Plugin for CyberActionPlugin {
.init_resource::<CyberLean>() .init_resource::<CyberLean>()
.register_type::<CyberLean>() .register_type::<CyberLean>()
.register_type::<CatControllerSettings>() .register_type::<CatControllerSettings>()
.add_plugin(RapierPhysicsPlugin::<NoUserData>::default()) .add_plugins((
.add_startup_system(timestep_setup) PhysicsPlugins::default(),
.add_plugin(FrameTimeDiagnosticsPlugin::default()) FrameTimeDiagnosticsPlugin::default(),
))
.insert_resource(SubstepCount(12))
.add_systems( .add_systems(
( Update,
gravity, (gravity, cyber_lean, falling_cat, input_forces).chain(),
cyber_lean,
falling_cat,
input_forces,
drag,
tunnel_out,
surface_fix,
)
.chain(),
); );
} }
} }

View File

@ -1,15 +1,14 @@
use std::f32::consts::{FRAC_PI_3, FRAC_PI_4}; use std::f32::consts::{FRAC_PI_3, FRAC_PI_4};
use avian3d::{
dynamics::solver::xpbd::AngularConstraint, parry::mass_properties::MassProperties, prelude::*,
};
use bevy::prelude::{ use bevy::prelude::{
Commands, Entity, Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without, Commands, Entity, Quat, Query, Res, ResMut, Time, Transform, Vec3, With, Without,
}; };
use bevy_rapier3d::prelude::{
CollisionGroups, ExternalForce, Group, MultibodyJoint, QueryFilter, RapierConfiguration,
RapierContext, ReadMassProperties, TimestepMode, Velocity,
};
#[cfg(feature = "inspector")] //#[cfg(feature = "inspector")]
use super::ActionDebugInstant; //use super::ActionDebugInstant;
use super::{CatControllerSettings, CatControllerState, CyberLean, MovementSettings, Tunneling}; use super::{CatControllerSettings, CatControllerState, CyberLean, MovementSettings, Tunneling};
use crate::{ use crate::{
bike::{CyberBikeBody, CyberSteering, CyberWheel, WheelConfig, BIKE_WHEEL_COLLISION_GROUP}, bike::{CyberBikeBody, CyberSteering, CyberWheel, WheelConfig, BIKE_WHEEL_COLLISION_GROUP},
@ -36,46 +35,28 @@ fn rotate_point(pt: &Vec3, rot: &Quat) -> Vec3 {
-Vec3::from_array([rot_qpt.x, rot_qpt.y, rot_qpt.z]) -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. /// The gravity vector points from the cyberbike to the center of the planet.
pub(super) fn gravity( pub(super) fn gravity(
mut query: Query<(&Transform, &mut ExternalForce), With<CyberBikeBody>>, mut query: Query<(&Transform, &mut ExternalForce), With<CyberBikeBody>>,
settings: Res<MovementSettings>, settings: Res<MovementSettings>,
mut rapier_config: ResMut<RapierConfiguration>, mut gravity: ResMut<Gravity>,
#[cfg(feature = "inspector")] mut debug_instant: ResMut<ActionDebugInstant>, #[cfg(feature = "inspector")] mut debug_instant: ResMut<ActionDebugInstant>,
) { ) {
let (xform, mut forces) = query.single_mut(); let (xform, mut forces) = query.single_mut();
*gravity = Gravity(xform.translation.normalize() * -settings.gravity);
#[cfg(feature = "inspectorb")] forces.clear();
{
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. /// The desired lean angle, given steering input and speed.
pub(super) fn cyber_lean( pub(super) fn cyber_lean(
bike_state: Query<(&Velocity, &Transform), With<CyberBikeBody>>, bike_state: Query<(&LinearVelocity, &Transform), With<CyberBikeBody>>,
wheels: Query<&Transform, With<CyberWheel>>, wheels: Query<&Transform, With<CyberWheel>>,
input: Res<InputState>, input: Res<InputState>,
gravity_settings: Res<MovementSettings>, gravity_settings: Res<MovementSettings>,
mut lean: ResMut<CyberLean>, mut lean: ResMut<CyberLean>,
) { ) {
let (velocity, xform) = bike_state.single(); let (velocity, xform) = bike_state.single();
let vel = velocity.linvel.dot(xform.forward()); let vel = velocity.dot(*xform.forward());
let v_squared = vel.powi(2); let v_squared = vel.powi(2);
let steering_angle = yaw_to_angle(input.yaw); let steering_angle = yaw_to_angle(input.yaw);
let wheels: Vec<_> = wheels.iter().map(|w| w.translation).collect(); let wheels: Vec<_> = wheels.iter().map(|w| w.translation).collect();
@ -94,20 +75,20 @@ pub(super) fn cyber_lean(
/// PID-based controller for stabilizing attitude; keeps the cyberbike upright. /// PID-based controller for stabilizing attitude; keeps the cyberbike upright.
pub(super) fn falling_cat( pub(super) fn falling_cat(
mut bike_query: Query<(&Transform, &mut ExternalForce, &mut CatControllerState)>, mut bike_query: Query<(&Transform, &mut ExternalTorque, &mut CatControllerState)>,
time: Res<Time>, time: Res<Time>,
settings: Res<CatControllerSettings>, settings: Res<CatControllerSettings>,
lean: Res<CyberLean>, lean: Res<CyberLean>,
) { ) {
let (xform, mut forces, 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();
let rot = Quat::from_axis_angle(xform.back(), lean.lean); let rot = Quat::from_axis_angle(*xform.back(), lean.lean);
let target_up = rotate_point(&world_up, &rot).normalize(); let target_up = rotate_point(&world_up, &rot).normalize();
let bike_right = xform.right(); let bike_right = xform.right();
let roll_error = bike_right.dot(target_up); let roll_error = bike_right.dot(target_up);
let pitch_error = world_up.dot(xform.back()); let pitch_error = world_up.dot(*xform.back());
// only try to correct roll if we're not totally vertical // only try to correct roll if we're not totally vertical
if pitch_error.abs() < 0.95 { if pitch_error.abs() < 0.95 {
@ -115,7 +96,7 @@ pub(super) fn falling_cat(
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_finite() {
forces.torque += xform.back() * mag; torque.apply_torque(*xform.back() * mag);
} }
} }
} }
@ -124,20 +105,27 @@ pub(super) fn falling_cat(
pub(super) fn input_forces( pub(super) fn input_forces(
settings: Res<MovementSettings>, settings: Res<MovementSettings>,
input: Res<InputState>, input: Res<InputState>,
mut braking_query: Query<&mut MultibodyJoint, (Without<CyberSteering>, With<CyberWheel>)>, time: Res<Time>,
axle: Query<Entity, With<CyberSteering>>,
mut braking_query: Query<&mut ExternalTorque, With<CyberWheel>>,
mut body_query: Query< mut body_query: Query<
(&Transform, &mut ExternalForce), (
(With<CyberBikeBody>, Without<CyberSteering>), Entity,
&Transform,
&ColliderMassProperties,
&mut ExternalForce,
),
With<CyberBikeBody>,
>, >,
mut steering_query: Query<&mut MultibodyJoint, With<CyberSteering>>,
) { ) {
let (xform, mut forces) = body_query.single_mut(); let (bike, xform, mass, mut forces) = body_query.single_mut();
let dt = time.delta_seconds();
// thrust // thrust
let thrust = xform.forward() * input.throttle * settings.accel; let thrust = xform.forward() * input.throttle * settings.accel;
let point = xform.translation + xform.back(); let point = xform.translation + *xform.back();
let force = ExternalForce::at_point(thrust, point, xform.translation);
*forces += force; *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 mut motor in braking_query.iter_mut() {
@ -147,99 +135,14 @@ pub(super) fn input_forces(
input.throttle * settings.accel input.throttle * settings.accel
}; };
let speed = if input.brake { 0.0 } else { -70.0 }; let speed = if input.brake { 0.0 } else { -70.0 };
motor.data = (*motor let target = dt * factor * speed;
.data let torque = target * Vec3::X;
.as_revolute_mut() motor.apply_torque(torque);
.unwrap()
.set_motor_max_force(factor)
.set_motor_velocity(speed, factor))
.into();
} }
// steering // steering
let angle = yaw_to_angle(input.yaw); let _angle = yaw_to_angle(input.yaw);
let mut steering = steering_query.single_mut(); let _axle = axle.single();
steering.data = (*steering //steering.align_orientation(bike, steering, rotation_difference, lagrange,
.data // compliance, dt)
.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

@ -1,11 +1,8 @@
use avian3d::prelude::*;
use bevy::{ use bevy::{
prelude::{AssetServer, BuildChildren, Commands, Quat, Res, SpatialBundle, Transform, Vec3}, prelude::{AssetServer, BuildChildren, Commands, Quat, Res, SpatialBundle, Transform, Vec3},
scene::SceneBundle, scene::SceneBundle,
}; };
use bevy_rapier3d::prelude::{
Ccd, Collider, ColliderMassProperties, CollisionGroups, Damping, ExternalForce, Friction,
ReadMassProperties, Restitution, RigidBody, Sleeping, TransformInterpolation, Velocity,
};
use super::{spawn_wheels, CyberBikeBody, Meshterial, WheelConfig, BIKE_BODY_COLLISION_GROUP}; use super::{spawn_wheels, CyberBikeBody, Meshterial, WheelConfig, BIKE_BODY_COLLISION_GROUP};
use crate::{action::CatControllerState, planet::PLANET_RADIUS}; use crate::{action::CatControllerState, planet::PLANET_RADIUS};
@ -24,14 +21,10 @@ pub(super) fn spawn_cyberbike(
let right = xform.right() * 350.0; let right = xform.right() * 350.0;
xform.translation += right; xform.translation += right;
let damping = Damping {
angular_damping: 2.0,
linear_damping: 0.1,
};
let friction = Friction { let friction = Friction {
coefficient: 0.01, dynamic_coefficient: 0.1,
..Default::default() static_coefficient: 0.6,
combine_rule: CoefficientCombine::Average,
}; };
let restitution = Restitution { let restitution = Restitution {
@ -39,10 +32,8 @@ pub(super) fn spawn_cyberbike(
..Default::default() ..Default::default()
}; };
let mass_properties = ColliderMassProperties::Density(1.5);
let (membership, filter) = BIKE_BODY_COLLISION_GROUP; let (membership, filter) = BIKE_BODY_COLLISION_GROUP;
let bike_collision_group = CollisionGroups::new(membership, filter); let bike_collision_group = CollisionLayers::new(membership, filter);
let scene = asset_server.load("cb-no-y_up.glb#Scene0"); let scene = asset_server.load("cb-no-y_up.glb#Scene0");
@ -51,26 +42,26 @@ pub(super) fn spawn_cyberbike(
..Default::default() ..Default::default()
}; };
let body =
Collider::capsule_endpoints(0.5, Vec3::new(0.0, 0.0, -0.65), Vec3::new(0.0, 0.0, 0.8));
let mass_props = MassPropertiesBundle::new_computed(&body, 0.6);
let bike = commands let bike = commands
.spawn(RigidBody::Dynamic) .spawn(RigidBody::Dynamic)
.insert(spatialbundle) .insert(spatialbundle)
.insert(( .insert((
Collider::capsule(Vec3::new(0.0, 0.0, -0.65), Vec3::new(0.0, 0.0, 0.8), 0.5), body,
mass_props.clone(),
bike_collision_group, bike_collision_group,
mass_properties,
damping,
restitution, restitution,
friction, friction,
Sleeping::disabled(), SleepingDisabled,
Ccd { enabled: true }, LinearDamping(0.1),
ReadMassProperties::default(), AngularDamping(2.0),
LinearVelocity::ZERO,
AngularVelocity::ZERO,
ExternalForce::ZERO,
ExternalTorque::ZERO,
)) ))
.insert(TransformInterpolation {
start: None,
end: None,
})
.insert(Velocity::zero())
.insert(ExternalForce::default())
.with_children(|rider| { .with_children(|rider| {
rider.spawn(SceneBundle { rider.spawn(SceneBundle {
scene, scene,

View File

@ -6,10 +6,10 @@ use bevy::{
#[derive(Component)] #[derive(Component)]
pub struct CyberBikeBody; pub struct CyberBikeBody;
#[derive(Component)] #[derive(Clone, Component)]
pub struct CyberSteering; pub struct CyberSteering;
#[derive(Debug, Component)] #[derive(Clone, Debug, Component)]
pub struct CyberWheel; pub struct CyberWheel;
#[derive(Resource, Reflect)] #[derive(Resource, Reflect)]

View File

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

View File

@ -1,9 +1,5 @@
use bevy::prelude::{shape::Torus as Tire, *}; use avian3d::prelude::*;
use bevy_rapier3d::prelude::{ use bevy::prelude::{Torus as Tire, *};
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 super::{CyberSteering, CyberWheel, Meshterial, WheelConfig, BIKE_WHEEL_COLLISION_GROUP};
@ -14,18 +10,19 @@ pub fn spawn_wheels(
meshterials: &mut Meshterial, meshterials: &mut Meshterial,
) { ) {
let (membership, filter) = BIKE_WHEEL_COLLISION_GROUP; let (membership, filter) = BIKE_WHEEL_COLLISION_GROUP;
let wheels_collision_group = CollisionGroups::new(membership, filter); let wheels_collision_group = CollisionLayers::new(membership, filter);
let wheel_y = conf.y; let wheel_y = conf.y;
let stiffness = conf.stiffness; let stiffness = conf.stiffness;
let not_sleeping = Sleeping::disabled(); let not_sleeping = SleepingDisabled;
let ccd = Ccd { enabled: true }; let ccd = SweptCcd::NON_LINEAR.include_dynamic(false);
let limits = conf.limits; 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 { let friction = Friction {
coefficient: conf.friction, dynamic_coefficient: conf.friction,
combine_rule: CoefficientCombineRule::Average, static_coefficient: conf.friction,
combine_rule: CoefficientCombine::Average,
}; };
let mut wheel_poses = Vec::with_capacity(2); let mut wheel_poses = Vec::with_capacity(2);
@ -50,12 +47,7 @@ pub fn spawn_wheels(
let (mesh, collider) = gen_tires(conf); let (mesh, collider) = gen_tires(conf);
let material = StandardMaterial { let material = StandardMaterial {
base_color: Color::Rgba { base_color: Color::linear_rgba(0.01, 0.01, 0.01, 1.0),
red: 0.01,
green: 0.01,
blue: 0.01,
alpha: 1.0,
},
alpha_mode: AlphaMode::Opaque, alpha_mode: AlphaMode::Opaque,
perceptual_roughness: 0.5, perceptual_roughness: 0.5,
..Default::default() ..Default::default()
@ -67,64 +59,55 @@ pub fn spawn_wheels(
..Default::default() ..Default::default()
}; };
let mass_props = ColliderMassProperties::Density(conf.density);
let suspension_damping = conf.damping;
let suspension_axis = if steering.is_some() { let suspension_axis = if steering.is_some() {
rake_vec rake_vec
} else { } else {
Vec3::Y Vec3::Y
}; };
let suspension_joint_builder = PrismaticJointBuilder::new(suspension_axis) let wheel = commands
.local_anchor1(offset) .spawn(pbr_bundle)
.limits(limits) .insert((
.motor_position(limits[0], stiffness, suspension_damping); collider,
let suspension_joint = MultibodyJoint::new(bike, suspension_joint_builder); ccd,
let fork_rb_entity = commands not_sleeping,
.spawn(RigidBody::Dynamic) wheels_collision_group,
.insert(suspension_joint) friction,
.insert(not_sleeping) CyberWheel,
ExternalForce::default(),
Restitution::new(conf.restitution),
SpatialBundle::default(),
RigidBody::Dynamic,
ColliderDensity(0.1),
AngularVelocity::ZERO,
ExternalTorque::ZERO,
))
.id(); .id();
let axel_parent_entity = if let Some(steering) = steering { let axel = if let Some(ref steering) = steering {
let neck_builder = commands.spawn((RigidBody::Dynamic, ExternalForce::ZERO, steering.clone()))
RevoluteJointBuilder::new(rake_vec).local_anchor1(Vec3::new(0.0, 0.0, 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)
.insert(neck_joint)
.insert(steering)
.insert(not_sleeping)
.id();
neck
} else { } else {
fork_rb_entity commands.spawn((RigidBody::Dynamic, ExternalForce::ZERO))
}; }
.id();
let axel_joint = RevoluteJoint::new(axel, wheel).with_aligned_axis(Vec3::NEG_X);
commands.spawn(axel_joint);
let axel_builder = RevoluteJointBuilder::new(Vec3::X); // suspension and steering:
let axel_joint = MultibodyJoint::new(axel_parent_entity, axel_builder); if steering.is_some() {
let wheel_damping = Damping { let joint = PrismaticJoint::new(axel, bike)
linear_damping: 0.8, .with_free_axis(suspension_axis)
..Default::default() .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);
} 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);
}; };
commands.spawn(pbr_bundle).insert((
collider,
mass_props,
wheel_damping,
ccd,
not_sleeping,
axel_joint,
wheels_collision_group,
friction,
CyberWheel,
ExternalForce::default(),
Restitution::new(conf.restitution),
SpatialBundle::default(),
TransformInterpolation::default(),
RigidBody::Dynamic,
));
} }
} }
@ -133,9 +116,8 @@ fn gen_tires(conf: &WheelConfig) -> (Mesh, Collider) {
let wheel_rad = conf.radius; let wheel_rad = conf.radius;
let tire_thickness = conf.thickness; let tire_thickness = conf.thickness;
let tire = Tire { let tire = Tire {
radius: wheel_rad, minor_radius: tire_thickness,
ring_radius: tire_thickness, major_radius: wheel_rad,
..Default::default()
}; };
let mut mesh = Mesh::from(tire); let mut mesh = Mesh::from(tire);
@ -161,17 +143,7 @@ fn gen_tires(conf: &WheelConfig) -> (Mesh, Collider) {
for idx in indices.as_slice().chunks_exact(3) { for idx in indices.as_slice().chunks_exact(3) {
idxs.push([idx[0] as u32, idx[1] as u32, idx[2] as u32]); idxs.push([idx[0] as u32, idx[1] as u32, idx[2] as u32]);
} }
let wheel_collider = Collider::convex_decomposition( let wheel_collider = Collider::convex_decomposition_from_mesh(&mesh).unwrap();
&mesh
.attribute(Mesh::ATTRIBUTE_POSITION)
.unwrap()
.as_float3()
.unwrap()
.iter()
.map(|v| Vec3::from_array(*v))
.collect::<Vec<_>>(),
&idxs,
);
(mesh, wheel_collider) (mesh, wheel_collider)
} }

View File

@ -1,4 +1,9 @@
use bevy::prelude::{App, Color, Plugin}; use avian3d::debug_render::PhysicsGizmos;
use bevy::{
color::Srgba,
gizmos::AppGizmoBuilder,
prelude::{App, Color, GizmoConfig, Plugin},
};
// use crate::planet::CyberPlanet; // use crate::planet::CyberPlanet;
@ -9,26 +14,16 @@ pub struct CyberGlamorPlugin;
impl Plugin for CyberGlamorPlugin { impl Plugin for CyberGlamorPlugin {
fn build(&self, app: &mut App) { fn build(&self, app: &mut App) {
{ {
use bevy_rapier3d::render::{ let plugin = avian3d::debug_render::PhysicsDebugPlugin::default();
DebugRenderMode, DebugRenderStyle, RapierDebugRenderPlugin,
};
let style = DebugRenderStyle {
multibody_joint_anchor_color: Color::GREEN.as_rgba_f32(),
..Default::default()
};
let mode = DebugRenderMode::CONTACTS
| DebugRenderMode::SOLVER_CONTACTS
| DebugRenderMode::JOINTS
| DebugRenderMode::RIGID_BODY_AXES;
let rplugin = RapierDebugRenderPlugin { app.add_plugins(plugin).insert_gizmo_config(
style, PhysicsGizmos {
always_on_top: true, contact_point_color: Some(Srgba::GREEN.into()),
enabled: true, contact_normal_color: Some(Srgba::WHITE.into()),
mode, ..Default::default()
}; },
GizmoConfig::default(),
app.add_plugin(rplugin); );
} }
} }
} }

View File

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

View File

@ -1,8 +1,8 @@
use avian3d::prelude::*;
use bevy::{ use bevy::{
prelude::{shape::Icosphere, *}, prelude::*,
render::{color::Color, mesh::Indices}, render::{mesh::Indices, render_asset::RenderAssetUsages},
}; };
use bevy_rapier3d::prelude::*;
use hexasphere::shapes::IcoSphere; use hexasphere::shapes::IcoSphere;
use noise::{HybridMulti, NoiseFn, SuperSimplex}; use noise::{HybridMulti, NoiseFn, SuperSimplex};
use rand::{Rng, SeedableRng}; use rand::{Rng, SeedableRng};
@ -20,20 +20,12 @@ fn spawn_planet(
mut meshes: ResMut<Assets<Mesh>>, mut meshes: ResMut<Assets<Mesh>>,
mut materials: ResMut<Assets<StandardMaterial>>, mut materials: ResMut<Assets<StandardMaterial>>,
) { ) {
//let color = Color::rgb(0.74, 0.5334, 0.176); let (mesh, shape) = gen_planet(PLANET_RADIUS);
let isphere = Icosphere {
radius: PLANET_RADIUS,
subdivisions: 88,
};
let (mesh, shape) = gen_planet(isphere);
let pbody = (RigidBody::Fixed, Ccd { enabled: true });
let pcollide = ( let pcollide = (
shape, shape,
Friction { Friction {
coefficient: 1.2, static_coefficient: 1.2,
..Default::default() ..Default::default()
}, },
Restitution::new(0.8), Restitution::new(0.8),
@ -42,18 +34,22 @@ fn spawn_planet(
commands commands
.spawn(PbrBundle { .spawn(PbrBundle {
mesh: meshes.add(mesh), mesh: meshes.add(mesh),
material: materials.add(Color::WHITE.into()), material: materials.add(Color::WHITE),
..Default::default() ..Default::default()
}) })
.insert(pbody) .insert((
.insert(pcollide) RigidBody::Static,
.insert(CyberPlanet); pcollide,
CyberPlanet,
CollisionLayers::new(u32::MAX, u32::MAX),
CollisionMargin(0.2),
));
} }
pub struct CyberPlanetPlugin; pub struct CyberPlanetPlugin;
impl Plugin for CyberPlanetPlugin { impl Plugin for CyberPlanetPlugin {
fn build(&self, app: &mut App) { fn build(&self, app: &mut App) {
app.add_startup_system(spawn_planet); app.add_systems(Startup, spawn_planet);
} }
} }
@ -61,10 +57,10 @@ impl Plugin for CyberPlanetPlugin {
// utils // utils
//--------------------------------------------------------------------- //---------------------------------------------------------------------
fn gen_planet(sphere: Icosphere) -> (Mesh, Collider) { fn gen_planet(radius: f32) -> (Mesh, Collider) {
// straight-up stolen from Bevy's impl of Mesh from Icosphere, so I can do the // straight-up stolen from Bevy's impl of Mesh from Icosphere, so I can do the
// displacement before normals are calculated. // displacement before normals are calculated.
let generated = IcoSphere::new(sphere.subdivisions, |point| { let generated = IcoSphere::new(79, |point| {
let inclination = point.y.acos(); let inclination = point.y.acos();
let azimuth = point.z.atan2(point.x); let azimuth = point.z.atan2(point.x);
@ -90,7 +86,7 @@ fn gen_planet(sphere: Icosphere) -> (Mesh, Collider) {
let points = noisy_points let points = noisy_points
.iter() .iter()
.map(|&p| (Vec3::from_slice(&p) * sphere.radius).into()) .map(|&p| (Vec3::from_slice(&p) * radius).into())
.collect::<Vec<[f32; 3]>>(); .collect::<Vec<[f32; 3]>>();
for p in &points { for p in &points {
@ -108,10 +104,13 @@ fn gen_planet(sphere: Icosphere) -> (Mesh, Collider) {
} }
let indices = Indices::U32(indices); let indices = Indices::U32(indices);
let collider = Collider::trimesh(points.iter().map(|p| Vect::from_slice(p)).collect(), idxs); let collider = Collider::trimesh(points.iter().map(|p| Vec3::from_slice(p)).collect(), idxs);
let mut mesh = Mesh::new(PrimitiveTopology::TriangleList); let mut mesh = Mesh::new(
mesh.set_indices(Some(indices)); PrimitiveTopology::TriangleList,
RenderAssetUsages::default(),
);
mesh.insert_indices(indices);
mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, points); mesh.insert_attribute(Mesh::ATTRIBUTE_POSITION, points);
//mesh.insert_attribute(Mesh::ATTRIBUTE_UV_0, uvs); //mesh.insert_attribute(Mesh::ATTRIBUTE_UV_0, uvs);
mesh.duplicate_vertices(); mesh.duplicate_vertices();
@ -129,7 +128,9 @@ fn gen_planet(sphere: Icosphere) -> (Mesh, Collider) {
let l = 0.41; let l = 0.41;
let jitter = rng.gen_range(-0.0..=360.0f32); let jitter = rng.gen_range(-0.0..=360.0f32);
let h = jitter; let h = jitter;
let color = Color::hsl(h, PLANET_SATURATION, l).as_linear_rgba_f32(); let color = Color::hsl(h, PLANET_SATURATION, l)
.to_linear()
.to_f32_array();
for _ in 0..3 { for _ in 0..3 {
colors.push(color); colors.push(color);
} }

View File

@ -1,10 +1,13 @@
use bevy::prelude::{ use avian3d::prelude::LinearVelocity;
AlignSelf, App, AssetServer, Color, Commands, Component, Plugin, Query, Res, Style, Text, use bevy::{
TextBundle, TextSection, TextStyle, Transform, With, app::{Startup, Update},
prelude::{
AlignSelf, App, AssetServer, Color, Commands, Component, Plugin, Query, Res, Style, Text,
TextBundle, TextSection, TextStyle, Transform, With,
},
}; };
#[cfg(feature = "inspector")] #[cfg(feature = "inspector")]
use bevy_inspector_egui::quick::WorldInspectorPlugin; use bevy_inspector_egui::quick::WorldInspectorPlugin;
use bevy_rapier3d::prelude::Velocity;
use crate::bike::CyberBikeBody; use crate::bike::CyberBikeBody;
@ -26,7 +29,7 @@ fn setup_ui(mut commands: Commands, asset_server: Res<AssetServer>) {
style: TextStyle { style: TextStyle {
font: asset_server.load("fonts/FiraMono-Medium.ttf"), font: asset_server.load("fonts/FiraMono-Medium.ttf"),
font_size: 40.0, font_size: 40.0,
color: Color::GOLD, color: Color::srgba_u8(255, 215, 0, 230),
}, },
}], }],
..Default::default() ..Default::default()
@ -37,12 +40,12 @@ fn setup_ui(mut commands: Commands, asset_server: Res<AssetServer>) {
} }
fn update_ui( fn update_ui(
state_query: Query<(&Velocity, &Transform), With<CyberBikeBody>>, state_query: Query<(&LinearVelocity, &Transform), With<CyberBikeBody>>,
mut text_query: Query<&mut Text, With<UpText>>, mut text_query: Query<&mut Text, With<UpText>>,
) { ) {
let mut text = text_query.single_mut(); let mut text = text_query.single_mut();
let (velocity, xform) = state_query.single(); let (velocity, xform) = state_query.single();
let speed = velocity.linvel.dot(xform.forward()); let speed = velocity.dot(*xform.forward());
text.sections[0].value = format!("spd: {:.2}", speed); text.sections[0].value = format!("spd: {:.2}", speed);
} }
@ -53,6 +56,7 @@ impl Plugin for CyberUIPlugin {
#[cfg(feature = "inspector")] #[cfg(feature = "inspector")]
app.add_plugin(WorldInspectorPlugin); app.add_plugin(WorldInspectorPlugin);
app.add_startup_system(setup_ui).add_system(update_ui); app.add_systems(Startup, setup_ui)
.add_systems(Update, update_ui);
} }
} }