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
15 changes: 15 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,21 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0

## [Unreleased]

### Added

- utils : add `FileDialogGui.h` (https://github.com/Simple-Robotics/candlewick/pull/61)

### Changed

- utils : avoid public inclusion of `libavutil/pixfmt` header for video recorder (https://github.com/Simple-Robotics/candlewick/pull/61)
- core : `errors.h`: make terminate_with_message a template (with formatting arguments, etc) (https://github.com/Simple-Robotics/candlewick/pull/61)
- utils: add VideoRecorder::close() API (to manually close recorder) (https://github.com/Simple-Robotics/candlewick/pull/61)
- multibody/RobotDebug.cpp : fix velocity arrow direction (https://github.com/Simple-Robotics/candlewick/pull/61)

### Fixed

- core : fix `CommandBuffer::submitAndAcquireFence()` not setting the internal pointer to null

## [0.0.7] - 2025-05-17

### Added
Expand Down
79 changes: 56 additions & 23 deletions examples/Ur5WithSystems.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
#include "candlewick/multibody/RobotScene.h"
#include "candlewick/multibody/RobotDebug.h"
#include "candlewick/primitives/Primitives.h"
#include "candlewick/utils/FileDialogGui.h"
#include "candlewick/utils/WriteTextureToImage.h"

#include <imgui.h>
Expand Down Expand Up @@ -184,11 +185,17 @@ void eventLoop(const Renderer &renderer) {
}
}

Renderer createRenderer(Uint32 width, Uint32 height,
SDL_GPUTextureFormat depth_stencil_format) {
return Renderer{Device{auto_detect_shader_format_subset(), true},
Window(__FILE__, int(width), int(height), 0),
depth_stencil_format};
static void screenshot_button_callback(Renderer &renderer,
media::TransferBufferPool &pool,
const char *filename) {
const auto &device = renderer.device;
CommandBuffer command_buffer{device};
renderer.waitAndAcquireSwapchain(command_buffer);

SDL_Log("Saving screenshot at %s", filename);
media::writeToFile(command_buffer, device, pool, renderer.swapchain,
renderer.getSwapchainTextureFormat(), wWidth, wHeight,
filename);
}

int main(int argc, char **argv) {
Expand All @@ -206,8 +213,11 @@ int main(int argc, char **argv) {
return 1;

// D16_UNORM works on macOS, D24_UNORM and D32_FLOAT break the depth prepass
Renderer renderer =
createRenderer(wWidth, wHeight, SDL_GPU_TEXTUREFORMAT_D16_UNORM);
Renderer renderer{
Device{auto_detect_shader_format_subset(), true},
Window(__FILE__, wWidth, wHeight, 0),
SDL_GPU_TEXTUREFORMAT_D16_UNORM,
};

entt::registry registry{};

Expand Down Expand Up @@ -313,6 +323,8 @@ int main(int argc, char **argv) {

FrustumBoundsDebugSystem frustumBoundsDebug{registry, renderer};

const char *screenshot_filename = nullptr;

GuiSystem gui_system{
renderer, [&](const Renderer &r) {
IMGUI_CHECKVERSION();
Expand Down Expand Up @@ -391,6 +403,13 @@ int main(int argc, char **argv) {
ImGui::RadioButton("Heatmap", (int *)&depth_mode, 1);
}

ImGui::SeparatorText("Screenshots");
static GuiFileSaveDialog scr_dialog;
scr_dialog.addFileDialog(renderer.window);
if (ImGui::Button("Take screenshot")) {
screenshot_filename = scr_dialog.filename.c_str();
}

ImGui::SeparatorText("Robot model");
ImGui::SetItemTooltip("Information about the displayed robot model.");
multibody::guiAddPinocchioModelInfo(registry, model, geom_model);
Expand All @@ -414,44 +433,43 @@ int main(int argc, char **argv) {

Uint32 frameNo = 0;

srand(42);
std::srand(42);
Eigen::VectorXd q0 = pin::neutral(model);
Eigen::VectorXd q1 = pin::randomConfiguration(model);

#ifdef CANDLEWICK_WITH_FFMPEG_SUPPORT
media::VideoRecorder recorder{NoInit};
media::TransferBufferPool transfer_buffer_pool{renderer.device};
if (performRecording)
recorder = media::VideoRecorder{wWidth, wHeight, "ur5.mp4"};
recorder = media::VideoRecorder{wWidth,
wHeight,
"ur5.mp4",
{
.fps = 50,
}};
#endif

auto record_callback = [&] {
#ifdef CANDLEWICK_WITH_FFMPEG_SUPPORT
auto swapchain_format = renderer.getSwapchainTextureFormat();
media::videoWriteTextureToFrame(renderer.device, recorder,
renderer.swapchain, swapchain_format,
wWidth, wHeight);
#endif
};

AABB &worldSpaceBounds = robot_scene.worldSpaceBounds;
worldSpaceBounds.update({-1.f, -1.f, 0.f}, {+1.f, +1.f, 1.f});

frustumBoundsDebug.addBounds(worldSpaceBounds);
frustumBoundsDebug.addFrustum(shadowPassInfo.cam);

Eigen::VectorXd q = q0;
Eigen::VectorXd qn = q;
Eigen::VectorXd v{model.nv};
const double dt = 1e-2;

while (!quitRequested) {
// logic
eventLoop(renderer);
double alpha = 0.5 * (1. + std::sin(frameNo * dt));
Eigen::VectorXd qn = q;
q = pin::interpolate(model, q0, q1, alpha);
Eigen::VectorXd v = pin::difference(model, q, qn) / dt;
pin::forwardKinematics(model, pin_data, q, v);
pin::interpolate(model, q0, q1, alpha, qn);
v = pin::difference(model, q, qn) / dt;
pin::forwardKinematics(model, pin_data, qn, v);
pin::updateFramePlacements(model, pin_data);
pin::updateGeometryPlacements(model, pin_data, geom_model, geom_data);
q = qn;
debug_scene.update();

// acquire command buffer and swapchain
Expand Down Expand Up @@ -494,7 +512,18 @@ int main(int argc, char **argv) {
command_buffer.submit();

if (performRecording) {
record_callback();
#ifdef CANDLEWICK_WITH_FFMPEG_SUPPORT
CommandBuffer command_buffer = renderer.acquireCommandBuffer();
auto swapchain_format = renderer.getSwapchainTextureFormat();
media::videoWriteTextureToFrame(
command_buffer, renderer.device, transfer_buffer_pool, recorder,
renderer.swapchain, swapchain_format, wWidth, wHeight);
#endif
}
if (screenshot_filename) {
screenshot_button_callback(renderer, transfer_buffer_pool,
screenshot_filename);
screenshot_filename = nullptr;
}
frameNo++;
}
Expand All @@ -507,6 +536,10 @@ int main(int argc, char **argv) {
robot_scene.release();
debug_scene.release();
gui_system.release();
#ifdef CANDLEWICK_WITH_FFMPEG_SUPPORT
recorder.close();
transfer_buffer_pool.release();
#endif
renderer.destroy();
SDL_Quit();
return 0;
Expand Down
2 changes: 0 additions & 2 deletions examples/lib/Common.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
#include "candlewick/core/MeshLayout.h"
#include "candlewick/core/Shader.h"
#include "candlewick/core/math_types.h"
#include "candlewick/primitives/Cube.h"
#include "candlewick/utils/MeshTransforms.h"
Expand Down
3 changes: 2 additions & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ add_library(
candlewick/core/debug/Frustum.cpp
candlewick/posteffects/ScreenSpaceShadows.cpp
candlewick/posteffects/SSAO.cpp
candlewick/utils/FileDialogGui.cpp
candlewick/utils/LoadMesh.cpp
candlewick/utils/LoadMaterial.cpp
candlewick/utils/MeshData.cpp
Expand All @@ -56,7 +57,7 @@ add_library(
candlewick/primitives/Internal.cpp
candlewick/primitives/Plane.cpp
candlewick/primitives/Sphere.cpp
candlewick/third-party/sbti_lib.cpp
candlewick/third-party/stbi_lib.cpp
# imgui sources
${IMGUI_SRC}
)
Expand Down
11 changes: 11 additions & 0 deletions src/candlewick/core/CommandBuffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,4 +21,15 @@ CommandBuffer &CommandBuffer::operator=(CommandBuffer &&other) noexcept {
return *this;
}

bool CommandBuffer::cancel() noexcept {
bool ret = SDL_CancelGPUCommandBuffer(_cmdBuf);
_cmdBuf = nullptr;
if (!ret) {
SDL_LogWarn(SDL_LOG_CATEGORY_APPLICATION,
"Failed to cancel command buffer: %s", SDL_GetError());
return false;
}
return true;
}

} // namespace candlewick
23 changes: 12 additions & 11 deletions src/candlewick/core/CommandBuffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,23 +46,28 @@ class CommandBuffer {
return true;
}

bool cancel() noexcept {
if (!(active() && SDL_CancelGPUCommandBuffer(_cmdBuf)))
return false;
SDL_GPUFence *submitAndAcquireFence() noexcept {
SDL_GPUFence *fence = SDL_SubmitGPUCommandBufferAndAcquireFence(_cmdBuf);
_cmdBuf = nullptr;
return true;
return fence;
}

/// \brief Cancel the command buffer, returning the bool value from the
/// wrapped SDL API.
bool cancel() noexcept;

/// \brief Check if the command buffer is still active.
///
/// For this wrapper class, it means the internal pointer is non-null.
bool active() const noexcept { return _cmdBuf; }

~CommandBuffer() noexcept {
if (active()) {
SDL_LogWarn(SDL_LOG_CATEGORY_APPLICATION,
"CommandBuffer object is being destroyed while still active! "
"It will be cancelled.");
SDL_CancelGPUCommandBuffer(_cmdBuf);
_cmdBuf = nullptr;
assert(false);
[[maybe_unused]] bool ret = cancel();
assert(ret);
}
}

Expand Down Expand Up @@ -99,10 +104,6 @@ class CommandBuffer {
SDL_PushGPUFragmentUniformData(_cmdBuf, slot_index, data, length);
return *this;
}

SDL_GPUFence *submitAndAcquireFence() {
return SDL_SubmitGPUCommandBufferAndAcquireFence(_cmdBuf);
}
};

} // namespace candlewick
4 changes: 2 additions & 2 deletions src/candlewick/core/DepthAndShadowPass.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ DepthPass::DepthPass(const Device &device, const MeshLayout &layout,
};
pipeline = SDL_CreateGPUGraphicsPipeline(device, &pipeline_desc);
if (!pipeline)
terminate_with_message(
std::format("Failed to create graphics pipeline: %s.", SDL_GetError()));
terminate_with_message("Failed to create graphics pipeline: %s.",
SDL_GetError());
}

DepthPass::DepthPass(const Device &device, const MeshLayout &layout,
Expand Down
15 changes: 10 additions & 5 deletions src/candlewick/core/errors.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,13 +47,18 @@ namespace detail {

} // namespace detail

template <typename... Ts>
[[noreturn]]
inline void terminate_with_message(
std::string_view msg,
std::source_location location = std::source_location::current()) {
void terminate_with_message(std::source_location location, std::string_view fmt,
const Ts &...args) {
throw std::runtime_error(
detail::error_message_format(location.function_name(), "{:s}", msg)
.c_str());
detail::error_message_format(location.function_name(), fmt, args...));
}

template <typename... Ts>
[[noreturn]]
void terminate_with_message(std::string_view fmt, const Ts &...args) {
terminate_with_message(std::source_location::current(), fmt, args...);
}

[[noreturn]]
Expand Down
2 changes: 1 addition & 1 deletion src/candlewick/multibody/RobotDebug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void RobotDebugSystem::updateFrameVelocities(entt::registry &reg) {
// the arrow mesh is posed z-up by default.
// we need to rotate towards where the velocity is pointing,
// then transform to the frame space.
quatf.setFromTwoVectors(Float3::UnitZ(), -v);
quatf.setFromTwoVectors(Float3::UnitZ(), v);
Mat3f R2 = quatf.toRotationMatrix() * scaleMatrix;
auto R = tr.topLeftCorner<3, 3>();
R.applyOnTheRight(R2);
Expand Down
7 changes: 4 additions & 3 deletions src/candlewick/multibody/RobotScene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,8 +226,8 @@ void RobotScene::initCompositePipeline(const MeshLayout &layout) {

pipelines.wboitComposite = SDL_CreateGPUGraphicsPipeline(device(), &desc);
if (!pipelines.wboitComposite) {
terminate_with_message(
std::format("Failed to create WBOIT pipeline: %s", SDL_GetError()));
terminate_with_message("Failed to create WBOIT pipeline: %s",
SDL_GetError());
}
}

Expand Down Expand Up @@ -279,7 +279,8 @@ void RobotScene::loadModels(const pin::GeometryModel &geom_model,
m_config.shadow_config);
shadows_configured = true;
}
this->initCompositePipeline(layout);
if (!pipelines.wboitComposite)
this->initCompositePipeline(layout);
}
}
m_initialized = true;
Expand Down
6 changes: 2 additions & 4 deletions src/candlewick/multibody/RobotScene.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,8 @@ template <typename T>
[[noreturn]] void
invalid_enum(const char *msg, T type,
std::source_location location = std::source_location::current()) {
char out[64];
SDL_snprintf(out, 64ul, "Invalid enum: %s - %s", msg,
magic_enum::enum_name(type).data());
terminate_with_message(out, location);
terminate_with_message(location, "Invalid enum: %s - %s", msg,
magic_enum::enum_name(type));
}

namespace multibody {
Expand Down
3 changes: 1 addition & 2 deletions src/candlewick/multibody/Visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,7 @@ namespace candlewick::multibody {

static Renderer _create_renderer(const Visualizer::Config &config) {
if (!SDL_Init(SDL_INIT_VIDEO)) {
throw std::runtime_error(
std::format("Failed to init video: {}", SDL_GetError()));
terminate_with_message("Failed to init video: %s", SDL_GetError());
}

return Renderer{Device{auto_detect_shader_format_subset()},
Expand Down
5 changes: 4 additions & 1 deletion src/candlewick/third-party/.clang-format-ignore
Original file line number Diff line number Diff line change
@@ -1,3 +1,6 @@
./magic_enum.hpp
./stb_image_write.h
./stb/stb_image_write.h
./float16_t.hpp
./ImGuiFileDialog.h
./ImGuiFileDialog.cpp
./ImGuiFileDialogConfig.h
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
#define STB_IMAGE_WRITE_IMPLEMENTATION
#include "stb_image_write.h"
#include "stb/stb_image_write.h"
Loading