Force based zero g movement component

This commit is contained in:
2025-11-15 22:38:24 +01:00
parent 3647aa599d
commit ec69ed2ee5
3 changed files with 115 additions and 98 deletions

View File

@ -58,29 +58,20 @@ func _ready():
camera.process_mode = Node.PROCESS_MODE_ALWAYS
func _process(delta: float) -> void:
func _process(_delta: float) -> void:
camera_pivot.global_transform = camera_anchor.get_global_transform_interpolated()
func _physics_process(delta: float):
# 1. Apply Mouse Rotation (Universal head look)
func _physics_process(_delta: float):
_apply_mouse_rotation()
if zero_g_movemement_component: # Fallback to ZeroG controller (for initiating reach)
zero_g_movemement_component.process_movement(delta, _move_input, _vertical_input, _roll_input, _l_click_input, _r_click_input)
# 3. Integrate Angular Velocity (Universal)
_integrate_angular_velocity(delta)
# 4. Apply Linear Velocity & Collision (Universal)
# Use move_and_slide for states affected by gravity/floor or zero-g collisions
move_and_collide(linear_velocity * delta)
# 5. Reset Inputs
_reset_inputs()
func _integrate_forces(state: PhysicsDirectBodyState3D):
pass
# 2. Let the active movement controller apply its forces
if zero_g_movemement_component:
# We pass the physics state and delta time (state.step)
zero_g_movemement_component.process_movement(state.step, _move_input, _vertical_input, _roll_input, _l_click_input, _r_click_input)
# --- Universal Rotation ---
func _apply_mouse_rotation():
@ -105,21 +96,6 @@ func _integrate_angular_velocity(delta: float):
if angular_velocity.length_squared() < 0.0001:
angular_velocity = Vector3.ZERO
# func _handle_basic_collision(collision: KinematicCollision3D):
# var surface_normal = collision.get_normal()
# velocity = velocity.bounce(surface_normal)
# velocity *= (1.0 - collision_energy_loss * 0.5)
# --- Public Helper for Controllers ---
# Applies torque affecting angular velocity
# func add_torque(torque_global: Vector3, delta: float):
# # Calculate effective inertia (base + suit multiplier if applicable)
# var effective_inertia = base_inertia * (eva_suit_component.inertia_multiplier if eva_suit_component else 1.0)
# if effective_inertia <= 0: effective_inertia = 1.0 # Safety prevent division by zero
# # Apply change directly to angular velocity using the global torque
# angular_velocity += (torque_global / effective_inertia) * delta
# --- Input Setters/Resets (Add vertical to set_movement_input) ---
func set_movement_input(move: Vector2, roll: float, vertical: float): _move_input = move; _roll_input = roll; _vertical_input = vertical
func set_interaction_input(interact_input: PlayerController3D.KeyInput): _interact_input = interact_input

View File

