Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion src/candlewick/core/CommandBuffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include "Core.h"
#include <SDL3/SDL_gpu.h>
#include <SDL3/SDL_log.h>
#include <cassert>
#include <utility>

namespace candlewick {
Expand Down
3 changes: 3 additions & 0 deletions src/candlewick/core/Core.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
#pragma once

#include <coal/fwd.hh>
#include <cassert>

#define CDW_ASSERT(condition, msg) assert(((condition) && (msg)))

namespace candlewick {
struct Camera;
Expand Down
7 changes: 3 additions & 4 deletions src/candlewick/core/GuiSystem.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
/// \defgroup gui_util GUI utilities
/// Tools, render systems, etc... for the Candlewick GUI.
#include "Core.h"
#include "Tags.h"
#include <functional>
#include <entt/entity/fwd.hpp>

Expand All @@ -14,17 +13,17 @@ class GuiSystem {
public:
using GuiBehavior = std::function<void(const Renderer &)>;

GuiSystem(NoInitT, GuiBehavior behav)
: m_renderer(nullptr), _callback(behav) {}
GuiSystem(const Renderer &renderer, GuiBehavior behav);

bool init(const Renderer &renderer);
void render(CommandBuffer &cmdBuf);
void release();

bool initialized() const { return m_initialized; }

GuiBehavior _callback;

private:
bool init(const Renderer &renderer);
};

/// \ingroup gui_util
Expand Down
9 changes: 4 additions & 5 deletions src/candlewick/core/Mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
#include "MeshLayout.h"
#include "./errors.h"

#include <cassert>

namespace candlewick {

MeshView::MeshView(const MeshView &parent, Uint32 subVertexOffset,
Expand All @@ -17,9 +15,10 @@ MeshView::MeshView(const MeshView &parent, Uint32 subVertexOffset,
indexOffset(parent.indexOffset + subIndexOffset),
indexCount(subIndexCount) {
// assumption: parent MeshView is validated
assert(validateMeshView(*this));
assert(subVertexOffset + subVertexCount <= parent.vertexCount);
assert(subIndexOffset + subIndexCount <= parent.indexCount);
CDW_ASSERT(validateMeshView(*this), "MeshView failed validation.");
CDW_ASSERT(subVertexOffset + subVertexCount <= parent.vertexCount &&
subIndexOffset + subIndexCount <= parent.indexCount,
"");
}

Mesh::Mesh(NoInitT) {}
Expand Down
1 change: 0 additions & 1 deletion src/candlewick/core/Renderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <magic_enum/magic_enum.hpp>

#include <utility>
#include <cassert>
#include <SDL3/SDL_init.h>
#include <SDL3/SDL_log.h>

Expand Down
4 changes: 2 additions & 2 deletions src/candlewick/core/Texture.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include "errors.h"
#include <magic_enum/magic_enum.hpp>

#include <cassert>
#include <format>

namespace candlewick {
Expand Down Expand Up @@ -45,7 +44,8 @@ Texture &Texture::operator=(Texture &&other) noexcept {

SDL_GPUBlitRegion Texture::blitRegion(Uint32 x, Uint32 y,
Uint32 layer_or_depth_plane) const {
assert(layer_or_depth_plane < layerCount());
CDW_ASSERT(layer_or_depth_plane < layerCount(),
"layer is higher than layerCount!");
return {
.texture = _texture,
.mip_level = 0,
Expand Down
66 changes: 37 additions & 29 deletions src/candlewick/multibody/RobotScene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,16 @@ invalid_enum(const char *msg, T type,
std::format("{:s} - {:s}", msg, magic_enum::enum_name(type)), location);
}

void updateRobotTransforms(entt::registry &registry,
const pin::GeometryData &geom_data) {
auto robot_view =
registry.view<const PinGeomObjComponent, TransformComponent>();
for (auto [ent, geom_id, tr] : robot_view.each()) {
SE3f pose = geom_data.oMg[geom_id].cast<float>();
tr = pose.toHomogeneousMatrix();
}
}

auto RobotScene::pinGeomToPipeline(const coal::CollisionGeometry &geom)
-> PipelineType {
using enum coal::OBJECT_TYPE;
Expand Down Expand Up @@ -102,9 +112,17 @@ void RobotScene::clearRobotGeometries() {
RobotScene::RobotScene(entt::registry &registry, const Renderer &renderer,
const pin::GeometryModel &geom_model,
const pin::GeometryData &geom_data, Config config)
: // screenSpaceShadows{.sampler = nullptr, .pass{NoInit}},
m_registry(registry), m_config(config), m_renderer(renderer),
m_geomModel(geom_model), m_geomData(geom_data) {
: RobotScene(registry, renderer) {
m_config = config;
this->loadModels(geom_model, geom_data);
}

void RobotScene::loadModels(const pin::GeometryModel &geom_model,
const pin::GeometryData &geom_data) {
SDL_assert(!initialized());
m_geomModel = &geom_model;
m_geomData = &geom_data;
SDL_assert(initialized());

for (size_t i = 0; i < kNumPipelineTypes; i++) {
renderPipelines[i] = NULL;
Expand All @@ -120,8 +138,8 @@ RobotScene::RobotScene(entt::registry &registry, const Renderer &renderer,
}

// initialize render target for GBuffer
const auto [width, height] = renderer.window.size();
gBuffer.normalMap = Texture{renderer.device,
const auto [width, height] = m_renderer.window.size();
gBuffer.normalMap = Texture{m_renderer.device,
{
.type = SDL_GPU_TEXTURETYPE_2D,
.format = SDL_GPU_TEXTUREFORMAT_R16G16_FLOAT,
Expand All @@ -143,56 +161,46 @@ RobotScene::RobotScene(entt::registry &registry, const Renderer &renderer,
auto meshDatas = loadGeometryObject(geom_obj);
PipelineType pipeline_type = pinGeomToPipeline(*geom_obj.geometry);
auto mesh = createMeshFromBatch(device(), meshDatas, true);
assert(validateMesh(mesh));
SDL_assert(validateMesh(mesh));

// local copy for use
const auto layout = mesh.layout();

// add entity for this geometry
entt::entity entity = registry.create();
registry.emplace<PinGeomObjComponent>(entity, geom_id);
registry.emplace<TransformComponent>(entity);
entt::entity entity = m_registry.create();
m_registry.emplace<PinGeomObjComponent>(entity, geom_id);
m_registry.emplace<TransformComponent>(entity);
if (pipeline_type != PIPELINE_POINTCLOUD)
registry.emplace<Opaque>(entity);
registry.emplace<MeshMaterialComponent>(entity, std::move(mesh),
extractMaterials(meshDatas));
m_registry.emplace<Opaque>(entity);
m_registry.emplace<MeshMaterialComponent>(entity, std::move(mesh),
extractMaterials(meshDatas));
add_pipeline_tag_component(m_registry, entity, pipeline_type);

if (pipeline_type == PIPELINE_TRIANGLEMESH) {
if (!ssaoPass.pipeline) {
ssaoPass = ssao::SsaoPass(renderer, layout, gBuffer.normalMap);
ssaoPass = ssao::SsaoPass(m_renderer, layout, gBuffer.normalMap);
}
// configure shadow pass
if (enable_shadows && !shadowPass.pipeline) {
shadowPass =
ShadowPassInfo::create(renderer, layout, config.shadow_config);
ShadowPassInfo::create(m_renderer, layout, m_config.shadow_config);
}
}

if (!renderPipelines[pipeline_type]) {
SDL_Log("Building pipeline for type %s",
magic_enum::enum_name(pipeline_type).data());
SDL_GPUGraphicsPipeline *pipeline =
createPipeline(layout, renderer.getSwapchainTextureFormat(),
renderer.depthFormat(), pipeline_type);
assert(pipeline);
createPipeline(layout, m_renderer.getSwapchainTextureFormat(),
m_renderer.depthFormat(), pipeline_type);
SDL_assert(pipeline);
renderPipelines[pipeline_type] = pipeline;
}
}
}

void updateRobotTransforms(entt::registry &registry,
const pin::GeometryData &geom_data) {
auto robot_view =
registry.view<const PinGeomObjComponent, TransformComponent>();
for (auto [ent, geom_id, tr] : robot_view.each()) {
SE3f pose = geom_data.oMg[geom_id].cast<float>();
tr = pose.toHomogeneousMatrix();
}
}

void RobotScene::updateTransforms() {
::candlewick::multibody::updateRobotTransforms(m_registry, m_geomData);
::candlewick::multibody::updateRobotTransforms(m_registry, *m_geomData);
}

void RobotScene::collectOpaqueCastables() {
Expand Down Expand Up @@ -312,7 +320,7 @@ void RobotScene::renderPBRTriangleGeometry(CommandBuffer &command_buffer,
.pushFragmentUniform(2, &_useSsao, sizeof(_useSsao));

auto *pipeline = renderPipelines[PIPELINE_TRIANGLEMESH];
assert(pipeline);
SDL_assert(pipeline);
SDL_BindGPUGraphicsPipeline(render_pass, pipeline);

auto all_view =
Expand Down
60 changes: 44 additions & 16 deletions src/candlewick/multibody/RobotScene.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,24 @@
#include <pinocchio/multibody/fwd.hpp>

namespace candlewick {

namespace multibody {

void updateRobotTransforms(entt::registry &registry,
const pin::GeometryData &geom_data);

/// \brief A scene/render system for robot geometries using Pinocchio.
class RobotScene {
/// \brief A render system for Pinocchio robot geometries using Pinocchio.
///
/// This internally stores references to pinocchio::GeometryModel and
/// pinocchio::GeometryData objects.
class RobotScene final {
[[nodiscard]] bool initialized() const { return m_geomModel && m_geomData; }

void renderPBRTriangleGeometry(CommandBuffer &command_buffer,
const Camera &camera);

void renderOtherGeometry(CommandBuffer &command_buffer,
const Camera &camera);

public:
enum PipelineType {
PIPELINE_TRIANGLEMESH,
Expand Down Expand Up @@ -83,10 +93,32 @@ namespace multibody {
ShadowPassConfig shadow_config;
};

/// \brief Non-initializing constructor.
RobotScene(entt::registry &registry, const Renderer &renderer)
: m_registry(registry), m_renderer(renderer), m_config() {}

/// \brief Constructor which initializes the system.
///
/// loadModels() will be called.
RobotScene(entt::registry &registry, const Renderer &renderer,
const pin::GeometryModel &geom_model,
const pin::GeometryData &geom_data, Config config);

RobotScene(const RobotScene &) = delete;

void setConfig(const Config &config) {
CDW_ASSERT(
!initialized(),
"Cannot call setConfig() after render system was initialized.");
m_config = config;
}

/// \brief Set the internal geometry model and data pointers, and load the
/// corresponding models.
void loadModels(const pin::GeometryModel &geom_model,
const pin::GeometryData &geom_data);

/// \brief Update the transform component of the GeometryObject entities.
void updateTransforms();

void collectOpaqueCastables();
Expand All @@ -112,24 +144,20 @@ namespace multibody {
/// \warning Call updateRobotTransforms() before rendering the objects with
/// this function.
void render(CommandBuffer &command_buffer, const Camera &camera);
/// \brief PBR render pass for triangle meshes.
void renderPBRTriangleGeometry(CommandBuffer &command_buffer,
const Camera &camera);
/// \brief Render pass for other geometry.
void renderOtherGeometry(CommandBuffer &command_buffer,
const Camera &camera);

/// \brief Release all resources.
void release();

Config &config() { return m_config; }
const Config &config() const { return m_config; }
inline bool pbrHasPrepass() const { return m_config.triangle_has_prepass; }
inline bool shadowsEnabled() const { return m_config.enable_shadows; }

/// \brief Getter for the referenced pinocchio GeometryModel object.
const pin::GeometryModel &geomModel() const { return m_geomModel; }
/// \brief Getter for the pinocchio GeometryModel object.
const pin::GeometryModel &geomModel() const { return *m_geomModel; }

/// \brief Getter for the referenced pinocchio GeometryData object.
const pin::GeometryData &geomData() const { return m_geomData; }
/// \brief Getter for the pinocchio GeometryData object.
const pin::GeometryData &geomData() const { return *m_geomData; }

const entt::registry &registry() const { return m_registry; }

Expand All @@ -146,10 +174,10 @@ namespace multibody {

private:
entt::registry &m_registry;
Config m_config;
const Renderer &m_renderer;
std::reference_wrapper<pin::GeometryModel const> m_geomModel;
std::reference_wrapper<pin::GeometryData const> m_geomData;
Config m_config;
const pin::GeometryModel *m_geomModel;
const pin::GeometryData *m_geomData;
std::vector<OpaqueCastable> m_castables;
};
static_assert(Scene<RobotScene>);
Expand Down
Loading