gutter_runner/game/game.odin
sergeypdev 999a7a4631 Calculate inertia tensor for the convex hull, convert simulation to use full inertia tensor matrix
I couldn't figure out how to diagonalize the inertia tensor matrix so I will go the simle route and just use the full 3x3 matrix
2025-02-02 01:17:35 +04:00

974 lines
23 KiB
Odin

// This file is compiled as part of the `odin.dll` file. It contains the
// procs that `game_hot_reload.exe` will call, such as:
//
// game_init: Sets up the game state
// game_update: Run once per frame
// game_shutdown: Shuts down game and frees memory
// game_memory: Run just before a hot reload, so game.exe has a pointer to the
// game's memory.
// game_hot_reloaded: Run after a hot reload so that the `g_mem` global variable
// can be set to whatever pointer it was in the old DLL.
//
// Note: When compiled as part of the release executable this whole package is imported as a normal
// odin package instead of a DLL.
package game
import "assets"
import "core:c"
import "core:fmt"
import "core:hash"
import "core:log"
import "core:math"
import "core:math/linalg"
import "core:slice"
import "game:halfedge"
import "game:physics"
import "game:physics/bvh"
import "game:physics/collision"
import "libs:tracy"
import rl "vendor:raylib"
import "vendor:raylib/rlgl"
PIXEL_WINDOW_HEIGHT :: 360
Track :: struct {
points: [dynamic]rl.Vector3,
}
World :: struct {
player_pos: rl.Vector3,
track: Track,
physics_scene: physics.Scene,
}
destroy_world :: proc(world: ^World) {
delete(world.track.points)
physics.destroy_physics_scene(&world.physics_scene)
}
Runtime_World :: struct {
world: World,
pause: bool,
solver_state: physics.Solver_State,
car_com: rl.Vector3,
car_handle: physics.Body_Handle,
camera_yaw_pitch: rl.Vector2,
camera_speed: f32,
camera: rl.Camera3D,
}
destroy_runtime_world :: proc(runtime_world: ^Runtime_World) {
destroy_world(&runtime_world.world)
physics.destroy_solver_state(&runtime_world.solver_state)
}
Car :: struct {
pos: rl.Vector3,
}
SOLVER_CONFIG :: physics.Solver_Config {
timestep = 1.0 / 120,
gravity = rl.Vector3{0, -9.8, 0},
substreps_minus_one = 2 - 1,
}
Game_Memory :: struct {
assetman: assets.Asset_Manager,
runtime_world: Runtime_World,
es: Editor_State,
editor: bool,
preview_bvh: int,
preview_node: int,
physics_pause: bool,
free_cam: bool,
}
Track_Edit_State :: enum {
// Point selection
Select,
// Moving points
Move,
}
Move_Axis :: enum {
None,
X,
Y,
Z,
XZ,
XY,
YZ,
}
Editor_State :: struct {
world: World,
mouse_captured: bool,
point_selection: map[int]bool,
track_edit_state: Track_Edit_State,
move_axis: Move_Axis,
total_movement_world: rl.Vector3,
initial_point_pos: rl.Vector3,
}
g_mem: ^Game_Memory
get_runtime_world :: proc() -> ^Runtime_World {
return &g_mem.runtime_world
}
get_world :: proc() -> ^World {
return g_mem.editor ? &g_mem.es.world : &g_mem.runtime_world.world
}
get_editor_state :: proc() -> ^Editor_State {
return &g_mem.es
}
game_camera :: proc() -> rl.Camera2D {
w := f32(rl.GetScreenWidth())
h := f32(rl.GetScreenHeight())
return {
zoom = h / PIXEL_WINDOW_HEIGHT,
target = get_world().player_pos.xy,
offset = {w / 2, h / 2},
}
}
camera_rotation_matrix :: proc() -> matrix[3, 3]f32 {
return linalg.matrix3_from_euler_angles_xy(
get_runtime_world().camera_yaw_pitch.x,
get_runtime_world().camera_yaw_pitch.y,
)
}
camera_forward_vec :: proc() -> rl.Vector3 {
rotation_matrix := camera_rotation_matrix()
return rotation_matrix * rl.Vector3{0, 0, 1}
}
game_camera_3d :: proc() -> rl.Camera3D {
if g_mem.editor || g_mem.free_cam {
return {
position = get_world().player_pos,
up = {0, 1, 0},
fovy = 60,
target = get_world().player_pos + camera_forward_vec(),
projection = .PERSPECTIVE,
}
}
return get_runtime_world().camera
}
ui_camera :: proc() -> rl.Camera2D {
return {zoom = f32(rl.GetScreenHeight()) / PIXEL_WINDOW_HEIGHT}
}
select_track_point :: proc(index: int) {
clear(&g_mem.es.point_selection)
g_mem.es.point_selection[index] = true
}
is_point_selected :: proc() -> bool {
return len(g_mem.es.point_selection) > 0
}
add_track_spline_point :: proc() {
forward := camera_rotation_matrix()[2]
append(&get_world().track.points, get_world().player_pos + forward)
select_track_point(len(&get_world().track.points) - 1)
}
get_movement_axes :: proc(
axis: Move_Axis,
out_axes: ^[2]rl.Vector3,
out_colors: ^[2]rl.Color,
) -> (
axes: []rl.Vector3,
colors: []rl.Color,
) {
switch axis {
case .None:
return out_axes[0:0], {}
case .X:
out_axes[0] = {1, 0, 0}
out_colors[0] = rl.RED
return out_axes[0:1], out_colors[0:1]
case .Y:
out_axes[0] = {0, 1, 0}
out_colors[0] = rl.GREEN
return out_axes[0:1], out_colors[0:1]
case .Z:
out_axes[0] = {0, 0, 1}
out_colors[0] = rl.BLUE
return out_axes[0:1], out_colors[0:1]
case .XZ:
out_axes[0] = {1, 0, 0}
out_axes[1] = {0, 0, 1}
out_colors[0] = rl.RED
out_colors[1] = rl.BLUE
return out_axes[:], out_colors[:]
case .XY:
out_axes[0] = {1, 0, 0}
out_axes[1] = {0, 1, 0}
out_colors[0] = rl.RED
out_colors[1] = rl.GREEN
return out_axes[:], out_colors[:]
case .YZ:
out_axes[0] = {0, 1, 0}
out_axes[1] = {0, 0, 1}
out_colors[0] = rl.GREEN
out_colors[1] = rl.BLUE
return out_axes[:], out_colors[:]
}
return out_axes[0:0], out_colors[0:0]
}
update_runtime_world :: proc(runtime_world: ^Runtime_World, dt: f32) {
world := &runtime_world.world
if !runtime_world.pause {
car_model := assets.get_model(&g_mem.assetman, "assets/toyota_corolla_ae86_trueno.glb")
car_bounds := rl.GetModelBoundingBox(car_model)
runtime_world.car_com = (car_bounds.min + car_bounds.max) / 2
physics.immediate_body(
&world.physics_scene,
&runtime_world.solver_state,
#hash("floor", "fnv32a"),
physics.Body_Config {
initial_pos = {0, -0.5, 0},
initial_rot = linalg.QUATERNIONF32_IDENTITY,
shape = physics.Shape_Box{size = {1000, 1, 1000}},
},
)
runtime_world.car_handle = physics.immediate_body(
&world.physics_scene,
&runtime_world.solver_state,
#hash("car", "fnv32a"),
physics.Body_Config {
initial_pos = {0, 2, 0},
initial_rot = linalg.quaternion_angle_axis(
math.RAD_PER_DEG * 100,
rl.Vector3{0, 1, 0},
),
initial_ang_vel = {0, 0, 0},
shape = physics.Shape_Box{size = car_bounds.max - car_bounds.min},
mass = 100,
},
)
if false {
for x in -3 ..< 3 {
for y in -3 ..< 3 {
physics.immediate_body(
&world.physics_scene,
&runtime_world.solver_state,
hash.fnv32a(slice.to_bytes([]int{(x | y << 8)})),
physics.Body_Config {
initial_pos = {f32(x), 5, f32(y)},
initial_rot = linalg.QUATERNIONF32_IDENTITY,
shape = physics.Shape_Box{size = 0.5},
mass = 10,
},
)
}
}
}
// car_body := physics.get_body(&world.physics_scene, runtime_world.car_handle)
camera := &runtime_world.camera
camera.up = rl.Vector3{0, 1, 0}
camera.fovy = 60
camera.projection = .PERSPECTIVE
// camera.position = physics.body_local_to_world(
// car_body,
// physics.body_world_to_local(
// car_body,
// physics.body_local_to_world(car_body, rl.Vector3{1, 0, -2}),
// ),
// )
camera.target = physics.get_body(&world.physics_scene, runtime_world.car_handle).x
if runtime_world.camera.position == {} {
runtime_world.camera.position = runtime_world.camera.target - rl.Vector3{10, 0, 10}
}
// 1.6 is a good value
wheel_extent_x := f32(2)
wheel_y := f32(-1)
rest := f32(1)
suspension_stiffness := f32(2000)
compliance := 1.0 / suspension_stiffness
damping := f32(0.01)
radius := f32(0.6)
wheel_fl := physics.immediate_suspension_constraint(
&world.physics_scene,
&runtime_world.solver_state,
#hash("FL", "fnv32a"),
{
rel_pos = {-wheel_extent_x, wheel_y, 2.9},
rel_dir = {0, -1, 0},
radius = radius,
rest = rest,
compliance = compliance,
damping = damping,
body = runtime_world.car_handle,
},
)
wheel_fr := physics.immediate_suspension_constraint(
&world.physics_scene,
&runtime_world.solver_state,
#hash("FR", "fnv32a"),
{
rel_pos = {wheel_extent_x, wheel_y, 2.9},
rel_dir = {0, -1, 0},
radius = radius,
rest = rest,
compliance = compliance,
damping = damping,
body = runtime_world.car_handle,
},
)
wheel_rl := physics.immediate_suspension_constraint(
&world.physics_scene,
&runtime_world.solver_state,
#hash("RL", "fnv32a"),
{
rel_pos = {-wheel_extent_x, wheel_y, -2.6},
rel_dir = {0, -1, 0},
radius = radius,
rest = rest,
compliance = compliance,
damping = damping,
body = runtime_world.car_handle,
},
)
wheel_rr := physics.immediate_suspension_constraint(
&world.physics_scene,
&runtime_world.solver_state,
#hash("RR", "fnv32a"),
{
rel_pos = {wheel_extent_x, wheel_y, -2.6},
rel_dir = {0, -1, 0},
radius = radius,
rest = rest,
compliance = compliance,
damping = damping,
body = runtime_world.car_handle,
},
)
drive_wheels := []physics.Suspension_Constraint_Handle{wheel_rl, wheel_rr}
turn_wheels := []physics.Suspension_Constraint_Handle{wheel_fl, wheel_fr}
DRIVE_IMPULSE :: 10
BRAKE_IMPULSE :: 20
TURN_ANGLE :: -f32(30) * math.RAD_PER_DEG
for wheel_handle in drive_wheels {
wheel := physics.get_suspension_constraint(&world.physics_scene, wheel_handle)
wheel.drive_impulse = 0
wheel.brake_impulse = 0
if rl.IsKeyDown(.W) && !g_mem.free_cam {
wheel.drive_impulse = DRIVE_IMPULSE
}
if rl.IsKeyDown(.S) && !g_mem.free_cam {
wheel.brake_impulse = BRAKE_IMPULSE
}
}
for wheel_handle in turn_wheels {
wheel := physics.get_suspension_constraint(&world.physics_scene, wheel_handle)
wheel.turn_angle = 0
if rl.IsKeyDown(.A) && !g_mem.free_cam {
wheel.turn_angle += -TURN_ANGLE
}
if rl.IsKeyDown(.D) && !g_mem.free_cam {
wheel.turn_angle += TURN_ANGLE
}
}
if !g_mem.physics_pause || rl.IsKeyPressed(.PERIOD) {
physics.simulate(&world.physics_scene, &runtime_world.solver_state, SOLVER_CONFIG, dt)
}
}
}
update :: proc() {
tracy.Zone()
if rl.IsKeyPressed(.TAB) {
g_mem.editor = !g_mem.editor
}
if rl.IsKeyPressed(.F1) {
g_mem.free_cam = !g_mem.free_cam
}
dt := rl.GetFrameTime()
// Debug BVH traversal
mesh_bvh := assets.get_bvh(&g_mem.assetman, "assets/toyota_corolla_ae86_trueno.glb")
if rl.IsKeyDown(.LEFT_SHIFT) {
if g_mem.preview_bvh >= 0 && g_mem.preview_bvh < len(mesh_bvh.bvhs) {
b := mesh_bvh.bvhs[g_mem.preview_bvh]
node := &b.nodes[g_mem.preview_node]
if !bvh.is_leaf_node(node^) {
if rl.IsKeyPressed(.LEFT_BRACKET) {
g_mem.preview_node = int(node.child_or_prim_start)
} else if rl.IsKeyPressed(.RIGHT_BRACKET) {
g_mem.preview_node = int(node.child_or_prim_start + 1)
} else if rl.IsKeyPressed(.P) {
g_mem.preview_node = 0
}
}
}
} else {
if rl.IsKeyPressed(.LEFT_BRACKET) {
g_mem.preview_bvh -= 1
g_mem.preview_node = 0
}
if rl.IsKeyPressed(.RIGHT_BRACKET) {
g_mem.preview_bvh += 1
g_mem.preview_node = 0
}
}
if rl.IsKeyPressed(.SPACE) {
g_mem.physics_pause = !g_mem.physics_pause
}
if g_mem.editor {
update_editor(get_editor_state())
} else {
if g_mem.free_cam {
update_free_look_camera(get_editor_state())
}
update_runtime_world(get_runtime_world(), dt)
}
}
catmull_rom_coefs :: proc(
v0, v1, v2, v3: rl.Vector3,
alpha, tension: f32,
) -> (
a, b, c, d: rl.Vector3,
) {
t01 := math.pow(linalg.distance(v0, v1), alpha)
t12 := math.pow(linalg.distance(v1, v2), alpha)
t23 := math.pow(linalg.distance(v2, v3), alpha)
m1 := (1.0 - tension) * (v2 - v1 + t12 * ((v1 - v0) / t01 - (v2 - v0) / (t01 + t12)))
m2 := (1.0 - tension) * (v2 - v1 + t12 * ((v3 - v2) / t23 - (v3 - v1) / (t12 + t23)))
a = 2.0 * (v1 - v2) + m1 + m2
b = -3.0 * (v1 - v2) - m1 - m1 - m2
c = m1
d = v1
return
}
catmull_rom :: proc(a, b, c, d: rl.Vector3, t: f32) -> rl.Vector3 {
t2 := t * t
t3 := t2 * t
return a * t3 + b * t2 + c * t + d
}
draw :: proc() {
tracy.Zone()
rl.BeginDrawing()
defer rl.EndDrawing()
rl.ClearBackground(rl.GRAY)
runtime_world := get_runtime_world()
world := get_world()
camera := game_camera_3d()
points := &world.track.points
interpolated_points := calculate_spline_interpolated_points(points[:], context.temp_allocator)
// collision, segment_idx := raycast_spline_tube(
// interpolated_points,
// rl.GetScreenToWorldRay(rl.GetMousePosition(), camera),
// )
car_body := physics.get_body(&world.physics_scene, runtime_world.car_handle)
car_model := assets.get_model(&g_mem.assetman, "assets/toyota_corolla_ae86_trueno.glb")
mesh_col: bvh.Collision
hit_mesh_idx := -1
rl_ray := rl.GetScreenToWorldRay(rl.GetMousePosition(), camera)
ray := bvh.Ray {
origin = rl_ray.position,
dir = rl_ray.direction,
}
_ = ray
{
rl.BeginMode3D(camera)
defer rl.EndMode3D()
// rl.DrawGrid(100, 1)
physics.draw_debug_scene(&world.physics_scene)
box1_mat := linalg.Matrix4f32(1)
box1_mat = linalg.matrix4_rotate(45 * math.RAD_PER_DEG, rl.Vector3{0, 1, 0}) * box1_mat
box2_mat := linalg.Matrix4f32(1)
box2_mat = linalg.matrix4_translate(rl.Vector3{0.0, 0.2, 0}) * box2_mat
box2_mat = linalg.matrix4_rotate(45 * math.RAD_PER_DEG, rl.Vector3{0, 0, 1}) * box2_mat
// box2_mat = linalg.matrix4_rotate(f32(rl.GetTime()), rl.Vector3{0, -1, 0}) * box2_mat
box2_mat = linalg.matrix4_translate(rl.Vector3{0.0, 0, 0}) * box2_mat
box2_mat = linalg.matrix4_rotate(f32(rl.GetTime()) * 0.1, rl.Vector3{0, 1, 0}) * box2_mat
box1, box2 := collision.Box {
pos = 0,
rad = 0.5,
}, collision.Box {
pos = 0,
rad = 0.5,
}
car_convex := assets.get_convex(&g_mem.assetman, "assets/car_convex.obj")
halfedge.debug_draw_mesh_wires(car_convex.mesh, rl.RED)
rl.DrawSphereWires(car_convex.mesh.center, 0.0, 8, 8, rl.BLUE)
rl.DrawSphereWires(car_convex.center_of_mass, 0.5, 8, 8, rl.RED)
box1_convex := collision.box_to_convex(box1, context.temp_allocator)
box2_convex := collision.box_to_convex(box2, context.temp_allocator)
halfedge.transform_mesh(&box1_convex, box1_mat)
halfedge.transform_mesh(&box2_convex, box2_mat)
// manifold, _ := collision.convex_vs_convex_sat(box1_convex, box2_convex)
// halfedge.debug_draw_mesh_wires(halfedge.Half_Edge_Mesh(box1_convex), rl.RED)
// halfedge.debug_draw_mesh_wires(halfedge.Half_Edge_Mesh(box2_convex), rl.RED)
// {
// rlgl_transform_scope(auto_cast linalg.matrix4_from_quaternion(rot1))
// rl.DrawCubeWiresV(box1.pos, box1.rad * 2, rl.RED)
// }
// {
// rlgl_transform_scope(auto_cast linalg.matrix4_from_quaternion(rot2))
// rl.DrawCubeWiresV(box2.pos, box2.rad * 2, rl.RED)
// }
// for p in manifold.points_a[:manifold.points_len] {
// rl.DrawSphereWires(p, 0.05, 8, 8, rl.BLUE)
// }
// {
// mesh_bvh := assets.get_bvh(&g_mem.assetman, "assets/toyota_corolla_ae86_trueno.glb")
// for &blas, i in mesh_bvh.bvhs {
// mesh := car_model.meshes[i]
// if i == g_mem.preview_bvh {
// bvh.debug_draw_bvh_bounds(
// &blas,
// bvh.bvh_mesh_from_rl_mesh(mesh),
// 0,
// g_mem.preview_node,
// )
// }
// vertices := (cast([^]rl.Vector3)mesh.vertices)[:mesh.vertexCount]
// indices := mesh.indices[:mesh.triangleCount * 3]
// if bvh.traverse_bvh_ray_mesh(
// &blas,
// bvh.Mesh{vertices = vertices, indices = indices},
// ray,
// &mesh_col,
// ) {
// hit_mesh_idx = i
// }
// }
// if mesh_col.hit {
// rl.DrawSphereWires(ray.origin + ray.dir * mesh_col.t, 0.1, 8, 8, rl.RED)
// }
// }
if !g_mem.editor {
car_matrix := rl.QuaternionToMatrix(car_body.q)
car_model.transform = car_matrix
rl.DrawModel(
car_model,
physics.body_local_to_world(car_body, -runtime_world.car_com),
1,
rl.WHITE,
)
} else {
// rl.DrawModel(car_model, 0, 1, rl.WHITE)
}
{
// Debug draw spline road
{
rlgl.EnableWireMode()
defer rlgl.DisableWireMode()
rlgl.Color3f(1, 0, 0)
debug_draw_spline(interpolated_points)
debug_draw_spline_mesh(interpolated_points)
}
if g_mem.editor {
es := &g_mem.es
switch es.track_edit_state {
case .Select:
case .Move:
rlgl.Begin(rlgl.LINES)
defer rlgl.End()
axes_buf: [2]rl.Vector3
colors_buf: [2]rl.Color
axes, colors := get_movement_axes(es.move_axis, &axes_buf, &colors_buf)
for v in soa_zip(axis = axes, color = colors) {
rlgl.Color4ub(v.color.r, v.color.g, v.color.b, v.color.a)
start, end :=
es.initial_point_pos -
v.axis * 100000,
es.initial_point_pos +
v.axis * 100000
rlgl.Vertex3f(start.x, start.y, start.z)
rlgl.Vertex3f(end.x, end.y, end.z)
}
}
}
// if mesh_col.hit {
// mesh := car_model.meshes[hit_mesh_idx]
// vertices := (cast([^]rl.Vector3)mesh.vertices)[:mesh.vertexCount]
// indices := mesh.indices[:mesh.triangleCount * 3]
// car_halfedge := halfedge.mesh_from_vertex_index_list(vertices, indices, 3, context.temp_allocator)
//
// face_idx := halfedge.Face_Index(mesh_col.prim)
// face := car_halfedge.faces[face_idx]
// first_edge_idx := face.edge
//
// first := true
// cur_edge_idx := first_edge_idx
// for first || cur_edge_idx != first_edge_idx {
// first = false
// edge := car_halfedge.edges[cur_edge_idx]
// cur_edge_idx = edge.next
//
// if edge.twin >= 0 {
// twin_edge := car_halfedge.edges[edge.twin]
// face := twin_edge.face
//
// i1, i2, i3 := indices[face * 3 + 0], indices[face * 3 + 1], indices[face * 3 + 2]
// v1, v2, v3 := vertices[i1], vertices[i2], vertices[i3]
//
// rl.DrawTriangle3D(v1, v2, v3, rl.RED)
// }
// }
// }
//
}
}
{
rl.BeginMode2D(ui_camera())
defer rl.EndMode2D()
rl.DrawFPS(0, 0)
if g_mem.editor {
rl.DrawText("Editor", 5, 5, 8, rl.ORANGE)
rl.DrawText(
fmt.ctprintf(
"mesh: %v, aabb tests: %v, tri tests: %v",
hit_mesh_idx,
mesh_col.aabb_tests,
mesh_col.triangle_tests,
),
5,
32,
8,
rl.ORANGE,
)
rl.DrawText(
fmt.ctprintf("bvh: %v, node: %v", g_mem.preview_bvh, g_mem.preview_node),
5,
48,
8,
rl.ORANGE,
)
switch g_mem.es.track_edit_state {
case .Select:
case .Move:
rl.DrawText(
fmt.ctprintf("%v %v", g_mem.es.move_axis, g_mem.es.total_movement_world),
5,
16,
8,
rl.ORANGE,
)
}
} else {
car := physics.get_body(&world.physics_scene, runtime_world.car_handle)
rl.DrawText(
fmt.ctprintf(
"p: %v\nv: %v\nw: %v\ng: %v",
car.x,
car.v,
car.w,
SOLVER_CONFIG.gravity,
),
5,
32,
8,
rl.ORANGE,
)
}
}
if g_mem.editor {
es := &g_mem.es
points_len := len(points)
if points_len > 0 {
// Add point before first
{
tangent: rl.Vector3
if points_len > 1 {
tangent = linalg.normalize0(points[1] - points[0])
} else {
tangent = rl.Vector3{-1, 0, 0}
}
new_point_pos := points[0] - tangent * 4
if (spline_handle(
new_point_pos,
camera,
false,
rl.GuiIconName.ICON_TARGET_POINT,
)) {
inject_at(&world.track.points, 0, new_point_pos)
log.debugf("add point before 0")
}
}
// Add point after last
{
tangent: rl.Vector3
if points_len > 1 {
tangent = linalg.normalize0(points[points_len - 1] - points[points_len - 2])
} else {
tangent = rl.Vector3{-1, 0, 0}
}
new_point_pos := points[points_len - 1] + tangent * 4
if (spline_handle(
new_point_pos,
camera,
false,
rl.GuiIconName.ICON_TARGET_POINT,
)) {
inject_at(&world.track.points, points_len - 1 + 1, new_point_pos)
log.debugf("add point before 0")
}
}
}
selected_point := false
for i in 0 ..< points_len {
if i < points_len - 1 {
t := (f32(i) + 0.5) / f32(points_len)
middle_pos := sample_spline(points[:], t)
if (spline_handle(middle_pos, camera, false, rl.GuiIconName.ICON_TARGET_POINT)) {
inject_at(&world.track.points, i + 1, middle_pos)
log.debugf("add point after %d", i)
}
}
if spline_handle(world.track.points[i], camera, es.point_selection[i]) {
if !rl.IsKeyDown(.LEFT_CONTROL) {
clear(&g_mem.es.point_selection)
}
g_mem.es.point_selection[i] = true
selected_point = true
}
}
if rl.IsMouseButtonPressed(.LEFT) && !selected_point {
clear(&g_mem.es.point_selection)
}
}
// axis lines
if g_mem.editor {
size := f32(100)
pos := rl.Vector2{20, f32(rl.GetScreenHeight()) - 20 - size}
view_rotation := linalg.transpose(rl.GetCameraMatrix(camera))
view_rotation[3].xyz = 0
view_proj := view_rotation * rl.MatrixOrtho(-1, 1, 1, -1, -1, 1)
center := (rl.Vector4{0, 0, 0, 1} * view_proj).xy * 0.5 + 0.5
x_axis := (rl.Vector4{1, 0, 0, 1} * view_proj).xy * 0.5 + 0.5
y_axis := (rl.Vector4{0, 1, 0, 1} * view_proj).xy * 0.5 + 0.5
z_axis := (rl.Vector4{0, 0, 1, 1} * view_proj).xy * 0.5 + 0.5
old_width := rlgl.GetLineWidth()
rlgl.SetLineWidth(4)
defer rlgl.SetLineWidth(old_width)
rl.DrawLineV(pos + center * size, pos + x_axis * size, rl.RED)
rl.DrawLineV(pos + center * size, pos + y_axis * size, rl.GREEN)
rl.DrawLineV(pos + center * size, pos + z_axis * size, rl.BLUE)
}
}
spline_handle :: proc(
world_pos: rl.Vector3,
camera: rl.Camera,
selected: bool,
icon := rl.GuiIconName.ICON_NONE,
size := f32(20),
) -> (
clicked: bool,
) {
if linalg.dot(camera.target - camera.position, world_pos - camera.position) < 0 {
return
}
pos := rl.GetWorldToScreen(world_pos, camera)
min, max := pos - size, pos + size
mouse_pos := rl.GetMousePosition()
is_hover :=
(mouse_pos.x >= min.x &&
mouse_pos.y >= min.y &&
mouse_pos.x <= max.x &&
mouse_pos.y <= max.y)
rl.DrawCircleV(pos, size / 2, selected ? rl.BLUE : (is_hover ? rl.ORANGE : rl.WHITE))
if icon != .ICON_NONE {
rl.GuiDrawIcon(
icon,
c.int(pos.x) - 7,
c.int(pos.y) - 7,
1,
selected || is_hover ? rl.WHITE : rl.BLACK,
)
}
// rl.DrawRectangleV(pos, size, selected ? rl.BLUE : (is_hover ? rl.ORANGE : rl.WHITE))
return rl.IsMouseButtonPressed(.LEFT) && is_hover
}
@(export)
game_update :: proc() -> bool {
tracy.Zone()
defer tracy.FrameMark()
update()
draw()
return !rl.WindowShouldClose()
}
@(export)
game_init_window :: proc() {
tracy.SetThreadName("Main")
rl.SetConfigFlags({.WINDOW_RESIZABLE, .VSYNC_HINT})
rl.InitWindow(1280, 720, "Odin + Raylib + Hot Reload template!")
rl.SetExitKey(.KEY_NULL)
rl.SetWindowPosition(200, 200)
rl.SetTargetFPS(120)
}
@(export)
game_init :: proc() {
g_mem = new(Game_Memory)
g_mem^ = Game_Memory{}
game_hot_reloaded(g_mem)
}
@(export)
game_shutdown :: proc() {
assets.shutdown(&g_mem.assetman)
destroy_world(&g_mem.es.world)
delete(g_mem.es.point_selection)
destroy_runtime_world(&g_mem.runtime_world)
free(g_mem)
}
@(export)
game_shutdown_window :: proc() {
rl.CloseWindow()
}
@(export)
game_memory :: proc() -> rawptr {
return g_mem
}
@(export)
game_memory_size :: proc() -> int {
return size_of(Game_Memory)
}
@(export)
game_hot_reloaded :: proc(mem: rawptr) {
g_mem = (^Game_Memory)(mem)
}
@(export)
game_force_reload :: proc() -> bool {
return rl.IsKeyPressed(.F5)
}
@(export)
game_force_restart :: proc() -> bool {
return rl.IsKeyPressed(.F6)
}