@ -6,8 +6,8 @@ class_name EVAMovementComponent
var pawn: CharacterPawn3D
## EVA Parameters (Moved from ZeroGPawn)
@export var orientation_speed: float = 20.0 # Used for orienting body to camera
@export var linear_acceleration: float = 20.0
@export var orientation_speed: float = 1.0 # Used for orienting body to camera
@export var linear_acceleration: float = 1.0
@export var roll_torque_acceleration: float = 2.5
@export var angular_damping: float = 0.95 # Base damping applied by pawn, suit might add more?
@export var inertia_multiplier: float = 1.0 # How much the suit adds to pawn's base inertia (placeholder)
@ -46,7 +46,7 @@ func process_movement(delta: float, move_input: Vector2, vertical_input: float,
# Apply regular movement/torque only if not stabilizing
_apply_floating_movement(delta, move_input, vertical_input, roll_input)
func apply_thrusters(pawn: CharacterPawn3D, delta: float, move_input: Vector2, vertical_input: float, roll_input: float):
func apply_thrusters(delta: float, move_input: Vector2, vertical_input: float, roll_input: float):
if not is_instance_valid(pawn): return
# Apply Linear Velocity
@ -58,7 +58,7 @@ func apply_thrusters(pawn: CharacterPawn3D, delta: float, move_input: Vector2, v
var combined_move_dir = move_dir_horizontal + move_dir_vertical
if combined_move_dir != Vector3.ZERO:
pawn.apply_central_force(combined_move_dir * linear_acceleration * delta)
pawn.apply_central_force(combined_move_dir * linear_acceleration)
# Apply Roll Torque
var roll_torque_global = -pawn.basis.z * (roll_input) * roll_torque_acceleration * delta # Sign fixed
@ -86,7 +86,7 @@ func _apply_floating_movement(delta: float, move_input: Vector2, vertical_input:
var combined_move_dir = move_dir_horizontal + move_dir_vertical
if combined_move_dir != Vector3.ZERO:
pawn.apply_central_force(combined_move_dir.normalized() * linear_acceleration * delta)
pawn.apply_central_force(combined_move_dir.normalized() * linear_acceleration)
# --- Apply Roll Torque ---
# Calculate torque magnitude based on input
var roll_acceleration = pawn.basis.z * (-roll_input) * roll_torque_acceleration * delta

View File

@ -10,20 +10,21 @@ var camera_pivot: Node3D
var current_grip: GripArea3D = null # Use GripArea3D type hint
var nearby_grips: Array[GripArea3D] = []
# --- Reach Parameters ---
@export var reach_speed: float = 10.0 # Speed pawn moves towards grip
@export var reach_orient_speed: float = 10.0 # Speed pawn orients to grip
# --- Grip damping parameters ---
@export var gripping_linear_damping: float = 50.0 # How quickly velocity stops
@export var gripping_linear_damping: float = 6.0 # How quickly velocity stops
@export var gripping_linear_kd: float = 2 * sqrt(gripping_linear_damping) # How quickly velocity stops
@export var gripping_angular_damping: float = 5.0 # How quickly spin stops
@export var gripping_orient_speed: float = 2.0 # How quickly pawn rotates to face grip
@export var gripping_angular_damping: float = 3.0 # How quickly spin stops
@export var gripping_orient_speed: float = 2 * sqrt(gripping_angular_damping) # How quickly pawn rotates to face grip
var _target_basis: Basis # The orientation the PD controller is currently seeking
var _manual_roll_timer: Timer
@export var manual_roll_reset_delay: float = 3.0 # Time in seconds to wait before auto-aligning
@export var manual_roll_speed: float = 2.0 # How fast (rad/s) to rotate the target
# --- Climbing parameters ---
@export var climb_speed: float = 2.0
@export var grip_handover_distance: float = 1 # How close to next grip to initiate handover
@export var climb_acceleration: float = 10.0 # How quickly pawn reaches climb_speed
@export var climb_acceleration: float = 1.0 # How quickly pawn reaches climb_speed
@export var climb_angle_threshold_deg: float = 120.0 # How wide the forward cone is
@export var release_past_grip_threshold: float = 0.4 # How far past the grip origin before releasing
var next_grip_target: GripArea3D = null # The grip we are trying to transition to
@ -60,30 +61,31 @@ func _ready():
camera_pivot = pawn.get_node_or_null("CameraPivot")
if not camera_pivot: printerr("ZeroGMovementComponent couldn't find CameraPivot")
_manual_roll_timer = Timer.new()
_manual_roll_timer.one_shot = true
_manual_roll_timer.wait_time = manual_roll_reset_delay
_manual_roll_timer.timeout.connect(_on_manual_roll_timeout)
add_child(_manual_roll_timer)
# --- Standardized Movement API ---
## Called by Pawn when relevant state is active (e.g., GRABBING_GRIP, REACHING_MOVE)
func process_movement(delta: float, move_input: Vector2, vertical_input: float, roll_input: float, reach_input: PlayerController3D.KeyInput, release_input: PlayerController3D.KeyInput):
if not is_instance_valid(pawn): return
_update_state(
delta,
move_input,
reach_input,
release_input
)
_update_state(move_input, reach_input, release_input)
match current_state:
MovementState.IDLE:
_process_idle(delta, move_input, vertical_input, roll_input, release_input)
MovementState.REACHING:
_process_reaching(delta)
_process_reaching()
MovementState.GRIPPING:
_apply_grip_physics(delta, move_input, roll_input)
MovementState.CLIMBING:
_apply_climb_physics(delta, move_input)
_apply_climb_physics(move_input)
MovementState.SEEKING_CLIMB:
_process_seeking_climb(delta, move_input)
_process_seeking_climb(move_input)
MovementState.CHARGING_LAUNCH:
_handle_launch_charge(delta)
@ -107,7 +109,6 @@ func _on_exit_state(state: MovementState):
#_release_current_grip()
func _update_state(
_delta: float,
move_input: Vector2,
reach_input: PlayerController3D.KeyInput,
release_input: PlayerController3D.KeyInput,
@ -173,7 +174,7 @@ func _process_idle(delta: float, move_input: Vector2, vertical_input: float, rol
if release_input.held and is_instance_valid(pawn.eva_suit_component):
pawn.eva_suit_component._orient_pawn(delta) # Use suit's orient
func _process_reaching(_delta: float):
func _process_reaching():
# TODO: Drive IK target towards current_grip.get_grip_transform().origin
# TODO: Monitor distance / animation state
# For now, we just instantly grip.
@ -189,42 +190,25 @@ func _apply_grip_physics(delta: float, _move_input: Vector2, roll_input: float):
# TODO: Later, replace step 2 and 3 with IK driving the hand bone to the target_transform.origin,
# while the physics/orientation logic stops the main body's momentum.
# --- 1. Calculate Target Transform (Same as before) ---
var grip_base_transform = current_grip.global_transform
var target_direction = grip_base_transform.basis.z.normalized()
var hold_distance = _get_hold_distance()
var target_position = grip_base_transform.origin + target_direction * hold_distance
var target_basis = _choose_grip_orientation(grip_base_transform.basis)
# --- 2. Apply Linear Force (PD Controller) ---
var error_pos = target_position - pawn.global_position
# Simple P-controller for velocity (acts as a spring)
# We get the force from the PD controller and apply it as acceleration.
var force = MotionUtils.calculate_pd_position_force(
target_position,
pawn.global_position,
pawn.linear_velocity, # Use linear_velocity (from RigidBody3D)
gripping_linear_damping, # Kp
gripping_linear_damping # Kd
)
# Simple D-controller (damping)
# target_velocity_pos -= pawn.linear_velocity * gripping_angular_damping # 'angular_damping' here acts as Kd
# TODO: Add less force the smaller error_pos is to stop ocillating around target pos
pawn.apply_central_force((force / pawn.mass) * delta)
# --- 3. Apply Angular Force (PD Controller) ---
# --- 2. Calculate Target Transform ---
if not is_zero_approx(roll_input):
# Manual Roll Input (applies torque)
var roll_torque_global = pawn.global_transform.basis.z * (-roll_input) * gripping_orient_speed # Use global Z
pawn.apply_torque(roll_torque_global * delta)
# User is rolling. Stop the reset timer.
_manual_roll_timer.stop()
# Rotate the current target basis around the grip's Z-axis
var grip_z_axis = current_grip.global_basis.z
_target_basis = _target_basis.rotated(grip_z_axis, -roll_input * manual_roll_speed * delta)
else:
# Auto-Orient (PD Controller)
_apply_orientation_torque(target_basis, delta)
# User is not rolling. Start the timer if it's not already running.
if _manual_roll_timer.is_stopped():
_manual_roll_timer.start()
func _apply_climb_physics(delta: float, move_input: Vector2):
# --- 3. Apply Linear Force (PD Controller) ---
pawn.apply_central_force(_get_hold_force())
_apply_orientation_torque(_target_basis)
func _apply_climb_physics(move_input: Vector2):
if not is_instance_valid(pawn) or not is_instance_valid(current_grip):
_stop_climb(true); return
@ -247,19 +231,38 @@ func _apply_climb_physics(delta: float, move_input: Vector2):
_release_current_grip(move_input)
return # State changed to IDLE
# 5. Apply Movement Force
# 5. Apply Combined Forces for Climbing & Holding
# --- Force 1: Positional Hold (From _apply_grip_physics) ---
# Calculate the force needed to stay at that position
var force_hold = _get_hold_force()
# --- Force 2: Climbing Movement ---
var target_velocity = climb_direction * climb_speed
var error_vel = target_velocity - pawn.linear_velocity
var force = error_vel * climb_acceleration # Kp = climb_acceleration
pawn.apply_central_force(force * delta)
var force_climb = error_vel * climb_acceleration # Kp = climb_acceleration
# Find the part of the "hold" force that is parallel to our climb direction
var force_hold_parallel = force_hold.project(climb_direction)
# Check if that parallel part is pointing *against* our climb
if force_hold_parallel.dot(climb_direction) < 0:
# If it is, remove it from the hold force.
# This leaves only the perpendicular (offset-correcting) force.
force_hold = force_hold - force_hold_parallel
# --- Combine and Apply ---
# We apply *both* forces. The hold force will manage the offset,
# while the climb force will overpower it in the climb direction.
var total_force = force_hold + force_climb
pawn.apply_central_force(total_force)
# 6. Apply Angular Force (Auto-Orient to current grip)
var grip_base_transform = current_grip.global_transform
var target_basis = _choose_grip_orientation(grip_base_transform.basis)
_apply_orientation_torque(target_basis, delta)
var target_basis = _choose_grip_orientation(current_grip.global_basis)
_apply_orientation_torque(target_basis)
func _process_seeking_climb(_delta: float, move_input: Vector2):
func _process_seeking_climb(move_input: Vector2):
# If the player's input has changed from what initiated the seek, cancel it.
if not move_input.is_equal_approx(_seeking_climb_input):
var target_grip = _find_best_grip()
@ -285,6 +288,11 @@ func _attempt_grip(target_grip: GripArea3D) -> bool:
if is_instance_valid(old_grip) and old_grip != target_grip:
old_grip.release(pawn)
_manual_roll_timer.stop()
_target_basis = _choose_grip_orientation(target_grip.global_basis)
current_grip = target_grip
current_grip = target_grip
next_grip_target = null
_seeking_climb_input = Vector2.ZERO
@ -387,6 +395,8 @@ func _release_current_grip(move_input: Vector2 = Vector2.ZERO):
current_grip.release(pawn)
current_grip = null
_manual_roll_timer.stop()
# If we were climbing and are still holding a climb input, start seeking.
if move_input != Vector2.ZERO:
current_state = MovementState.SEEKING_CLIMB
@ -423,16 +433,16 @@ func _stop_climb(release_grip: bool):
else:
current_state = MovementState.GRIPPING # Go back to stationary gripping
func _apply_orientation_torque(target_basis: Basis, delta: float):
func _apply_orientation_torque(target_basis: Basis):
var torque = MotionUtils.calculate_pd_rotation_torque(
target_basis,
pawn.global_basis,
pawn.angular_velocity, # Use angular_velocity (from RigidBody3D)
gripping_orient_speed, # Kp
gripping_orient_speed # Kd
gripping_angular_damping # Kd
)
pawn.apply_torque(torque * delta)
pawn.apply_torque(torque)
# --- Launch helpers ---
func _start_charge(move_input: Vector2):
@ -451,14 +461,17 @@ func _start_charge(move_input: Vector2):
func _handle_launch_charge(delta: float):
# hold on to current grip
pawn.apply_central_force(_get_hold_force())
launch_charge = min(launch_charge + launch_charge_rate * delta, max_launch_speed)
func _execute_launch(move_input: Vector2):
if not is_instance_valid(current_grip): return # Safety check
launch_charge = 0.0
_release_current_grip(move_input) # Release AFTER calculating direction
pawn.apply_impulse(launch_direction * launch_charge)
launch_charge = 0.0
# Instead of going to IDLE, go to SEEKING_CLIMB to find the next grip.
# The move_input that started the launch is what we'll use for the seek direction.
@ -467,6 +480,34 @@ func _execute_launch(move_input: Vector2):
print("ZeroGMovementComponent: Launched with speed ", pawn.linear_velocity.length(), " and now SEEKING_CLIMB")
# --- Force Calculation Helpers ---
func _get_hold_force() -> Vector3:
if not is_instance_valid(pawn) or not is_instance_valid(current_grip):
return Vector3.ZERO
var grip_base_transform = current_grip.global_transform
var target_direction = grip_base_transform.basis.z.normalized()
var hold_distance = _get_hold_distance()
var target_position = grip_base_transform.origin + target_direction * hold_distance
# Calculate the force needed to stay at that position
var force_hold = MotionUtils.calculate_pd_position_force(
target_position,
pawn.global_position,
pawn.linear_velocity,
gripping_linear_damping, # Kp
gripping_linear_kd # Kd
)
return force_hold
# --- Manual Roll Reset ---
func _on_manual_roll_timeout():
# Timer fired. This means the user hasn't touched roll for [delay] seconds.
# We smoothly reset the _target_basis back to the closest grip orientation.
if is_instance_valid(current_grip):
_target_basis = _choose_grip_orientation(current_grip.global_basis)
# --- Signal Handlers ---
func on_grip_area_entered(area: Area3D):
if area is GripArea3D: # Check if the entered area is actually a GripArea3D node