Skip to content

Add Candlewick runtime (executable) #37

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Draft
wants to merge 10 commits into
base: main
Choose a base branch
from
22 changes: 16 additions & 6 deletions examples/Ur5WithSystems.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,17 +273,30 @@ int main(int argc, char **argv) {

GuiSystem gui_system{
renderer, [&](const Renderer &r) {
IMGUI_CHECKVERSION();

static bool demo_window_open = true;
static bool show_about_window = false;
static bool show_plane_vis = true;

ImGui::Begin("Renderer info & controls", nullptr,
ImGuiWindowFlags_AlwaysAutoResize);
if (show_about_window)
showCandlewickAboutWindow(&show_about_window);

ImGuiWindowFlags window_flags = 0;
window_flags |= ImGuiWindowFlags_AlwaysAutoResize;
window_flags |= ImGuiWindowFlags_MenuBar;
ImGui::Begin("Renderer info & controls", nullptr, window_flags);

if (ImGui::BeginMenuBar()) {
ImGui::MenuItem("About Candlewick", NULL, &show_about_window);
ImGui::EndMenuBar();
}

ImGui::Text("Video driver: %s", SDL_GetCurrentVideoDriver());
ImGui::SameLine();
ImGui::Text("Device driver: %s", r.device.driverName());
ImGui::Text("Display pixel density: %.2f / scale: %.2f",
r.window.pixelDensity(), r.window.displayScale());
ImGui::Text("Device driver: %s", r.device.driverName());
ImGui::SeparatorText("Camera");
bool ortho_change, persp_change;
ortho_change = ImGui::RadioButton("Orthographic", (int *)&g_cameraType,
Expand Down Expand Up @@ -348,9 +361,6 @@ int main(int argc, char **argv) {
ImGui::ColorEdit4("plane color",
plane_obj.materials[0].baseColor.data());

if (ImGui::Button("About candlewick"))
show_about_window = true;

ImGui::End();

ImGui::SetNextWindowCollapsed(true, ImGuiCond_Once);
Expand Down
14 changes: 11 additions & 3 deletions examples/Visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,24 +10,32 @@
#include <CLI/Formatter.hpp>
#include <CLI/Config.hpp>

namespace cdw = candlewick;
using namespace candlewick::multibody;
using std::chrono::steady_clock;

int main(int argc, char **argv) {
CLI::App app{"Visualizer example"};
argv = app.ensure_utf8(argv);
double fps;
std::vector<Uint32> window_dims{1920u, 1080u};
double fps = 50.0;
app.add_option("--dims", window_dims, "Window dimensions.")
->capture_default_str();
app.add_option<double, unsigned int>("--fps", fps, "Framerate")
->default_val(50);
->default_str("50.0");

CLI11_PARSE(app, argc, argv);

if (window_dims.size() != 2) {
cdw::terminate_with_message("Expected only two values for argument --dims");
}

pin::Model model;
pin::GeometryModel geom_model;
robot_descriptions::loadModelsFromToml("ur.toml", "ur5_gripper", model,
&geom_model, NULL);

Visualizer visualizer{{1920, 1280}, model, geom_model};
Visualizer visualizer{{window_dims[0], window_dims[1]}, model, geom_model};
assert(!visualizer.hasExternalData());

Eigen::VectorXd q0 = pin::neutral(model);
Expand Down
8 changes: 8 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ ADD_PROJECT_DEPENDENCY(
avcodec
swscale
)
find_package(ZeroMQ REQUIRED)

add_library(
candlewick_core
Expand Down Expand Up @@ -129,6 +130,13 @@ if(BUILD_PINOCCHIO_VISUALIZER)
INCLUDES DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
)

find_package(cppzmq)
add_executable(candlewick_visualizer candlewick/runtime/main.cpp)
target_link_libraries(
candlewick_visualizer
PRIVATE cppzmq candlewick_multibody
)
endif()

# install headers
Expand Down
5 changes: 3 additions & 2 deletions src/candlewick/core/errors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,10 @@ RAIIException::RAIIException(std::string_view msg,
location.file_name(), location.line(), msg.data())) {}

namespace detail {
std::string _error_message_impl(const char *fname, std::string_view _fmtstr,
std::string _error_message_impl(std::string_view fname,
std::string_view fmtstr,
std::format_args args) {
return std::format("{:s} :: {:s}", fname, std::vformat(_fmtstr, args));
return std::format("{:s} :: {:s}", fname, std::vformat(fmtstr, args));
}
} // namespace detail
} // namespace candlewick
7 changes: 3 additions & 4 deletions src/candlewick/core/errors.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,8 @@ struct RAIIException : std::runtime_error {

namespace detail {

std::string _error_message_impl(const char *fname, std::string_view fmtstr,
std::string _error_message_impl(std::string_view fname,
std::string_view fmtstr,
std::format_args args);

template <typename... Ts>
Expand All @@ -38,11 +39,9 @@ namespace detail {
inline void terminate_with_message(
std::string_view msg,
std::source_location location = std::source_location::current()) {
SDL_LogError(
SDL_LOG_CATEGORY_APPLICATION, "%s",
throw std::runtime_error(
detail::error_message_format(location.function_name(), "{:s}", msg)
.c_str());
::std::terminate();
}

[[noreturn]]
Expand Down
59 changes: 21 additions & 38 deletions src/candlewick/multibody/RobotScene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,10 @@
#include "Components.h"
#include "LoadPinocchioGeometry.h"
#include "../core/Components.h"
#include "../core/errors.h"
#include "../core/Shader.h"
#include "../core/Components.h"
#include "../core/TransformUniforms.h"
#include "../core/Camera.h"
#include "../core/errors.h"

#include <entt/entity/registry.hpp>
#include <coal/BVH/BVH_model.h>
Expand All @@ -26,15 +24,6 @@ struct alignas(16) light_ubo_t {
alignas(16) GpuMat4 projMat;
};

template <typename T>
requires std::is_enum_v<T>
[[noreturn]] void
invalid_enum(const char *msg, T type,
std::source_location location = std::source_location::current()) {
terminate_with_message(
std::format("{:s} - {:s}", msg, magic_enum::enum_name(type)), location);
}

void updateRobotTransforms(entt::registry &registry,
const pin::GeometryData &geom_data) {
auto robot_view =
Expand Down Expand Up @@ -77,9 +66,7 @@ auto RobotScene::pinGeomToPipeline(const coal::CollisionGeometry &geom)
void add_pipeline_tag_component(entt::registry &reg, entt::entity ent,
RobotScene::PipelineType type) {
magic_enum::enum_switch(
[&reg, ent](auto pt) {
reg.emplace<RobotScene::pipeline_tag_component<pt>>(ent);
},
[&reg, ent](auto pt) { reg.emplace<RobotScene::pipeline_tag<pt>>(ent); },
type);
}

Expand Down Expand Up @@ -165,11 +152,18 @@ void RobotScene::loadModels(const pin::GeometryModel &geom_model,
const auto &geom_obj = geom_model.geometryObjects[geom_id];
auto meshDatas = loadGeometryObject(geom_obj);
PipelineType pipeline_type = pinGeomToPipeline(*geom_obj.geometry);
auto mesh = createMeshFromBatch(device(), meshDatas, true);
Mesh mesh = createMeshFromBatch(device(), meshDatas, true);
SDL_assert(validateMesh(mesh));

// local copy for use
const auto layout = mesh.layout();
if (!renderPipelines[pipeline_type]) {
SDL_Log("Building pipeline for type %s",
magic_enum::enum_name(pipeline_type).data());
renderPipelines[pipeline_type] =
createPipeline(layout, m_renderer.getSwapchainTextureFormat(),
m_renderer.depthFormat(), pipeline_type);
SDL_assert(renderPipelines[pipeline_type]);
}

// add entity for this geometry
entt::entity entity = m_registry.create();
Expand All @@ -191,16 +185,6 @@ void RobotScene::loadModels(const pin::GeometryModel &geom_model,
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, m_renderer.getSwapchainTextureFormat(),
m_renderer.depthFormat(), pipeline_type);
SDL_assert(pipeline);
renderPipelines[pipeline_type] = pipeline;
}
}
m_initialized = true;
}
Expand All @@ -210,11 +194,10 @@ void RobotScene::updateTransforms() {
}

void RobotScene::collectOpaqueCastables() {
auto all_view =
m_registry.view<const Opaque, const TransformComponent,
const MeshMaterialComponent,
pipeline_tag_component<PIPELINE_TRIANGLEMESH>>(
entt::exclude<Disable>);
auto all_view = m_registry.view<const Opaque, const TransformComponent,
const MeshMaterialComponent,
pipeline_tag<PIPELINE_TRIANGLEMESH>>(
entt::exclude<Disable>);

m_castables.clear();

Expand Down Expand Up @@ -331,7 +314,7 @@ void RobotScene::renderPBRTriangleGeometry(CommandBuffer &command_buffer,

auto all_view =
m_registry.view<const TransformComponent, const MeshMaterialComponent,
pipeline_tag_component<PIPELINE_TRIANGLEMESH>>(
pipeline_tag<PIPELINE_TRIANGLEMESH>>(
entt::exclude<Disable>);
for (auto [ent, tr, obj] : all_view.each()) {
const Mat4f modelView = camera.view * tr;
Expand Down Expand Up @@ -378,12 +361,11 @@ void RobotScene::renderOtherGeometry(CommandBuffer &command_buffer,

auto env_view =
m_registry.view<const TransformComponent, const MeshMaterialComponent,
pipeline_tag_component<current_pipeline_type>>(
pipeline_tag<current_pipeline_type>>(
entt::exclude<Disable>);
for (auto [entity, tr, obj] : env_view.each()) {
auto &modelMat = tr;
for (auto &&[entity, tr, obj] : env_view.each()) {
const Mesh &mesh = obj.mesh;
const Mat4f mvp = viewProj * modelMat;
const Mat4f mvp = viewProj * tr;
const auto &color = obj.materials[0].baseColor;
command_buffer
.pushVertexUniform(VertexUniformSlots::TRANSFORM, &mvp, sizeof(mvp))
Expand All @@ -400,9 +382,10 @@ void RobotScene::release() {
if (!device())
return;

m_registry.clear<MeshMaterialComponent>();
clearEnvironment();
clearRobotGeometries();

for (auto &pipeline : renderPipelines) {
for (auto *pipeline : renderPipelines) {
SDL_ReleaseGPUGraphicsPipeline(device(), pipeline);
pipeline = nullptr;
}
Expand Down
15 changes: 14 additions & 1 deletion src/candlewick/multibody/RobotScene.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,19 @@
#include <pinocchio/multibody/fwd.hpp>

namespace candlewick {

/// \brief Terminate the application after encountering an invalid enum value.
template <typename T>
requires std::is_enum_v<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);
}

namespace multibody {

void updateRobotTransforms(entt::registry &registry,
Expand Down Expand Up @@ -63,7 +76,7 @@ namespace multibody {
}
}

template <PipelineType t> using pipeline_tag_component = entt::tag<t>;
template <PipelineType t> using pipeline_tag = entt::tag<t>;

struct PipelineConfig {
// shader set
Expand Down
13 changes: 13 additions & 0 deletions src/candlewick/multibody/VisualizerClient.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
#pragma once

#include "Multibody.h"
#include <pinocchio/visualizers/base-visualizer.hpp>
#include <zmq.h>

namespace candlewick {
namespace multibody {
class VisualizerClient final : public pin::visualizers::BaseVisualizer {
public:
};
} // namespace multibody
} // namespace candlewick
63 changes: 63 additions & 0 deletions src/candlewick/runtime/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
#include <zmq.hpp>
#include <zmq_addon.hpp>
#include "candlewick/multibody/Multibody.h"
#include "candlewick/multibody/Visualizer.h"

#include <pinocchio/serialization/model.hpp>
#include <pinocchio/serialization/geometry.hpp>

#include <CLI/App.hpp>
#include <CLI/Formatter.hpp>
#include <CLI/Config.hpp>

namespace cdw = candlewick;
namespace pin = pinocchio;
using cdw::multibody::Visualizer;

int main(int argc, char **argv) {
CLI::App app{"Candlewick visualizer runtime"};
argv = app.ensure_utf8(argv);

std::vector<Uint32> window_dims{1920u, 1080u};
app.add_option("--dims", window_dims, "Window dimensions.")
->capture_default_str();

CLI11_PARSE(app, argc, argv);

if (window_dims.size() != 2) {
cdw::terminate_with_message("Expected only two values for argument --dims");
}

zmq::context_t ctx;
zmq::socket_t sock{ctx, zmq::socket_type::pull};
sock.bind("tcp://127.0.0.1:12000");
const std::string endpoint = sock.get(zmq::sockopt::last_endpoint);
printf("ZMQ endpoint: %s\n", endpoint.c_str());

pin::Model model;
pin::GeometryModel geom_model;

std::vector<zmq::message_t> recv_models;

printf("Receiving Model and GeometryModel...\n");

const auto ret = zmq::recv_multipart(sock, std::back_inserter(recv_models));
assert(*ret == 2);
printf("Received %zu messages\n", ret.value());

model.loadFromString(recv_models[0].to_string());
geom_model.loadFromString(recv_models[1].to_string());

Visualizer::Config config;
config.width = window_dims[0];
config.height = window_dims[1];
Visualizer viz{config, model, geom_model};

Eigen::VectorXd q0 = pin::neutral(model);

while (!viz.shouldExit()) {
viz.display(q0);
}

return 0;
}
19 changes: 19 additions & 0 deletions tests/test_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
import pinocchio as pin
import example_robot_data as erd
import zmq


PORT = 12000

ctx = zmq.Context.instance()
sock: zmq.Socket = ctx.socket(zmq.SocketType.PUSH)
sock.connect(f"tcp://127.0.0.1:{PORT}")

robot: pin.RobotWrapper = erd.load("solo12")
model = robot.model
geom_model = robot.visual_model

model_str = model.saveToString()
geom_str = geom_model.saveToString()
sock.send_multipart([model_str.encode(), geom_str.encode()])
print("Sent")
Loading