Skip to content

Commit

Permalink
[wip] very dirty CUDA hookup
Browse files Browse the repository at this point in the history
VERY
  • Loading branch information
mosra committed Dec 21, 2021
1 parent 9475d1e commit 9ab8474
Show file tree
Hide file tree
Showing 14 changed files with 360 additions and 59 deletions.
41 changes: 34 additions & 7 deletions src/esp/batched_sim/BatchedSimulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ void BatchedSimulator::randomizeRobotsForCurrentStep() {
RobotInstanceSet::RobotInstanceSet(Robot* robot,
int numEnvs,
#ifdef MAGNUM_RENDERER
MagnumRenderer& renderer,
MagnumRendererStandalone& renderer,
#else
std::vector<bps3D::Environment>* envs,
#endif
Expand Down Expand Up @@ -160,7 +160,8 @@ RobotInstanceSet::RobotInstanceSet(Robot* robot,
/* The Magnum renderer contains the dynamic URDF scene already, just
reset the link transformations to identities */
#ifdef MAGNUM_RENDERER
renderer.dynamicScenes()[env][i] = Mn::Matrix4{};
if(i != -1)
renderer.dynamicScenes()[env][i] = Mn::Matrix4{};
#else
const std::string linkVisualFilepath = visualAttachments[0].second;
const std::string nodeName =
Expand Down Expand Up @@ -408,9 +409,14 @@ Robot::Robot(const std::string& filepath, esp::sim::Simulator* sim) {

artObj = static_cast<esp::physics::BulletArticulatedObject*>(
managedObj->hackGetBulletObjectReference().get());
#ifdef MAGNUM_RENDERER
sceneMapping = BpsSceneMapping::loadFromFile(
"combined_Stage_v3_sc0_staging_trimesh.bps.mapping.json");
#else
sceneMapping = BpsSceneMapping::loadFromFile(
"../data/bps_data/combined_Stage_v3_sc0_staging/"
"combined_Stage_v3_sc0_staging_trimesh.bps.mapping.json");
#endif

jointPositionLimits = artObj->getJointPositionLimits();

Expand Down Expand Up @@ -484,8 +490,9 @@ BatchedSimulator::BatchedSimulator(const BatchedSimulatorConfig& config) {
config_ = config;
#ifdef MAGNUM_RENDERER
renderer_.emplace(MagnumRendererConfiguration{}
.setFilename("../data/bps_data/combined_Stage_v3_sc0_staging/"
"combined_Stage_v3_sc0_staging_trimesh.bps"_s)
// TODO Yes, sorry, you have to cd into this dir first, otherwise it won't
// find the ktx files
.setFilename("combined_Stage_v3_sc0_staging_trimesh.bps"_s)
.setTileSizeCount({config_.sensor0.width, config_.sensor0.height},
// TODO better way to specify this
{16, (config_.numEnvs + 15)/16})
Expand All @@ -511,7 +518,11 @@ BatchedSimulator::BatchedSimulator(const BatchedSimulatorConfig& config) {

legacySim_ = esp::sim::Simulator::create_unique(simConfig);

#ifdef MAGNUM_RENDERER
const std::string filepath = "../../URDF/opt_fetch/robots/fetch.urdf";
#else
const std::string filepath = "../data/URDF/opt_fetch/robots/fetch.urdf";
#endif

robot_ = Robot(filepath, legacySim_.get());
int numLinks = robot_.artObj->getNumLinks();
Expand Down Expand Up @@ -696,7 +707,7 @@ void BatchedSimulator::stepPhysicsWithReferenceActions() {
void BatchedSimulator::startRender() {
CORRADE_INTERNAL_ASSERT(isOkToRender_);
#ifdef MAGNUM_RENDERER
renderer_->draw(Mn::GL::defaultFramebuffer); // TODO nooo need a CUDA texture
renderer_->draw();
#else
bpsWrapper_->renderer_->render(bpsWrapper_->envs_.data());
#endif
Expand All @@ -707,15 +718,20 @@ void BatchedSimulator::startRender() {
void BatchedSimulator::waitForFrame() {
CORRADE_INTERNAL_ASSERT(isRenderStarted_);
#ifdef MAGNUM_RENDERER
Mn::GL::Renderer::finish(); // TODO U sure?
/* Nothing, all blocking will happen when retrieving the CUDA device
pointer */
#else
bpsWrapper_->renderer_->waitForFrame();
#endif
isRenderStarted_ = false;
isOkToRender_ = true;
}

#ifndef MAGNUM_RENDERER
#ifdef MAGNUM_RENDERER
MagnumRendererStandalone& BatchedSimulator::getMagnumRenderer() {
return *renderer_;
}
#else
bps3D::Renderer& BatchedSimulator::getBpsRenderer() {
CORRADE_INTERNAL_ASSERT(bpsWrapper_->renderer_.get());
return *bpsWrapper_->renderer_.get();
Expand All @@ -727,8 +743,13 @@ RewardCalculationContext::RewardCalculationContext(const Robot* robot,
RolloutRecord* rollouts)
: robot_(robot), numEnvs_(numEnvs), rollouts_(rollouts) {
esp::sim::SimulatorConfiguration simConfig{};
#ifdef MAGNUM_RENDERER
simConfig.activeSceneName =
"../../stages/Stage_v3_sc0_staging_no_textures.glb";
#else
simConfig.activeSceneName =
"../data/stages/Stage_v3_sc0_staging_no_textures.glb";
#endif
simConfig.enablePhysics = true;
simConfig.createRenderer = false;
simConfig.loadRenderAssets =
Expand All @@ -738,7 +759,13 @@ RewardCalculationContext::RewardCalculationContext(const Robot* robot,
legacySim_ = esp::sim::Simulator::create_unique(simConfig);

// todo: avoid code duplication with Robot

#ifdef MAGNUM_RENDERER
const std::string filepath = "../../URDF/opt_fetch/robots/fetch.urdf";
#else
const std::string filepath = "../data/URDF/opt_fetch/robots/fetch.urdf";
#endif

// todo: delete object on destruction
auto managedObj = legacySim_->getArticulatedObjectManager()
->addBulletArticulatedObjectFromURDF(filepath);
Expand Down
12 changes: 7 additions & 5 deletions src/esp/batched_sim/BatchedSimulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include "esp/sim/Simulator.h"

#ifdef MAGNUM_RENDERER
#include "MagnumRenderer.h"
#include "MagnumRendererStandalone.h"
#else
#include <bps3D.hpp>
#endif
Expand Down Expand Up @@ -75,7 +75,7 @@ class RobotInstanceSet {
RobotInstanceSet(Robot* robot,
int numEnvs,
#ifdef MAGNUM_RENDERER
MagnumRenderer& renderer_,
MagnumRendererStandalone& renderer_,
#else
std::vector<bps3D::Environment>* envs,
#endif
Expand All @@ -94,7 +94,7 @@ class RobotInstanceSet {
btAlignedObjectArray<btVector3> scratch_m_;

#ifdef MAGNUM_RENDERER
MagnumRenderer* renderer_ = nullptr;
MagnumRendererStandalone* renderer_ = nullptr;
#else
std::vector<bps3D::Environment>* envs_;
#endif
Expand Down Expand Up @@ -136,7 +136,9 @@ class BatchedSimulator {
void setActions(std::vector<float>&& actions);
void autoResetOrStepPhysics();

#ifndef MAGNUM_RENDERER
#ifdef MAGNUM_RENDERER
MagnumRendererStandalone& getMagnumRenderer();
#else
bps3D::Renderer& getBpsRenderer();
#endif

Expand All @@ -160,7 +162,7 @@ class BatchedSimulator {
RolloutRecord rollouts_;
std::unique_ptr<esp::sim::Simulator> legacySim_;
#ifdef MAGNUM_RENDERER
Corrade::Containers::Optional<MagnumRenderer> renderer_;
Corrade::Containers::Optional<MagnumRendererStandalone> renderer_;
#else
std::unique_ptr<BpsWrapper> bpsWrapper_;
#endif
Expand Down
44 changes: 36 additions & 8 deletions src/esp/batched_sim/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,18 +1,20 @@
option(MAGNUM_RENDERER "Use Magnum renderer instead of BPS3D" ON)

configure_file(${CMAKE_CURRENT_SOURCE_DIR}/configure.h.cmake
${CMAKE_CURRENT_BINARY_DIR}/configure.h)

# Required by Magnum
if(MAGNUM_RENDERER)
if(NOT BUILD_WITH_CUDA)
message(FATAL_ERROR "BUILD_WITH_CUDA has to be enabled for the Magnum Batch Renderer")
endif()
# Required by BPS3D
if(NOT MAGNUM_RENDERER)
else()
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED 17)
endif()

# BpsImporter plugin
if(MAGNUM_RENDERER)
find_package(Corrade REQUIRED PluginManager)
find_package(Magnum REQUIRED GL GlfwApplication Trade MeshTools Shaders DebugTools)
find_package(Magnum REQUIRED GL GlfwApplication Trade MeshTools Shaders DebugTools WindowlessEglApplication)
if(MAGNUM_BUILD_STATIC)
find_package(MagnumPlugins REQUIRED BasisImporter)
corrade_add_static_plugin(BpsImporter ";" BpsImporter.conf BpsImporter.cpp)
Expand All @@ -22,6 +24,16 @@ if(MAGNUM_RENDERER)
target_link_libraries(BpsImporter PUBLIC Magnum::Trade)
endif()

if(MAGNUM_RENDERER AND NOT MAGNUM_BUILD_STATIC)
set(BPSIMPORTER_PLUGIN_FILENAME $<TARGET_FILE:BpsImporter>)
endif()

# First replace ${} variables, then $<> generator expressions
configure_file(${CMAKE_CURRENT_SOURCE_DIR}/configure.h.cmake
${CMAKE_CURRENT_BINARY_DIR}/configure.h.in)
file(GENERATE OUTPUT ${CMAKE_CURRENT_BINARY_DIR}/configure.h
INPUT ${CMAKE_CURRENT_BINARY_DIR}/configure.h.in)

# The batched_sim library
set(batched_sim_SRCS
BatchedSimulator.cpp
Expand All @@ -33,6 +45,8 @@ if(MAGNUM_RENDERER)
list(APPEND batched_sim_SRCS
MagnumRenderer.cpp
MagnumRenderer.h
MagnumRendererStandalone.cpp
MagnumRendererStandalone.h
)
else()
list(APPEND batched_sim_SRCS
Expand All @@ -46,13 +60,25 @@ target_link_libraries(
PUBLIC core sim)
target_include_directories(batched_sim PRIVATE ${CMAKE_BINARY_DIR})
if(MAGNUM_RENDERER)
target_include_directories(batched_sim PRIVATE
${CMAKE_CUDA_TOOLKIT_INCLUDE_DIRECTORIES}
${CMAKE_CURRENT_LIST_DIR}/../gfx/cuda_helpers
)
target_link_libraries(batched_sim PUBLIC ${CUDART_LIBRARY})
target_link_libraries(batched_sim PRIVATE
Magnum::GL
Magnum::Magnum
Magnum::Shaders
Magnum::Trade
Magnum::MeshTools)
add_dependencies(batched_sim BpsImporter)
Magnum::MeshTools
Magnum::WindowlessEglApplication)
if(MAGNUM_BUILD_STATIC)
target_link_libraries(batched_sim PRIVATE
MagnumPlugins::BasisImporter
BpsImporter)
else()
add_dependencies(batched_sim BpsImporter)
endif()
else()
target_link_libraries(
batched_sim
Expand All @@ -77,7 +103,9 @@ if(MAGNUM_RENDERER)
Magnum::Shaders
Magnum::Trade
Magnum::MeshTools)

target_include_directories(MagnumRendererDemo PRIVATE
${PROJECT_BINARY_DIR}
)
if(MAGNUM_BUILD_STATIC)
target_link_libraries(MagnumRendererDemo PRIVATE
MagnumPlugins::BasisImporter
Expand Down
27 changes: 23 additions & 4 deletions src/esp/batched_sim/MagnumRenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,12 @@
#include <Magnum/Trade/SceneData.h>
#include <Magnum/Trade/TextureData.h>

#include "esp/batched_sim/configure.h"

#ifdef MAGNUM_BUILD_STATIC
int importStaticPlugins() {
void importStaticPlugins() {
CORRADE_PLUGIN_IMPORT(BpsImporter)
return 0;
} CORRADE_AUTOMATIC_INITIALIZER(importStaticPlugins);
}
#endif

namespace Cr = Corrade;
Expand All @@ -47,7 +48,13 @@ using namespace Cr::Containers::Literals;
struct MagnumRendererConfiguration::State {
Cr::Containers::String filename;
Cr::Containers::String importer =
Cr::Containers::String::nullTerminatedGlobalView("BpsImporter"_s);
Cr::Containers::String::nullTerminatedGlobalView(
#ifdef MAGNUM_BUILD_STATIC
"BpsImporter"_s
#else
BPSIMPORTER_PLUGIN_FILENAME
#endif
);
MagnumRendererFlags flags;
Magnum::Vector2i tileSize{128, 128};
Magnum::Vector2i tileCount{16, 12};
Expand Down Expand Up @@ -107,6 +114,10 @@ struct MagnumRenderer::State {
};

MagnumRenderer::MagnumRenderer(const MagnumRendererConfiguration& configurationWrapper): _state{Cr::InPlaceInit} {
#ifdef MAGNUM_BUILD_STATIC
importStaticPlugins();
#endif

const MagnumRendererConfiguration::State& configuration = *configurationWrapper.state;

_state->tileSize = configuration.tileSize;
Expand Down Expand Up @@ -308,6 +319,14 @@ Cr::Containers::StridedArrayView2D<Mn::Matrix4> MagnumRenderer::dynamicScenes()
}.suffix({0, _state->staticSceneSize});
}

Mn::Vector2i MagnumRenderer::tileCount() const {
return _state->tileCount;
}

Mn::Vector2i MagnumRenderer::tileSize() const {
return _state->tileSize;
}

void MagnumRenderer::draw(Mn::GL::AbstractFramebuffer& framebuffer) {
/* Upload projection and transformation uniforms, assuming they change every
frame */
Expand Down
3 changes: 3 additions & 0 deletions src/esp/batched_sim/MagnumRenderer.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@ class MagnumRenderer {
Corrade::Containers::StridedArrayView1D<Magnum::Matrix4> cameras();
Corrade::Containers::StridedArrayView2D<Magnum::Matrix4> dynamicScenes();

Magnum::Vector2i tileSize() const;
Magnum::Vector2i tileCount() const;

void draw(Magnum::GL::AbstractFramebuffer& framebuffer);

private:
Expand Down
17 changes: 8 additions & 9 deletions src/esp/batched_sim/MagnumRendererDemo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,8 @@ class MagnumRendererDemo: public Mn::Platform::Application {
MagnumRendererDemo::MagnumRendererDemo(const Arguments& arguments): Mn::Platform::Application{arguments, Mn::NoCreate} {
Cr::Utility::Arguments args;
args.addArgument("file").setHelp("file", "bps file to load")
#ifdef MAGNUM_BUILD_STATIC
.addOption('I', "importer", "BpsImporter")
#else
.addNamedArgument('I', "importer")
#endif
.setHelp("importer", "path to the bps importer plugin")
.addOption('I', "importer")
.setHelp("importer", "importer plugin to use instead of BpsImporter")
.addBooleanOption("profile")
.setHelp("profile", "profile frame times")
.addOption('S', "size", "128 128")
Expand All @@ -59,11 +55,14 @@ MagnumRendererDemo::MagnumRendererDemo(const Arguments& arguments): Mn::Platform
.setTitle("Magnum Renderer Demo"));

/* Create the renderer */
_renderer.emplace(MagnumRendererConfiguration{}
MagnumRendererConfiguration configuration;
configuration
.setFilename(args.value("file"))
.setImporter(args.value("importer"))
.setFlags(args.isSet("no-textures") ? MagnumRendererFlag::NoTextures : MagnumRendererFlags{})
.setTileSizeCount(tileSize, tileCount));
.setTileSizeCount(tileSize, tileCount);
if(!args.value("importer").empty())
configuration.setImporter(args.value("importer"));
_renderer.emplace(configuration);

/* Hardcode camera position + projection for all views (taken from
BatchSimulator.cpp) */
Expand Down
Loading

0 comments on commit 9ab8474

Please sign in to comment.