Skip to content

Commit 045e9fd

Browse files
authored
Merge pull request #92 from Simple-Robotics/next
Rework debug scene (re-use `Mesh` object)
2 parents 4ed5368 + a463008 commit 045e9fd

22 files changed

+168
-121
lines changed

.pre-commit-config.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ repos:
3030
doc/doxygen-awesome.*
3131
)$
3232
- repo: https://github.com/astral-sh/ruff-pre-commit
33-
rev: 'v0.12.4'
33+
rev: 'v0.12.7'
3434
hooks:
3535
- id: ruff
3636
args: [--fix, --exit-non-zero-on-fix]

CHANGELOG.md

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,10 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
77

88
## [Unreleased]
99

10-
## [0.8.0] - 2025-07-25
10+
- core : Add `LambertMaterial`
11+
- multibody/Visualizer : remove default world triad
12+
* user must add it explicitly
13+
- multibody/Visualizer : pass scale to addFrameViz()
1114

1215
## [0.8.0] - 2025-07-25
1316

bindings/python/candlewick/video_context.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,9 @@
1+
import warnings
2+
import os
3+
14
from contextlib import contextmanager
25
from . import Visualizer, hasFfmpegSupport
36
from typing import Union, TYPE_CHECKING
4-
import warnings
57

68
if TYPE_CHECKING:
79
from .async_visualizer import AsyncVisualizer
@@ -14,7 +16,7 @@
1416
@contextmanager
1517
def create_recorder_context(
1618
viz: Union[Visualizer, "AsyncVisualizer"],
17-
filename: str,
19+
filename: Union[str | os.PathLike],
1820
/,
1921
fps: int = _DEFAULT_VIDEO_SETTINGS["fps"],
2022
bitRate: int = _DEFAULT_VIDEO_SETTINGS["bitRate"],

bindings/python/src/expose-visualizer.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,8 +25,12 @@ static auto visualizer_get_frame_debugs(Visualizer &viz) {
2525

2626
void exposeVisualizer() {
2727
using pinocchio::python::VisualizerPythonVisitor;
28+
using pinocchio::visualizers::Vector3;
2829

2930
eigenpy::OptionalConverter<ConstVectorRef, std::optional>::registration();
31+
eigenpy::OptionalConverter<Vector3, std::optional>::registration();
32+
eigenpy::detail::NoneToPython<std::nullopt_t>::registration();
33+
3034
bp::class_<Visualizer::Config>("VisualizerConfig", bp::init<>("self"_a))
3135
.def_readwrite("width", &Visualizer::Config::width)
3236
.def_readwrite("height", &Visualizer::Config::height);
@@ -71,7 +75,8 @@ void exposeVisualizer() {
7175
bp::return_internal_reference<>())
7276
#endif
7377
.def("addFrameViz", &Visualizer::addFrameViz,
74-
("self"_a, "frame_id", "show_velocity"_a = true),
78+
("self"_a, "frame_id", "show_velocity"_a = true,
79+
"scale"_a = std::nullopt, "vel_scale"_a = std::nullopt),
7580
"Add visualization (triad and frame velocity) for the given frame "
7681
"by ID.")
7782
.def("removeFramesViz", &Visualizer::removeFramesViz, ("self"_a),

examples/LitMesh.cpp

Lines changed: 8 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -71,8 +71,7 @@ int main() {
7171

7272
std::vector<Mesh> meshes;
7373
for (std::size_t j = 0; j < meshDatas.size(); j++) {
74-
Mesh mesh = createMesh(device, meshDatas[j]);
75-
uploadMeshToDevice(device, mesh, meshDatas[j]);
74+
Mesh mesh = createMesh(device, meshDatas[j], true);
7675
meshes.push_back(std::move(mesh));
7776
}
7877
SDL_assert(meshDatas[0].numIndices() == meshes[0].indexCount);
@@ -204,14 +203,9 @@ int main() {
204203
.store_op = SDL_GPU_STOREOP_STORE,
205204
.cycle = false,
206205
};
207-
SDL_GPUBufferBinding vertex_binding = meshes[0].getVertexBinding(0);
208-
SDL_GPUBufferBinding index_binding = meshes[0].getIndexBinding();
209206
render_pass = SDL_BeginGPURenderPass(command_buffer, &ctinfo, 1,
210207
&depth_target_info);
211208
SDL_BindGPUGraphicsPipeline(render_pass, pipeline);
212-
SDL_BindGPUVertexBuffers(render_pass, 0, &vertex_binding, 1);
213-
SDL_BindGPUIndexBuffer(render_pass, &index_binding,
214-
SDL_GPU_INDEXELEMENTSIZE_32BIT);
215209

216210
TransformUniformData cameraUniform{
217211
.modelView = modelView.matrix(),
@@ -224,16 +218,15 @@ int main() {
224218
myLight.intensity,
225219
};
226220

221+
rend::bindMesh(render_pass, meshes[0]);
222+
227223
auto materialUbo = meshDatas[0].material;
228224

229-
SDL_PushGPUVertexUniformData(command_buffer, 0, &cameraUniform,
230-
sizeof(cameraUniform));
231-
SDL_PushGPUFragmentUniformData(command_buffer, 0, &materialUbo,
232-
sizeof(materialUbo));
233-
SDL_PushGPUFragmentUniformData(command_buffer, 1, &lightUbo,
234-
sizeof(lightUbo));
235-
SDL_DrawGPUIndexedPrimitives(render_pass, meshes[0].indexCount, 1, 0, 0,
236-
0);
225+
command_buffer.pushVertexUniform(0u, cameraUniform)
226+
.pushFragmentUniform(0u, materialUbo)
227+
.pushFragmentUniform(1u, lightUbo);
228+
229+
rend::draw(render_pass, meshes[0]);
237230

238231
SDL_EndGPURenderPass(render_pass);
239232
}

examples/MeshNormalsRgb.cpp

Lines changed: 8 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -58,8 +58,7 @@ int main() {
5858

5959
std::vector<Mesh> meshes;
6060
for (std::size_t j = 0; j < meshDatas.size(); j++) {
61-
Mesh mesh = createMesh(device, meshDatas[j]);
62-
uploadMeshToDevice(device, mesh, meshDatas[j]);
61+
Mesh mesh = createMesh(device, meshDatas[j], true);
6362
meshes.push_back(std::move(mesh));
6463
}
6564
SDL_assert(meshDatas[0].numIndices() == meshes[0].indexCount);
@@ -117,8 +116,6 @@ int main() {
117116
vertexShader.release();
118117
fragmentShader.release();
119118

120-
SDL_GPUTexture *swapchain;
121-
122119
Radf fov = 70.0_degf;
123120
Mat4f projectionMat = perspectiveFromFov(fov, aspectRatio, 0.1f, 40.0f);
124121

@@ -185,17 +182,16 @@ int main() {
185182
modelView.topLeftCorner<3, 3>().inverse().transpose();
186183

187184
// render pass
188-
189185
SDL_GPURenderPass *render_pass;
190186

191187
CommandBuffer command_buffer(device);
192188
SDL_Log("Frame [%u]", frameNo);
193189

194-
if (!SDL_WaitAndAcquireGPUSwapchainTexture(command_buffer, window,
195-
&swapchain, NULL, NULL)) {
190+
if (!ctx.waitAndAcquireSwapchain(command_buffer)) {
196191
SDL_Log("Failed to acquire swapchain: %s", SDL_GetError());
197192
break;
198193
} else {
194+
auto *swapchain = ctx.swapchain;
199195

200196
SDL_GPUColorTargetInfo ctinfo{
201197
.texture = swapchain,
@@ -204,24 +200,19 @@ int main() {
204200
.store_op = SDL_GPU_STOREOP_STORE,
205201
.cycle = false,
206202
};
207-
SDL_GPUBufferBinding vertex_binding = meshes[0].getVertexBinding(0);
208-
SDL_GPUBufferBinding index_binding = meshes[0].getIndexBinding();
209203
render_pass =
210204
SDL_BeginGPURenderPass(command_buffer, &ctinfo, 1, &depthTarget);
211205
SDL_BindGPUGraphicsPipeline(render_pass, pipeline);
212-
SDL_BindGPUVertexBuffers(render_pass, 0, &vertex_binding, 1);
213-
SDL_BindGPUIndexBuffer(render_pass, &index_binding,
214-
SDL_GPU_INDEXELEMENTSIZE_32BIT);
215-
216206
TransformUniformData cameraUniform{
217207
projViewMat,
218208
normalMatrix,
219209
};
210+
command_buffer.pushVertexUniform(0u, cameraUniform);
220211

221-
SDL_PushGPUVertexUniformData(command_buffer, 0, &cameraUniform,
222-
sizeof(cameraUniform));
223-
SDL_DrawGPUIndexedPrimitives(render_pass, meshes[0].indexCount, 1, 0, 0,
224-
0);
212+
for (auto &mesh : meshes) {
213+
rend::bindMesh(render_pass, mesh);
214+
rend::draw(render_pass, mesh);
215+
}
225216

226217
SDL_EndGPURenderPass(render_pass);
227218
}

examples/Visualizer.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
#include <CLI/Config.hpp>
1111

1212
using namespace candlewick::multibody;
13+
using pinocchio::visualizers::Vector3;
1314
using std::chrono::steady_clock;
1415
namespace fs = std::filesystem;
1516

@@ -41,6 +42,7 @@ int main(int argc, char **argv) {
4142

4243
Visualizer visualizer{{window_dims[0], window_dims[1]}, model, geom_model};
4344
assert(!visualizer.hasExternalData());
45+
visualizer.addFrameViz(model.getFrameId("world"), false, Vector3::Ones());
4446
visualizer.addFrameViz(model.getFrameId("elbow_joint"));
4547
visualizer.addFrameViz(model.getFrameId("ee_link"));
4648
pin::Data &data = visualizer.data();

src/candlewick/core/DebugScene.cpp

Lines changed: 32 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -12,45 +12,55 @@ DebugScene::DebugScene(entt::registry &reg, const RenderContext &renderer)
1212
: m_registry(reg)
1313
, m_renderer(renderer)
1414
, m_trianglePipeline(nullptr)
15-
, m_linePipeline(nullptr) {}
15+
, m_linePipeline(nullptr)
16+
, m_sharedMeshes() {
17+
this->initializeSharedMeshes();
18+
}
1619

1720
DebugScene::DebugScene(DebugScene &&other)
1821
: m_registry(other.m_registry)
1922
, m_renderer(other.m_renderer)
2023
, m_trianglePipeline(other.m_trianglePipeline)
2124
, m_linePipeline(other.m_linePipeline)
22-
, m_subsystems(std::move(other.m_subsystems)) {
25+
, m_subsystems(std::move(other.m_subsystems))
26+
, m_sharedMeshes(std::move(other.m_sharedMeshes)) {
2327
other.m_trianglePipeline = nullptr;
2428
other.m_linePipeline = nullptr;
2529
}
2630

31+
void DebugScene::initializeSharedMeshes() {
32+
{
33+
std::array triad_datas = loadTriadSolid();
34+
Mesh mesh = createMeshFromBatch(device(), triad_datas, true);
35+
setupPipelines(mesh.layout());
36+
m_sharedMeshes.emplace(TRIAD, std::move(mesh));
37+
}
38+
{
39+
MeshData grid_data = loadGrid(20);
40+
m_sharedMeshes.emplace(GRID, createMesh(device(), grid_data, true));
41+
}
42+
{
43+
MeshData arrow_data = loadArrowSolid(false);
44+
m_sharedMeshes.emplace(ARROW, createMesh(device(), arrow_data, true));
45+
}
46+
}
47+
2748
std::tuple<entt::entity, DebugMeshComponent &>
2849
DebugScene::addTriad(const Float3 &scale) {
29-
auto triad_datas = loadTriadSolid();
30-
std::vector<Float4> triad_colors(3);
31-
Mesh triad = createMeshFromBatch(device(), triad_datas, true);
32-
for (size_t i = 0; i < 3; i++) {
33-
triad_colors[i] = triad_datas[i].material.baseColor;
34-
}
35-
setupPipelines(triad.layout());
3650
entt::entity entity = m_registry.create();
3751
auto &item = m_registry.emplace<DebugMeshComponent>(
38-
entity, DebugPipelines::TRIANGLE_FILL, std::move(triad), triad_colors,
39-
true, scale);
52+
entity, DebugPipelines::TRIANGLE_FILL, TRIAD,
53+
std::vector<Float4>{m_triadColors.begin(), m_triadColors.end()}, true,
54+
scale);
4055
m_registry.emplace<TransformComponent>(entity, Mat4f::Identity());
4156
return {entity, item};
4257
}
4358

4459
std::tuple<entt::entity, DebugMeshComponent &>
4560
DebugScene::addLineGrid(const Float4 &color) {
46-
auto grid_data = loadGrid(20);
47-
Mesh grid = createMesh(device(), grid_data, true);
48-
49-
setupPipelines(grid.layout());
5061
auto entity = m_registry.create();
5162
auto &item = m_registry.emplace<DebugMeshComponent>(
52-
entity, DebugPipelines::TRIANGLE_LINE, std::move(grid),
53-
std::vector{color});
63+
entity, DebugPipelines::TRIANGLE_LINE, GRID, std::vector{color});
5464
m_registry.emplace<TransformComponent>(entity, Mat4f::Identity());
5565
return {entity, item};
5666
}
@@ -116,7 +126,7 @@ void DebugScene::render(CommandBuffer &cmdBuf, const Camera &camera) const {
116126
auto group =
117127
m_registry.view<const DebugMeshComponent, const TransformComponent>(
118128
entt::exclude<Disable>);
119-
group.each([&](auto &cmd, auto &tr) {
129+
group.each([&](const DebugMeshComponent &cmd, auto &tr) {
120130
if (!cmd.enable)
121131
return;
122132

@@ -131,11 +141,12 @@ void DebugScene::render(CommandBuffer &cmdBuf, const Camera &camera) const {
131141

132142
const GpuMat4 mvp = viewProj * tr;
133143
cmdBuf.pushVertexUniform(TRANSFORM_SLOT, mvp);
134-
rend::bindMesh(render_pass, cmd.mesh);
135-
for (size_t i = 0; i < cmd.mesh.numViews(); i++) {
144+
auto &mesh = this->getMesh(cmd.meshType);
145+
rend::bindMesh(render_pass, mesh);
146+
for (size_t i = 0; i < mesh.numViews(); i++) {
136147
const auto &color = cmd.colors[i];
137148
cmdBuf.pushFragmentUniform(COLOR_SLOT, color);
138-
rend::drawView(render_pass, cmd.mesh.view(i));
149+
rend::drawView(render_pass, mesh.view(i));
139150
}
140151
});
141152

0 commit comments

Comments
 (0)