Skip to content
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

Remove deprecated WGPU swapchain, allow window to resize #6

Merged
merged 2 commits into from
Sep 15, 2024
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 simulator/simulator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -273,7 +273,6 @@ namespace mrover {
wgpu::Device mDevice;
std::unique_ptr<wgpu::ErrorCallback> mErrorCallback;
wgpu::Queue mQueue;
wgpu::SwapChain mSwapChain;
wgpu::Texture mDepthTexture;
wgpu::TextureView mDepthTextureView;
wgpu::Texture mNormalTexture;
Expand Down
47 changes: 30 additions & 17 deletions simulator/simulator.render.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,15 @@ namespace mrover {
}

auto Simulator::makeFramebuffers(int width, int height) -> void {
wgpu::SwapChainDescriptor descriptor;
descriptor.usage = wgpu::TextureUsage::RenderAttachment;
descriptor.format = COLOR_FORMAT;
descriptor.width = width;
descriptor.height = height;
descriptor.presentMode = wgpu::PresentMode::Immediate;
mSwapChain = mDevice.createSwapChain(mSurface, descriptor);
if (!mSwapChain) throw std::runtime_error("Failed to create WGPU swap chain");
wgpu::SurfaceConfiguration surfaceConfiguration;
surfaceConfiguration.device = mDevice;
surfaceConfiguration.format = COLOR_FORMAT;
surfaceConfiguration.usage = wgpu::TextureUsage::RenderAttachment;
surfaceConfiguration.width = width;
surfaceConfiguration.height = height;
surfaceConfiguration.alphaMode = wgpu::CompositeAlphaMode::Auto;
surfaceConfiguration.presentMode = wgpu::PresentMode::Immediate;
mSurface.configure(surfaceConfiguration);
std::tie(mNormalTexture, mNormalTextureView) = makeTextureAndView(width, height, NORMAL_FORMAT, wgpu::TextureUsage::RenderAttachment, wgpu::TextureAspect::All);
std::tie(mDepthTexture, mDepthTextureView) = makeTextureAndView(width, height, DEPTH_FORMAT, wgpu::TextureUsage::RenderAttachment, wgpu::TextureAspect::DepthOnly);
}
Expand Down Expand Up @@ -203,7 +204,9 @@ namespace mrover {
constexpr auto WINDOW_NAME = "MRover Simulator (DEBUG BUILD, MAY BE SLOW)";
#endif
glfwWindowHint(GLFW_CLIENT_API, GLFW_NO_API);
glfwWindowHint(GLFW_RESIZABLE, GLFW_FALSE);
// There is still an off-by-one error on Vulkan with resizing windows and ImGui.
// See: https://matrix.to/#/!ZSOHTEPDbwuEgSJwYw:matrix.org
glfwWindowHint(GLFW_RESIZABLE, GLFW_TRUE);
glfwWindowHint(GLFW_COCOA_RETINA_FRAMEBUFFER, GLFW_FALSE);
mWindow = GlfwPointer<GLFWwindow, glfwCreateWindow, glfwDestroyWindow>{w, h, WINDOW_NAME, nullptr, nullptr};
RCLCPP_INFO_STREAM(get_logger(), std::format("Created window of size: {}x{}", w, h));
Expand Down Expand Up @@ -258,7 +261,7 @@ namespace mrover {
mNormalTextureView.release();
mNormalTexture.destroy();
mNormalTexture.release();
mSwapChain.release();
mSurface.unconfigure();

makeFramebuffers(width, height);
}
Expand Down Expand Up @@ -492,7 +495,7 @@ namespace mrover {
for (int i = 0; i < compound->getNumChildShapes(); ++i) {
SE3d modelInLink = btTransformToSe3(urdfPoseToBtTransform(link->collision_array.at(i)->origin));
SE3d modelInWorld = linkToWorld * modelInLink;
auto* shape = compound->getChildShape(i);
btCollisionShape* shape = compound->getChildShape(i);
if (auto* box = dynamic_cast<btBoxShape const*>(shape)) {
btVector3 extents = box->getHalfExtentsWithoutMargin() * 2;
SIM3 modelToWorld{modelInWorld, R3d{extents.x(), extents.y(), extents.z()}};
Expand Down Expand Up @@ -723,10 +726,20 @@ namespace mrover {
camerasUpdate(encoder, colorAttachment, normalAttachment, depthStencilAttachment, renderPassDescriptor);

if (!mIsHeadless) {
wgpu::TextureView nextTexture = mSwapChain.getCurrentTextureView();
if (!nextTexture) throw std::runtime_error("Failed to get WGPU next texture view");

colorAttachment.view = nextTexture;
wgpu::SurfaceTexture surfaceTexture;
mSurface.getCurrentTexture(&surfaceTexture);
if (surfaceTexture.status != wgpu::SurfaceGetCurrentTextureStatus::Success)
throw std::runtime_error{"Failed to get WGPU surface texture"};

wgpu::TextureViewDescriptor nextTextureViewDescriptor;
nextTextureViewDescriptor.format = COLOR_FORMAT;
nextTextureViewDescriptor.dimension = wgpu::TextureViewDimension::_2D;
nextTextureViewDescriptor.mipLevelCount = 1;
nextTextureViewDescriptor.arrayLayerCount = 1;
nextTextureViewDescriptor.aspect = wgpu::TextureAspect::All;
wgpu::TextureView nextTextureView = wgpu::Texture{surfaceTexture.texture}.createView(nextTextureViewDescriptor);

colorAttachment.view = nextTextureView;
normalAttachment.view = mNormalTextureView;
depthStencilAttachment.view = mDepthTextureView;

Expand Down Expand Up @@ -768,7 +781,7 @@ namespace mrover {

bindGroup.release();

nextTexture.release();
nextTextureView.release();
}

wgpu::CommandBuffer commands = encoder.finish();
Expand All @@ -791,7 +804,7 @@ namespace mrover {
}
#endif

if (!mIsHeadless) mSwapChain.present();
if (!mIsHeadless) mSurface.present();

// TODO(quintin): Remote duplicate code
for (StereoCamera& stereoCamera: mStereoCameras) {
Expand Down