From 5721c05e3ceb0591a79885dfbe5e28628e19a90a Mon Sep 17 00:00:00 2001 From: "C. J. Howard" Date: Fri, 11 Jun 2021 21:41:16 +0800 Subject: [PATCH] Remove cart namespace, add more mesh-related functions, add initial test of quadsphere-based terrain LOD using quadtree faces --- src/cart/cart.hpp | 28 - src/entity/components/observer.hpp | 4 +- src/entity/components/terrain.hpp | 7 + src/entity/systems/terrain.cpp | 571 ++++++++++++++---- src/entity/systems/terrain.hpp | 81 ++- src/game/bootloader.cpp | 4 +- src/game/states/play-state.cpp | 14 +- src/geom/mesh-functions.cpp | 50 ++ src/geom/mesh-functions.hpp | 9 + src/geom/mesh.cpp | 110 +++- src/geom/mesh.hpp | 16 +- .../relief-map.cpp => geom/meshes/grid.cpp} | 84 +-- .../relief-map.hpp => geom/meshes/grid.hpp} | 24 +- src/renderer/vertex-attributes.hpp | 3 + 14 files changed, 764 insertions(+), 241 deletions(-) delete mode 100644 src/cart/cart.hpp rename src/{cart/relief-map.cpp => geom/meshes/grid.cpp} (57%) rename src/{cart/relief-map.hpp => geom/meshes/grid.hpp} (60%) diff --git a/src/cart/cart.hpp b/src/cart/cart.hpp deleted file mode 100644 index d789e93..0000000 --- a/src/cart/cart.hpp +++ /dev/null @@ -1,28 +0,0 @@ -/* - * Copyright (C) 2021 Christopher J. Howard - * - * This file is part of Antkeeper source code. - * - * Antkeeper source code is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Antkeeper source code is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Antkeeper source code. If not, see . - */ - -#ifndef ANTKEEPER_CART_HPP -#define ANTKEEPER_CART_HPP - -/// Cartography-related functions -namespace cart {} - -#include "relief-map.hpp" - -#endif // ANTKEEPER_CART_HPP diff --git a/src/entity/components/observer.hpp b/src/entity/components/observer.hpp index 9c860e6..8b8bff3 100644 --- a/src/entity/components/observer.hpp +++ b/src/entity/components/observer.hpp @@ -22,6 +22,7 @@ #include "entity/id.hpp" #include "utility/fundamental-types.hpp" +#include "scene/camera.hpp" namespace entity { namespace component { @@ -30,9 +31,10 @@ namespace component { struct observer { entity::id reference_body_eid; - double altitude; + double elevation; double latitude; double longitude; + scene::camera* camera; }; } // namespace component diff --git a/src/entity/components/terrain.hpp b/src/entity/components/terrain.hpp index 4351b93..6e5a7bd 100644 --- a/src/entity/components/terrain.hpp +++ b/src/entity/components/terrain.hpp @@ -20,6 +20,7 @@ #ifndef ANTKEEPER_ENTITY_COMPONENT_TERRAIN_HPP #define ANTKEEPER_ENTITY_COMPONENT_TERRAIN_HPP +#include "renderer/material.hpp" #include namespace entity { @@ -29,6 +30,12 @@ struct terrain { /// Function object which returns elevation (in meters) given latitude (radians) and longitude (radians). std::function elevation; + + /// Maximum level of detail (maximum quadtree depth level) + std::size_t max_lod; + + /// Material for terrain patches; + material* patch_material; }; } // namespace component diff --git a/src/entity/systems/terrain.cpp b/src/entity/systems/terrain.cpp index 00d1434..c85bfd3 100644 --- a/src/entity/systems/terrain.cpp +++ b/src/entity/systems/terrain.cpp @@ -18,119 +18,21 @@ */ #include "entity/systems/terrain.hpp" -#include "utility/fundamental-types.hpp" +#include "entity/components/celestial-body.hpp" #include "entity/components/observer.hpp" #include "entity/components/terrain.hpp" -#include "entity/components/celestial-body.hpp" +#include "geom/meshes/grid.hpp" +#include "geom/mesh-functions.hpp" +#include "geom/morton.hpp" #include "geom/quadtree.hpp" - - -/** - * A cube with six quadtrees as faces. - */ -struct quadtree_cube -{ - typedef geom::quadtree32 quadtree_type; - typedef quadtree_type::node_type node_type; - - void clear(); - - /** - * Refines the quadtree cube. - * - * @param threshold Function object which, given a quadsphere face index and quadtree node, returns `true` if the node should be subdivided, and `false` otherwise. - */ - void refine(const std::function& threshold); - - quadtree_type faces[6]; -}; - -void quadtree_cube::clear() -{ - for (std::uint8_t i = 0; i < 6; ++i) - faces[i].clear(); -} - -void quadtree_cube::refine(const std::function& threshold) -{ - for (std::uint8_t i = 0; i < 6; ++i) - { - for (auto it = faces[i].begin(); it != faces[i].end(); ++it) - { - node_type node = *it; - - if (threshold(i, node)) - faces[i].insert(quadtree_type::child(node, 0)); - } - } -} - -/* -terrain_qtc.refine -( - [observer](std::uint8_t face_index, quadtree_cube_type::node_type node) -> bool - { - // Extract morton location code - quadtree_type::node_type location = quadtree_type::location(node); - quadtree_type::node_type morton_x; - quadtree_type::node_type morton_y; - geom::morton::decode(location, morton_x, morton_y); - - // Extract depth - quadtree_type::node_type depth = quadtree_type::depth(node); - - // Determine fractional side length at depth - float length = 1.0f / std::exp2(depth); - - // Determine fractional center of node - float3 center; - center.x = (static_cast(morton_x) * length + length * 0.5f) * 2.0f - 1.0f; - center.y = (static_cast(morton_y) * length + length * 0.5f) * 2.0f - 1.0f; - center.z = 1.0f; - - // Project node center onto unit sphere - center = math::normalize(center); - - // Rotate projected center into sphere space - center = face_rotations[face_index] * center; - - // Scale center by body radius - center *= body_radius; - - // Calculate distance from observer to node center - float distance = math::length(projected_center - observer_location); - - if (depth < 4 && distance < ...) - return true; - - return false; - } -); -*/ - -/** - * Queries a quad sphere for a list of leaf nodes. Leaf nodes will be inserted in the set - * - * - * 0. If observer position changed more than x amount: - * 1. Clear quad sphere - * 2. Insert leaves based on observer distance. - * 3. Pass quad sphere to tile generation function. - * 3. Iterate leaves, deriving the face, depth, and morton location from each leaf index. - * 4. Face, depth, and morton location can be used to determine latitude, longitude, and generate tiles. - * 5. Generated tiles cached and added to scene. - * 6. Record position of observer - */ - -/** - * Lat, lon determination: - * - * 1. Use morton location and depth to determine the x-y coordinates on a planar cube face. - * 2. Project x-y coordinates onto sphere. - * 3. Rotate coordinates according to face index. - * 4. Convert cartesian coordinates to spherical coordinates. - */ - +#include "geom/spherical.hpp" +#include "gl/vertex-attribute-type.hpp" +#include "math/constants.hpp" +#include "math/quaternion-operators.hpp" +#include "renderer/vertex-attributes.hpp" +#include "utility/fundamental-types.hpp" +#include +#include namespace entity { namespace system { @@ -138,14 +40,27 @@ namespace system { terrain::terrain(entity::registry& registry): updatable(registry), patch_subdivisions(0), + patch_base_mesh(nullptr), patch_vertex_size(0), patch_vertex_count(0), - patch_vertex_data(nullptr) + patch_vertex_data(nullptr), + patch_scene_collection(nullptr), + max_error(0.0) { - // position + uv + normal + tangent + barycentric - patch_vertex_size = 3 + 2 + 3 + 4 + 3; + // Build set of quaternions to rotate quadtree cube coordinates into BCBF space according to face index + face_rotations[0] = math::quaternion::identity(); // +x + face_rotations[1] = math::quaternion::rotate_z(math::pi); // -x + face_rotations[2] = math::quaternion::rotate_z( math::half_pi); // +y + face_rotations[3] = math::quaternion::rotate_z(-math::half_pi); // -y + face_rotations[4] = math::quaternion::rotate_y(-math::half_pi); // +z + face_rotations[5] = math::quaternion::rotate_y( math::half_pi); // -z + // Specify vertex size and stride + // (position + uv + normal + tangent + barycentric + target) + patch_vertex_size = 3 + 2 + 3 + 4 + 3 + 3; + patch_vertex_stride = patch_vertex_size * sizeof(float); + // Init patch subdivisions to zero set_patch_subdivisions(0); registry.on_construct().connect<&terrain::on_terrain_construct>(this); @@ -157,23 +72,171 @@ terrain::~terrain() void terrain::update(double t, double dt) { - // Subdivide or collapse quad sphere - registry.view().each( - [&](entity::id observer_eid, const auto& observer) + // Refine the level of detail of each terrain quadsphere + registry.view().each( + [&](entity::id terrain_eid, const auto& terrain_component, const auto& terrain_body) { - // Skip observers with null reference body - if (observer.reference_body_eid == entt::null) - return; - - // Skip observers with non-body or non-terrestrial reference bodies - if (!registry.has(observer.reference_body_eid) || - !registry.has(observer.reference_body_eid)) - return; + // Retrieve terrain quadsphere + terrain_quadsphere* quadsphere = terrain_quadspheres[terrain_eid]; - const auto& celestial_body = registry.get(observer.reference_body_eid); - const auto& terrain = registry.get(observer.reference_body_eid); + // For each observer + this->registry.view().each( + [&](entity::id observer_eid, const auto& observer) + { + // Skip observers with invalid reference body + if (!this->registry.has(observer.reference_body_eid) || + !this->registry.has(observer.reference_body_eid)) + return; + + // Get celestial body and terrain component of observer reference body + const auto& reference_celestial_body = this->registry.get(observer.reference_body_eid); + const auto& reference_terrain = this->registry.get(observer.reference_body_eid); + + // Calculate reference BCBF-space position of observer. + //double3 observer_spherical = {reference_celestial_body.radius + observer.elevation, observer.latitude, observer.longitude}; + double3 observer_spherical = {observer.elevation, observer.latitude, observer.longitude}; + double3 observer_cartesian = geom::spherical::to_cartesian(observer_spherical); + + observer_cartesian = math::type_cast(observer.camera->get_translation()); + + /// @TODO Transform observer position into BCBF space of terrain body (use orbit component?) + + // For each terrain quadsphere face + for (int i = 0; i < 6; ++i) + { + terrain_quadsphere_face& quadsphere_face = quadsphere->faces[i]; + + // Get the quadsphere faces's quadtree + quadtree_type& quadtree = quadsphere_face.quadtree; + + // Clear quadsphere face quadtree + quadtree.clear(); + + // For each node in the face quadtree + for (auto node_it = quadtree.begin(); node_it != quadtree.end(); ++node_it) + { + quadtree_node_type node = *node_it; + + // Skip non leaf nodes + if (!quadtree.is_leaf(node)) + continue; + + // Extract node depth + quadtree_type::node_type node_depth = quadtree_type::depth(node); + + // Skip nodes at max depth level + if (node_depth >= terrain_component.max_lod) + continue; + + // Extract node location from Morton location code + quadtree_type::node_type node_location = quadtree_type::location(node); + quadtree_type::node_type node_location_x; + quadtree_type::node_type node_location_y; + geom::morton::decode(node_location, node_location_x, node_location_y); + + + + const double nodes_per_axis = std::exp2(node_depth); + const double node_width = 2.0 / nodes_per_axis; + + // Determine node center on front face of unit BCBF cube. + double3 center; + center.y = -(nodes_per_axis * 0.5 * node_width) + node_width * 0.5; + center.z = center.y; + center.y += static_cast(node_location_x) * node_width; + center.z += static_cast(node_location_y) * node_width; + center.x = 1.0; + + // Rotate node center according to cube face + /// @TODO Rather than rotating every center, "unrotate" observer position 6 times + center = face_rotations[i] * center; + + // Project node center onto unit sphere + double xx = center.x * center.x; + double yy = center.y * center.y; + double zz = center.z * center.z; + center.x *= std::sqrt(std::max(0.0, 1.0 - yy * 0.5 - zz * 0.5 + yy * zz / 3.0)); + center.y *= std::sqrt(std::max(0.0, 1.0 - xx * 0.5 - zz * 0.5 + xx * zz / 3.0)); + center.z *= std::sqrt(std::max(0.0, 1.0 - xx * 0.5 - yy * 0.5 + xx * yy / 3.0)); + + // Scale node center by body radius + center *= terrain_body.radius; + center.y -= terrain_body.radius; + //center *= 50.0; + + const double horizontal_fov = observer.camera->get_fov(); + const double horizontal_resolution = 1920.0; + const double distance = math::length(center - observer_cartesian); + const double geometric_error = static_cast(524288.0 / std::exp2(node_depth)); + const double screen_error = screen_space_error(horizontal_fov, horizontal_resolution, distance, geometric_error); + + if (screen_error > max_error) + { + //std::cout << screen_error << std::endl; + quadtree.insert(quadtree_type::child(node, 0)); + } + } + } + }); + }); + + // Handle meshes and models for each terrain patch + registry.view().each( + [&](entity::id terrain_eid, const auto& terrain_component, const auto& terrain_body) + { + // Retrieve terrain quadsphere + terrain_quadsphere* quadsphere = terrain_quadspheres[terrain_eid]; - // Haversine distance to all 6 faces, then recursively to children + // For each terrain quadsphere face + for (int i = 0; i < 6; ++i) + { + terrain_quadsphere_face& quadsphere_face = quadsphere->faces[i]; + const quadtree_type& quadtree = quadsphere_face.quadtree; + + // For each quadtree node + for (auto node_it = quadtree.unordered_begin(); node_it != quadtree.unordered_end(); ++node_it) + { + quadtree_node_type node = *node_it; + + // Look up cached patch for this node + auto patch_it = quadsphere_face.patches.find(node); + + // If there is no cached patch instance for this node + if (patch_it == quadsphere_face.patches.end()) + { + // Construct a terrain patch + terrain_patch* patch = new terrain_patch(); + + // Generate a patch mesh + patch->mesh = generate_patch_mesh(i, *node_it, terrain_body.radius, terrain_component.elevation); + //patch->mesh = generate_patch_mesh(i, *node_it, 50.0, terrain_component.elevation); + + // Generate a patch model + patch->model = generate_patch_model(*patch->mesh, terrain_component.patch_material); + + // Construct patch model instance + patch->model_instance = new scene::model_instance(patch->model); + + + // Cache the terrain patch + quadsphere_face.patches[node] = patch; + + // Add patch model instance to the patch scene collection + if (patch_scene_collection) + patch_scene_collection->add_object(patch->model_instance); + } + } + + // For each terrain pach + for (auto patch_it = quadsphere_face.patches.begin(); patch_it != quadsphere_face.patches.end(); ++patch_it) + { + quadtree_node_type node = patch_it->first; + + // Set patch model instance active if its node is a leaf node, otherwise deactivate it + bool active = (quadtree.contains(node) && quadtree.is_leaf(node)); + patch_it->second->model_instance->set_active(active); + } + } }); } @@ -181,28 +244,274 @@ void terrain::set_patch_subdivisions(std::uint8_t n) { patch_subdivisions = n; + // Rebuid patch base mesh + { + delete patch_base_mesh; + patch_base_mesh = geom::meshes::grid_xy(2.0f, patch_subdivisions, patch_subdivisions); + + // Convert quads to triangle fans + for (std::size_t i = 0; i < patch_base_mesh->get_faces().size(); ++i) + { + geom::mesh::face* face = patch_base_mesh->get_faces()[i]; + + std::size_t edge_count = 1; + for (geom::mesh::edge* edge = face->edge->next; edge != face->edge; edge = edge->next) + ++edge_count; + + if (edge_count > 3) + { + geom::poke_face(*patch_base_mesh, face->index); + --i; + } + } + } + + // Transform patch base mesh coordinates to match the front face of a BCBF cube + const math::quaternion xy_to_zy = math::quaternion::rotate_y(-math::half_pi); + for (geom::mesh::vertex* vertex: patch_base_mesh->get_vertices()) + { + vertex->position = xy_to_zy * vertex->position; + vertex->position.x = 1.0f; + } + // Recalculate number of vertices per patch - patch_vertex_count = static_cast(std::pow(std::exp2(patch_subdivisions) + 1, 2)); + patch_vertex_count = patch_base_mesh->get_faces().size() * 3; // Resize patch vertex data buffer delete[] patch_vertex_data; patch_vertex_data = new float[patch_vertex_count * patch_vertex_size]; } +void terrain::set_patch_scene_collection(scene::collection* collection) +{ + patch_scene_collection = collection; +} + +void terrain::set_max_error(double error) +{ + max_error = error; +} + void terrain::on_terrain_construct(entity::registry& registry, entity::id entity_id, component::terrain& component) { - // Build quad sphere + terrain_quadsphere* quadsphere = new terrain_quadsphere(); + terrain_quadspheres[entity_id] = quadsphere; } void terrain::on_terrain_destroy(entity::registry& registry, entity::id entity_id) { - // Destroy quad sphere + // Find terrain quadsphere for the given entity ID + auto quadsphere_it = terrain_quadspheres.find(entity_id); + + if (quadsphere_it != terrain_quadspheres.end()) + { + terrain_quadsphere* quadsphere = quadsphere_it->second; + + // For each terrain quadsphere face + for (int i = 0; i < 6; ++i) + { + terrain_quadsphere_face& quadsphere_face = quadsphere->faces[i]; + + for (auto patch_it = quadsphere_face.patches.begin(); patch_it != quadsphere_face.patches.end(); ++patch_it) + { + terrain_patch* patch = patch_it->second; + + if (patch_scene_collection) + patch_scene_collection->remove_object(patch->model_instance); + + delete patch->model_instance; + delete patch->model; + delete patch->mesh; + + delete patch; + } + } + + // Free terrain quadsphere + delete quadsphere; + } + + // Remove terrain quadsphere from the map + terrain_quadspheres.erase(quadsphere_it); +} + +geom::mesh* terrain::generate_patch_mesh(std::uint8_t face_index, quadtree_node_type node, double body_radius, const std::function& elevation) const +{ + // Extract node depth + const quadtree_type::node_type depth = quadtree_type::depth(node); + + // Extract node Morton location code and decode location + const quadtree_type::node_type location = quadtree_type::location(node); + quadtree_type::node_type location_x; + quadtree_type::node_type location_y; + geom::morton::decode(location, location_x, location_y); + + const double nodes_per_axis = std::exp2(depth); + + const double scale_yz = 1.0 / nodes_per_axis; + + const double node_width = 2.0 / nodes_per_axis; + + // Determine vertex offset according to node location + double offset_y = -(nodes_per_axis * 0.5 * node_width) + node_width * 0.5; + double offset_z = offset_y; + offset_y += static_cast(location_x) * node_width; + offset_z += static_cast(location_y) * node_width; + + // Copy base mesh + geom::mesh* patch_mesh = new geom::mesh(*patch_base_mesh); + + // Modify patch mesh vertex positions + for (geom::mesh::vertex* v: patch_mesh->get_vertices()) + { + double3 position = math::type_cast(v->position); + + // Offset and scale vertex position + position.y *= scale_yz; + position.z *= scale_yz; + position.y += offset_y; + position.z += offset_z; + + // Rotate according to cube face + position = face_rotations[face_index] * position; + + // Project onto unit sphere + //position = math::normalize(position); + + // Cartesian Spherical Cube projection (KSC) + /// @see https://catlikecoding.com/unity/tutorials/cube-sphere/ + /// @see https://core.ac.uk/download/pdf/228552506.pdf + double xx = position.x * position.x; + double yy = position.y * position.y; + double zz = position.z * position.z; + position.x *= std::sqrt(std::max(0.0, 1.0 - yy * 0.5 - zz * 0.5 + yy * zz / 3.0)); + position.y *= std::sqrt(std::max(0.0, 1.0 - xx * 0.5 - zz * 0.5 + xx * zz / 3.0)); + position.z *= std::sqrt(std::max(0.0, 1.0 - xx * 0.5 - yy * 0.5 + xx * yy / 3.0)); + + // Calculate latitude and longitude of vertex position + const double latitude = std::atan2(position.z, std::sqrt(position.x * position.x + position.y * position.y)); + const double longitude = std::atan2(position.y, position.x); + + // Look up elevation at latitude and longitude and use to calculate radial distance + const double radial_distance = body_radius + elevation(latitude, longitude); + + // Scale vertex position by radial distance + position *= radial_distance; + position.y -= body_radius; + + v->position = math::type_cast(position); + } + + return patch_mesh; } -void terrain::generate_patch() +model* terrain::generate_patch_model(const geom::mesh& patch_mesh, material* patch_material) const { + // Barycentric coordinates + static const float3 barycentric[3] = + { + {1, 0, 0}, + {0, 1, 0}, + {0, 0, 1} + }; + + // Fill vertex data buffer + float* v = patch_vertex_data; + for (const geom::mesh::face* face: patch_mesh.get_faces()) + { + const geom::mesh::vertex* a = face->edge->vertex; + const geom::mesh::vertex* b = face->edge->next->vertex; + const geom::mesh::vertex* c = face->edge->previous->vertex; + const geom::mesh::vertex* face_vertices[] = {a, b, c}; + + // Calculate facted normal + float3 normal = math::normalize(math::cross(b->position - a->position, c->position - a->position)); + + for (std::size_t i = 0; i < 3; ++i) + { + const geom::mesh::vertex* vertex = face_vertices[i]; + + // Vertex position + const float3& position = vertex->position; + *(v++) = position.x; + *(v++) = position.y; + *(v++) = position.z; + + // Vertex UV coordinates (latitude, longitude) + const float latitude = std::atan2(position.z, std::sqrt(position.x * position.x + position.y * position.y)); + const float longitude = std::atan2(position.y, position.x); + *(v++) = latitude; + *(v++) = longitude; + + // Vertex normal + *(v++) = normal.x; + *(v++) = normal.y; + *(v++) = normal.z; + + /// @TODO Vertex tangent + *(v++) = 0.0f; + *(v++) = 0.0f; + *(v++) = 0.0f; + *(v++) = 0.0f; + + // Vertex barycentric coordinates + *(v++) = barycentric[i].x; + *(v++) = barycentric[i].y; + *(v++) = barycentric[i].z; + + // Vertex morph target (LOD transition) + *(v++) = 0.0f; + *(v++) = 0.0f; + *(v++) = 0.0f; + } + } + + // Get triangle count of patch mesh + std::size_t patch_triangle_count = patch_mesh.get_faces().size(); + + // Allocate patch model + model* patch_model = new model(); + // Resize model VBO and upload vertex data + gl::vertex_buffer* vbo = patch_model->get_vertex_buffer(); + vbo->resize(patch_triangle_count * 3 * patch_vertex_stride, patch_vertex_data); + + // Bind vertex attributes to model VAO + gl::vertex_array* vao = patch_model->get_vertex_array(); + std::size_t offset = 0; + vao->bind_attribute(VERTEX_POSITION_LOCATION, *vbo, 3, gl::vertex_attribute_type::float_32, patch_vertex_stride, 0); + offset += 3; + vao->bind_attribute(VERTEX_TEXCOORD_LOCATION, *vbo, 2, gl::vertex_attribute_type::float_32, patch_vertex_stride, sizeof(float) * offset); + offset += 2; + vao->bind_attribute(VERTEX_NORMAL_LOCATION, *vbo, 3, gl::vertex_attribute_type::float_32, patch_vertex_stride, sizeof(float) * offset); + offset += 3; + vao->bind_attribute(VERTEX_TANGENT_LOCATION, *vbo, 4, gl::vertex_attribute_type::float_32, patch_vertex_stride, sizeof(float) * offset); + offset += 4; + vao->bind_attribute(VERTEX_BARYCENTRIC_LOCATION, *vbo, 3, gl::vertex_attribute_type::float_32, patch_vertex_stride, sizeof(float) * offset); + offset += 3; + vao->bind_attribute(VERTEX_TARGET_LOCATION, *vbo, 3, gl::vertex_attribute_type::float_32, patch_vertex_stride, sizeof(float) * offset); + offset += 3; + + // Create model group + model_group* patch_model_group = patch_model->add_group("terrain"); + patch_model_group->set_material(patch_material); + patch_model_group->set_drawing_mode(gl::drawing_mode::triangles); + patch_model_group->set_start_index(0); + patch_model_group->set_index_count(patch_triangle_count * 3); + + // Calculate model bounds + geom::aabb bounds = geom::calculate_bounds(patch_mesh); + patch_model->set_bounds(bounds); + + return patch_model; +} +double terrain::screen_space_error(double horizontal_fov, double horizontal_resolution, double distance, double geometric_error) +{ + // Calculate view frustum width at given distance + const double frustum_width = 2.0 * distance * std::tan(horizontal_fov * 0.5); + + return (geometric_error * horizontal_resolution) / frustum_width; } } // namespace system diff --git a/src/entity/systems/terrain.hpp b/src/entity/systems/terrain.hpp index ae2cc43..062fd1a 100644 --- a/src/entity/systems/terrain.hpp +++ b/src/entity/systems/terrain.hpp @@ -23,10 +23,22 @@ #include "entity/systems/updatable.hpp" #include "entity/components/terrain.hpp" #include "entity/id.hpp" +#include "math/quaternion-type.hpp" +#include "geom/quadtree.hpp" +#include "geom/mesh.hpp" +#include "utility/fundamental-types.hpp" +#include "renderer/model.hpp" +#include "renderer/material.hpp" +#include "scene/model-instance.hpp" +#include "scene/collection.hpp" +#include namespace entity { namespace system { +/** + * Generates and manages terrain with LOD based on distance to observers. + */ class terrain: public updatable { public: @@ -36,22 +48,87 @@ public: virtual void update(double t, double dt); /** - * Sets the number of subdivisions for a patch. + * Sets the number of subdivisions for a patch. Zero subdivisions results in a single quad, one subdivison results in four quads, etc. * * @param n Number of subdivisions. */ void set_patch_subdivisions(std::uint8_t n); + + /** + * Sets the scene collection into which terrain patch model instances will be inserted. + */ + void set_patch_scene_collection(scene::collection* collection); + + /** + * Sets the maximum tolerable screen-space error. + * + * If the screen-space error of a terrain patch exceeds the maximum tolerable value, it will be subdivided. + * + * @param error Maximum tolerable screen-space error. + */ + void set_max_error(double error); private: + typedef geom::quadtree64 quadtree_type; + typedef quadtree_type::node_type quadtree_node_type; + + struct terrain_patch + { + geom::mesh* mesh; + model* model; + scene::model_instance* model_instance; + float error; + float morph; + }; + + /// Single face of a terrain quadsphere + struct terrain_quadsphere_face + { + /// Quadtree describing level of detail + quadtree_type quadtree; + + /// Map linking quadtree nodes to terrain patches + std::unordered_map patches; + }; + + /// A terrain quadsphere with six faces. + struct terrain_quadsphere + { + /// Array of six terrain quadsphere faces, in the order of +x, -x, +y, -y, +z, -z. + terrain_quadsphere_face faces[6]; + }; + + + static double screen_space_error(double horizontal_fov, double horizontal_resolution, double distance, double geometric_error); + void on_terrain_construct(entity::registry& registry, entity::id entity_id, entity::component::terrain& component); void on_terrain_destroy(entity::registry& registry, entity::id entity_id); - void generate_patch(); + /** + * Generates a mesh for a terrain patch given the patch's quadtree node + */ + geom::mesh* generate_patch_mesh(std::uint8_t face_index, quadtree_node_type node, double body_radius, const std::function& elevation) const; + + /** + * Generates a model for a terrain patch given the patch's mesh. + */ + model* generate_patch_model(const geom::mesh& patch_mesh, material* patch_material) const; + + + + /// @TODO horizon culling std::uint8_t patch_subdivisions; std::size_t patch_vertex_size; + std::size_t patch_vertex_stride; std::size_t patch_vertex_count; float* patch_vertex_data; + math::quaternion face_rotations[6]; + geom::mesh* patch_base_mesh; + scene::collection* patch_scene_collection; + double max_error; + + std::unordered_map terrain_quadspheres; }; } // namespace system diff --git a/src/game/bootloader.cpp b/src/game/bootloader.cpp index d6bde3a..ea89ca3 100644 --- a/src/game/bootloader.cpp +++ b/src/game/bootloader.cpp @@ -794,7 +794,9 @@ void setup_systems(game_context* ctx) // Setup terrain system ctx->terrain_system = new entity::system::terrain(*ctx->entity_registry); - ctx->terrain_system->set_patch_subdivisions(4); + ctx->terrain_system->set_patch_subdivisions(30); + ctx->terrain_system->set_patch_scene_collection(ctx->overworld_scene); + ctx->terrain_system->set_max_error(200.0); // Setup vegetation system //ctx->vegetation_system = new entity::system::vegetation(*ctx->entity_registry); diff --git a/src/game/states/play-state.cpp b/src/game/states/play-state.cpp index 15bd9f9..0a7beb2 100644 --- a/src/game/states/play-state.cpp +++ b/src/game/states/play-state.cpp @@ -65,6 +65,7 @@ #include "utility/fundamental-types.hpp" #include "utility/bit-math.hpp" #include "genetics/genetics.hpp" +#include "math/random.hpp" #include #include #include @@ -144,8 +145,11 @@ void play_state_enter(game_context* ctx) entity::component::terrain terrain; terrain.elevation = [](double, double) -> double { + //return math::random(0.0, 1.0); return 0.0; }; + terrain.max_lod = 18; + terrain.patch_material = resource_manager->load("desert-terrain.mtl"); entity::component::atmosphere atmosphere; atmosphere.exosphere_altitude = 65e3; @@ -172,9 +176,10 @@ void play_state_enter(game_context* ctx) { entity::component::observer observer; observer.reference_body_eid = earth_entity; - observer.altitude = 0.0; + observer.elevation = 0.0; observer.latitude = 0.0; observer.longitude = 0.0; + observer.camera = ctx->overworld_camera; entity_registry.assign(observer_eid, observer); } @@ -268,8 +273,8 @@ void play_state_enter(game_context* ctx) //ctx->tool_system->set_active_tool(ctx->brush_entity); // Create ant-hill - auto ant_hill_entity = ant_hill_archetype->create(entity_registry); - entity::command::place(entity_registry, ant_hill_entity, earth_entity, 0.0, 0.0, 0.0); + //auto ant_hill_entity = ant_hill_archetype->create(entity_registry); + //entity::command::place(entity_registry, ant_hill_entity, earth_entity, 0.0, 0.0, 0.0); // Create color checker /* @@ -283,6 +288,7 @@ void play_state_enter(game_context* ctx) // Setup camera focal point entity::component::transform focal_point_transform; focal_point_transform.local = math::identity_transform; + //focal_point_transform.local.translation = {0, 6.3781e6, 0}; focal_point_transform.warp = true; entity::component::camera_follow focal_point_follow; entity::component::snap focal_point_snap; @@ -292,7 +298,7 @@ void play_state_enter(game_context* ctx) focal_point_snap.autoremove = false; entity_registry.assign_or_replace(ctx->focal_point_entity, focal_point_transform); entity_registry.assign_or_replace(ctx->focal_point_entity, focal_point_follow); - entity_registry.assign_or_replace(ctx->focal_point_entity, focal_point_snap); + //entity_registry.assign_or_replace(ctx->focal_point_entity, focal_point_snap); // Setup camera ctx->overworld_camera->look_at({0, 0, 1}, {0, 0, 0}, {0, 1, 0}); diff --git a/src/geom/mesh-functions.cpp b/src/geom/mesh-functions.cpp index 2f5d0a6..cebb6f4 100644 --- a/src/geom/mesh-functions.cpp +++ b/src/geom/mesh-functions.cpp @@ -184,4 +184,54 @@ aabb calculate_bounds(const mesh& mesh) return aabb{bounds_min, bounds_max}; } +mesh::vertex* poke_face(mesh& mesh, std::size_t index) +{ + mesh::face* face = mesh.get_faces()[index]; + + // Collect face edges and sum edge vertex positions + std::vector edges = {face->edge}; + float3 sum_positions = face->edge->vertex->position; + for (mesh::edge* edge = face->edge->next; edge != face->edge; edge = edge->next) + { + edges.push_back(edge); + sum_positions += edge->vertex->position; + } + + if (edges.size() > 2) + { + // Remove face + mesh.remove_face(face); + + // Add vertex in center + mesh::vertex* center = mesh.add_vertex(sum_positions / static_cast(edges.size())); + + // Create first triangle + geom::mesh::edge* ab = edges[0]; + geom::mesh::edge* bc = mesh.add_edge(ab->next->vertex, center); + geom::mesh::edge* ca = mesh.add_edge(center, ab->vertex); + mesh.add_face({ab, bc, ca}); + + // Save first triangle CA edge + geom::mesh::edge* first_triangle_ca = ca; + + // Create remaining triangles + for (std::size_t i = 1; i < edges.size(); ++i) + { + ab = edges[i]; + ca = bc->symmetric; + + if (i == edges.size() - 1) + bc = first_triangle_ca->symmetric; + else + bc = mesh.add_edge(ab->next->vertex, center); + + mesh.add_face({ab, bc, ca}); + } + + return center; + } + + return nullptr; +} + } // namespace geom diff --git a/src/geom/mesh-functions.hpp b/src/geom/mesh-functions.hpp index 6587633..b1a81fc 100644 --- a/src/geom/mesh-functions.hpp +++ b/src/geom/mesh-functions.hpp @@ -61,6 +61,15 @@ void calculate_vertex_tangents(float4* tangents, const float2* texcoords, const */ aabb calculate_bounds(const mesh& mesh); +/** + * Triangulates a face by adding a new vertex in the center, then creating triangles between the edges of the original face and the new vertex. + * + * @param mesh Mesh containing the face to poke. + * @param index Index of the face to poke. + * @return Pointer to the newly-created vertex in the center of the face, or `nullptr` if the face could not be poked. + */ +mesh::vertex* poke_face(mesh& mesh, std::size_t index); + } // namespace geom #endif // ANTKEEPER_GEOM_MESH_FUNCTIONS_HPP diff --git a/src/geom/mesh.cpp b/src/geom/mesh.cpp index 4c4ca14..a5f2150 100644 --- a/src/geom/mesh.cpp +++ b/src/geom/mesh.cpp @@ -22,13 +22,109 @@ namespace geom { +mesh::mesh(const mesh& other) +{ + *this = other; +} + mesh::~mesh() +{ + clear(); +} + +mesh& mesh::operator=(const mesh& other) +{ + // Clear the mesh + clear(); + + // Resize vertices, edges, and faces + vertices.resize(other.vertices.size()); + edges.resize(other.edges.size()); + faces.resize(other.faces.size()); + + // Allocate vertices + for (std::size_t i = 0; i < vertices.size(); ++i) + vertices[i] = new vertex(); + + // Allocate edges + for (std::size_t i = 0; i < edges.size(); ++i) + { + edges[i] = new edge(); + edges[i]->symmetric = new edge(); + edges[i]->symmetric->symmetric = edges[i]; + } + + // Allocate faces + for (std::size_t i = 0; i < faces.size(); ++i) + faces[i] = new face(); + + // Copy vertices + for (std::size_t i = 0; i < vertices.size(); ++i) + { + vertex* va = vertices[i]; + const vertex* vb = other.vertices[i]; + + va->index = vb->index; + va->position = vb->position; + va->edge = nullptr; + + if (vb->edge) + { + va->edge = edges[vb->edge->index]; + if (vb->edge != other.edges[vb->edge->index]) + va->edge = va->edge->symmetric; + } + } + + // Copy edges + for (std::size_t i = 0; i < edges.size(); ++i) + { + edge* ea = edges[i]; + const edge* eb = other.edges[i]; + + for (std::size_t j = 0; j < 2; ++j) + { + ea->index = eb->index; + ea->vertex = vertices[eb->vertex->index]; + + ea->face = nullptr; + if (eb->face) + ea->face = faces[eb->face->index]; + + ea->previous = edges[eb->previous->index]; + if (eb->previous != other.edges[eb->previous->index]) + ea->previous = ea->previous->symmetric; + + ea->next = edges[eb->next->index]; + if (eb->next != other.edges[eb->next->index]) + ea->next = ea->next->symmetric; + + ea = ea->symmetric; + eb = eb->symmetric; + } + } + + // Copy faces + for (std::size_t i = 0; i < faces.size(); ++i) + { + face* fa = faces[i]; + const face* fb = other.faces[i]; + + fa->index = fb->index; + + fa->edge = edges[fb->edge->index]; + if (fb->edge != other.edges[fb->edge->index]) + fa->edge = fa->edge->symmetric; + } + + return *this; +} + +void mesh::clear() { // Deallocate vertices for (mesh::vertex* vertex: vertices) - { delete vertex; - } // Deallocate edges for (mesh::edge* edge: edges) @@ -39,9 +135,11 @@ mesh::~mesh() // Deallocate faces for (mesh::face* face: faces) - { delete face; - } + + vertices.clear(); + edges.clear(); + faces.clear(); } mesh::vertex* mesh::add_vertex(const float3& position) @@ -120,13 +218,13 @@ mesh::face* mesh::add_face(const loop& loop) { mesh::edge* current = loop[i]; mesh::edge* next = loop[(i + 1) % loop.size()]; - + if (current->symmetric->vertex != next->vertex) { // Disconnected edge loop throw std::runtime_error("Disconnected edge loop"); } - + if (current->face) { // This edge already has a face diff --git a/src/geom/mesh.hpp b/src/geom/mesh.hpp index d59ed4d..e54b43a 100644 --- a/src/geom/mesh.hpp +++ b/src/geom/mesh.hpp @@ -39,14 +39,23 @@ public: typedef std::vector loop; /** - * Creates a mesh. + * Constructs a mesh. */ mesh() = default; + /// Copy-constructs a mesh. + mesh(const mesh& other); + /** * Destroys a mesh. */ ~mesh(); + + /// Copies another mesh into this mesh. + mesh& operator=(const mesh& other); + + /// Removes all vertices, edges, and faces from the mesh. + void clear(); /** * Adds a vertex to the mesh. This vertex initially has a null edge. @@ -70,6 +79,11 @@ public: * * @param loop List of edges which form the face. * @return Pointer to the added face. + * + * @exception std::runtime_error Empty edge loop. + * @exception std::runtime_error Disconnected edge loop. + * @exception std::runtime_error Non-manifold mesh 1. + * @exception std::runtime_error Non-manifold mesh 2. */ mesh::face* add_face(const loop& loop); diff --git a/src/cart/relief-map.cpp b/src/geom/meshes/grid.cpp similarity index 57% rename from src/cart/relief-map.cpp rename to src/geom/meshes/grid.cpp index 349e1c7..c9630fd 100644 --- a/src/cart/relief-map.cpp +++ b/src/geom/meshes/grid.cpp @@ -17,42 +17,40 @@ * along with Antkeeper source code. If not, see . */ -#include "relief-map.hpp" +#include "geom/meshes/grid.hpp" #include #include #include -namespace cart -{ +namespace geom { +namespace meshes { -geom::mesh* map_elevation(const std::function& function, float scale, std::size_t subdivisions) +geom::mesh* grid_xy(float length, std::size_t subdivisions_x, std::size_t subdivisions_y) { - // Allocate terrain mesh + // Allocate new mesh geom::mesh* mesh = new geom::mesh(); // Determine vertex count and placement - std::size_t columns = static_cast(std::pow(2, subdivisions)); - std::size_t rows = columns; - float uv_scale = 1.0f / static_cast(columns); - //std::size_t vertex_count = (columns + 1) * (rows + 1); + std::size_t columns = subdivisions_x + 1; + std::size_t rows = subdivisions_y + 1; + float column_length = length / static_cast(columns); + float row_length = length / static_cast(rows); // Generate mesh vertices float3 position; - float2 uv; + position.z = 0.0f; + position.y = -length * 0.5f; for (std::size_t i = 0; i <= rows; ++i) { - uv.y = static_cast(i) * uv_scale; - position.z = (uv.y - 0.5f) * scale; - + position.x = -length * 0.5f; for (std::size_t j = 0; j <= columns; ++j) { - uv.x = static_cast(j) * uv_scale; - - position.x = (uv.x - 0.5f) * scale; - position.y = function(uv.x, uv.y); - mesh->add_vertex(position); + + position.x += column_length; } + + position.y += row_length; } // Function to eliminate duplicate edges @@ -84,47 +82,21 @@ geom::mesh* map_elevation(const std::function& function, fl geom::mesh::vertex* b = vertices[(i + 1) * (columns + 1) + j]; geom::mesh::vertex* c = vertices[i * (columns + 1) + j + 1]; geom::mesh::vertex* d = vertices[(i + 1) * (columns + 1) + j + 1]; - - // +---+---+ - // | \ | / | - // |---+---| - // | / | \ | - // +---+---+ - if ((j % 2) == (i % 2)) - { - geom::mesh::edge* ab = add_or_find_edge(a, b); - geom::mesh::edge* bd = add_or_find_edge(b, d); - geom::mesh::edge* da = add_or_find_edge(d, a); - - geom::mesh::edge* ca = add_or_find_edge(c, a); - geom::mesh::edge* ad = da->symmetric; - geom::mesh::edge* dc = add_or_find_edge(d, c); - - // a---c - // | \ | - // b---d - mesh->add_face({ab, bd, da}); - mesh->add_face({ca, ad, dc}); - } - else - { - geom::mesh::edge* ab = add_or_find_edge(a, b); - geom::mesh::edge* bc = add_or_find_edge(b, c); - geom::mesh::edge* ca = add_or_find_edge(c, a); - geom::mesh::edge* cb = bc->symmetric; - geom::mesh::edge* bd = add_or_find_edge(b, d); - geom::mesh::edge* dc = add_or_find_edge(d, c); - - // a---c - // | / | - // b---d - mesh->add_face({ab, bc, ca}); - mesh->add_face({cb, bd, dc}); - } + + // a---c + // | | + // b---d + geom::mesh::edge* ab = add_or_find_edge(a, b); + geom::mesh::edge* bd = add_or_find_edge(b, d); + geom::mesh::edge* dc = add_or_find_edge(d, c); + geom::mesh::edge* ca = add_or_find_edge(c, a); + + mesh->add_face({ab, bd, dc, ca}); } } return mesh; } -} // namespace cart +} // namespace meshes +} // namespace geom diff --git a/src/cart/relief-map.hpp b/src/geom/meshes/grid.hpp similarity index 60% rename from src/cart/relief-map.hpp rename to src/geom/meshes/grid.hpp index d39ffbf..f85b199 100644 --- a/src/cart/relief-map.hpp +++ b/src/geom/meshes/grid.hpp @@ -17,23 +17,25 @@ * along with Antkeeper source code. If not, see . */ -#ifndef ANTKEEPER_RELIEF_MAP_HPP -#define ANTKEEPER_RELIEF_MAP_HPP +#ifndef ANTKEEPER_GEOM_MESHES_GRID_HPP +#define ANTKEEPER_GEOM_MESHES_GRID_HPP #include "geom/mesh.hpp" -#include -namespace cart -{ +namespace geom { +namespace meshes { /** - * Generates a relief map mesh given an elevation function. + * Generates a grid mesh on the XY plane. * - * @param function Function which returns an elevation given UV coordinates on a unit plane. - * @param subdivisions Number of lines of longitude. Minimum value is 3. + * @param length Side length of the grid. + * @param subdivisions_x Number of subdivisions on the x-axis. + * @param subdivisions_y Number of subdivisions on the y-axis. + * @return Grid mesh on the XY plane. */ -geom::mesh* map_elevation(const std::function& function, float scale, std::size_t subdivisions); +geom::mesh* grid_xy(float length, std::size_t subdivisions_x, std::size_t subdivisions_y); -} // namespace cart +} // namespace meshes +} // namespace geom -#endif // ANTKEEPER_RELIEF_MAP_HPP +#endif // ANTKEEPER_GEOM_MESHES_GRID_HPP diff --git a/src/renderer/vertex-attributes.hpp b/src/renderer/vertex-attributes.hpp index 9ca920e..942af70 100644 --- a/src/renderer/vertex-attributes.hpp +++ b/src/renderer/vertex-attributes.hpp @@ -44,5 +44,8 @@ /// Vertex barycentric coordinates (vec3) #define VERTEX_BARYCENTRIC_LOCATION 7 +/// Vertex morph target (vec3) +#define VERTEX_TARGET_LOCATION 8 + #endif // ANTKEEPER_VERTEX_ATTRIBUTES_HPP