Skip to content

Commit

Permalink
Implement the renderer in Magnum.
Browse files Browse the repository at this point in the history
Very content-free commit message, sorry.
  • Loading branch information
mosra committed Dec 16, 2021
1 parent 56f12fa commit 4693edb
Show file tree
Hide file tree
Showing 12 changed files with 1,370 additions and 28 deletions.
121 changes: 112 additions & 9 deletions src/esp/batched_sim/BatchedSimulator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,35 @@
// LICENSE file in the root directory of this source tree.

#include "BatchedSimulator.h"
#include "GlmUtils.h"

#include "esp/gfx/replay/Keyframe.h"
#include "esp/io/json.h"

// #include <bps3D.hpp>

#include <iostream>

#include <mutex>

#ifdef MAGNUM_RENDERER
#include <Magnum/GL/DefaultFramebuffer.h>
#include <Magnum/GL/Renderer.h>
#include <Magnum/BulletIntegration/Integration.h>
#else
// #include <bps3D.hpp>

#include "GlmUtils.h"
#endif

namespace esp {
namespace batched_sim {

#ifdef MAGNUM_RENDERER
using namespace Cr::Containers::Literals;
using namespace Mn::Math::Literals;
#endif

namespace {

#ifndef MAGNUM_RENDERER
Mn::Vector3 toMagnumVector3(const btVector3& src) {
return {src.x(), src.y(), src.z()};
}
Expand Down Expand Up @@ -48,9 +61,11 @@ Mn::Matrix4 toMagnumMatrix4(const btTransform& btTrans) {

return tmp2;
}
#endif

std::string getMeshNameFromURDFVisualFilepath(const std::string& filepath) {
// "../meshes/base_link.dae" => "base_link"
#ifndef MAGNUM_RENDERER
auto index0 = filepath.rfind('/');
if (index0 == -1) {
// this is okay; the substring will start at 0
Expand All @@ -60,13 +75,20 @@ std::string getMeshNameFromURDFVisualFilepath(const std::string& filepath) {

auto retval = filepath.substr(index0 + 1, index1 - index0 - 1);
return retval;
#else
return Cr::Utility::Directory::splitExtension(Cr::Utility::Directory::filename(filepath)).first;
#endif
}

} // namespace

void BatchedSimulator::randomizeRobotsForCurrentStep() {
CORRADE_INTERNAL_ASSERT(currRolloutStep_ >= 0);
#ifdef MAGNUM_RENDERER
int numEnvs = renderer_->cameras().size(); // TODO make a non-silly getter
#else
int numEnvs = bpsWrapper_->envs_.size();
#endif
int numPosVars = robot_.numPosVars;

float* yaws = &rollouts_.yaws_[currRolloutStep_ * numEnvs];
Expand All @@ -91,9 +113,19 @@ void BatchedSimulator::randomizeRobotsForCurrentStep() {

RobotInstanceSet::RobotInstanceSet(Robot* robot,
int numEnvs,
#ifdef MAGNUM_RENDERER
MagnumRenderer& renderer,
#else
std::vector<bps3D::Environment>* envs,
#endif
RolloutRecord* rollouts)
: numEnvs_(numEnvs), envs_(envs), robot_(robot), rollouts_(rollouts) {
: numEnvs_(numEnvs),
#ifdef MAGNUM_RENDERER
renderer_{&renderer},
#else
envs_(envs),
#endif
robot_(robot), rollouts_(rollouts) {
int numLinks = robot->artObj->getNumLinks();
int numNodes = numLinks + 1; // include base
int batchNumPosVars = robot_->numPosVars * numEnvs;
Expand All @@ -103,11 +135,18 @@ RobotInstanceSet::RobotInstanceSet(Robot* robot,

const auto* mb = robot_->artObj->btMultiBody_.get();

#ifndef MAGNUM_RENDERER
glm::mat4x3 identityMat(1.f, 0.f, 0.f, 1.f, 1.f, 0.f, 0.f, 0.f, 1.f, 0.f, 0.f,
0.f);
#endif

int baseInstanceIndex = 0;
for (auto& env : *envs_) {
#ifdef MAGNUM_RENDERER
for(std::size_t env = 0; env != numEnvs; ++env)
#else
for (auto& env : *envs_)
#endif
{
// sloppy: pass -1 to getLinkVisualSceneNodes to get base
for (int i = -1; i < numLinks; i++) {
const auto& link = robot->artObj->getLink(i); // -1 gets base link
Expand All @@ -118,6 +157,11 @@ RobotInstanceSet::RobotInstanceSet(Robot* robot,

int instanceId = -1;
if (!visualAttachments.empty()) {
/* 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{};
#else
const std::string linkVisualFilepath = visualAttachments[0].second;
const std::string nodeName =
getMeshNameFromURDFVisualFilepath(linkVisualFilepath);
Expand All @@ -126,6 +170,7 @@ RobotInstanceSet::RobotInstanceSet(Robot* robot,
CORRADE_INTERNAL_ASSERT(scale == 1.f);

instanceId = env.addInstance(meshIndex, mtrlIndex, identityMat);
#endif
} else {
// these are camera links
// sloppy: we should avoid having these items in the nodeInstanceIds_
Expand Down Expand Up @@ -216,7 +261,11 @@ void RobotInstanceSet::updateLinkTransforms(int currRolloutStep) {

mb->forwardKinematics(scratch_q_, scratch_m_);

#ifdef MAGNUM_RENDERER
Cr::Containers::StridedArrayView1D<Mn::Matrix4> environmentTransforms = renderer_->dynamicScenes()[b];
#else
auto& env = (*envs_)[b];
#endif
int baseInstanceIndex = b * numNodes;

// extract link transforms
Expand All @@ -235,15 +284,25 @@ void RobotInstanceSet::updateLinkTransforms(int currRolloutStep) {
// todo: avoid btTransform copy for case of i != -1
const auto btTrans = i == -1 ? mb->getBaseWorldTransform()
: mb->getLink(i).m_cachedWorldTransform;
Mn::Matrix4 mat = toMagnumMatrix4(btTrans);
Mn::Matrix4 mat =
#ifdef MAGNUM_RENDERER
Mn::Matrix4{btTrans}
#else
toMagnumMatrix4(btTrans)
#endif
;

auto tmp = robot_->nodeTransformFixups[nodeIndex];
// auto vec = tmp[3];
// const float scale = (float)b / (numEnvs_ - 1);
// tmp[3] = Mn::Vector4(vec.xyz() * scale, 1.f);
mat = mat * tmp;

#ifdef MAGNUM_RENDERER
environmentTransforms[instanceId] = mat;
#else
env.updateInstanceTransform(instanceId, toGlmMat4x3(mat));
#endif

// hack calc reward
{
Expand Down Expand Up @@ -384,6 +443,7 @@ Robot::Robot(const std::string& filepath, esp::sim::Simulator* sim) {
CORRADE_INTERNAL_ASSERT(numPosVars > 0);
}

#ifndef MAGNUM_RENDERER
BpsWrapper::BpsWrapper(int numEnvs, const CameraSensorConfig& sensor0) {
glm::u32vec2 out_dim(
sensor0.width,
Expand Down Expand Up @@ -418,10 +478,29 @@ BpsWrapper::~BpsWrapper() {
loader_ = nullptr;
renderer_ = nullptr;
}
#endif

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)
.setTileSizeCount({config_.sensor0.width, config_.sensor0.height},
// TODO better way to specify this
{16, (config_.numEnvs + 15)/16})
);
#else
bpsWrapper_ = std::make_unique<BpsWrapper>(config_.numEnvs, config_.sensor0);
#endif

#ifdef MAGNUM_RENDERER
/* Hardcode camera position + projection for all views (taken from
BpsWrapper) */
for(Mn::Matrix4& projection: renderer_->cameras()) projection =
Mn::Matrix4::perspectiveProjection(Mn::Deg(config_.sensor0.hfov), Mn::Vector2{Mn::Float(config_.sensor0.width), Mn::Float(config_.sensor0.height)}.aspectRatio(), 0.01f, 1000.0f)*
(Mn::Matrix4::from(Mn::Quaternion{{0.0f, -0.529178f, 0.0f}, 0.848511f}.toMatrix(), {-1.61004f, 1.5f, 3.5455f}).inverted());
#endif

esp::sim::SimulatorConfiguration simConfig{};
simConfig.activeSceneName = "NONE";
Expand All @@ -439,7 +518,13 @@ BatchedSimulator::BatchedSimulator(const BatchedSimulatorConfig& config) {
int numNodes = numLinks + 1; // include base

const int numEnvs = config_.numEnvs;
robots_ = RobotInstanceSet(&robot_, numEnvs, &bpsWrapper_->envs_, &rollouts_);
robots_ = RobotInstanceSet(&robot_, numEnvs,
#ifdef MAGNUM_RENDERER
*renderer_,
#else
&bpsWrapper_->envs_,
#endif
&rollouts_);

// see also python/rl/agent.py
const int numJointDegrees = robot_.numPosVars;
Expand Down Expand Up @@ -508,7 +593,11 @@ void BatchedSimulator::stepPhysics() {
currRolloutStep_ = 0;
}

#ifdef MAGNUM_RENDERER
int numEnvs = renderer_->cameras().size(); // TODO make a non-silly getter
#else
int numEnvs = bpsWrapper_->envs_.size();
#endif
int numPosVars = robot_.numPosVars;

auto& robots = robots_;
Expand All @@ -534,8 +623,8 @@ void BatchedSimulator::stepPhysics() {
// note clamp move-forward action to [0,-]
constexpr float baseMovementSpeed = 1.f;
positions[b] =
prevPositions[b] + Mn::Vector2(Mn::Math::cos(Mn::Math::Rad(yaws[b])),
-Mn::Math::sin(Mn::Math::Rad(yaws[b]))) *
prevPositions[b] + Mn::Vector2(Mn::Math::cos(Mn::Rad(yaws[b])),
-Mn::Math::sin(Mn::Rad(yaws[b]))) *
Mn::Math::max(actions_[actionIndex++], 0.f) *
baseMovementSpeed;

Expand Down Expand Up @@ -606,22 +695,32 @@ void BatchedSimulator::stepPhysicsWithReferenceActions() {

void BatchedSimulator::startRender() {
CORRADE_INTERNAL_ASSERT(isOkToRender_);
#ifdef MAGNUM_RENDERER
renderer_->draw(Mn::GL::defaultFramebuffer); // TODO nooo need a CUDA texture
#else
bpsWrapper_->renderer_->render(bpsWrapper_->envs_.data());
#endif
isOkToRender_ = false;
isRenderStarted_ = true;
}

void BatchedSimulator::waitForFrame() {
CORRADE_INTERNAL_ASSERT(isRenderStarted_);
#ifdef MAGNUM_RENDERER
Mn::GL::Renderer::finish(); // TODO U sure?
#else
bpsWrapper_->renderer_->waitForFrame();
#endif
isRenderStarted_ = false;
isOkToRender_ = true;
}

#ifndef MAGNUM_RENDERER
bps3D::Renderer& BatchedSimulator::getBpsRenderer() {
CORRADE_INTERNAL_ASSERT(bpsWrapper_->renderer_.get());
return *bpsWrapper_->renderer_.get();
}
#endif

RewardCalculationContext::RewardCalculationContext(const Robot* robot,
int numEnvs,
Expand Down Expand Up @@ -716,7 +815,11 @@ const std::vector<bool>& BatchedSimulator::getDones() {
}

void BatchedSimulator::calcRewards() {
#ifdef MAGNUM_RENDERER
int numEnvs = renderer_->cameras().size(); // TODO make a non-silly getter
#else
int numEnvs = bpsWrapper_->envs_.size();
#endif

rewardContext_.calcRewards(currRolloutStep_, 0, numEnvs);
}
Expand Down
21 changes: 21 additions & 0 deletions src/esp/batched_sim/BatchedSimulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,15 @@

#include "BpsSceneMapping.h"

#include "esp/batched_sim/configure.h"
#include "esp/physics/bullet/BulletArticulatedObject.h"
#include "esp/sim/Simulator.h"

#ifdef MAGNUM_RENDERER
#include "MagnumRenderer.h"
#else
#include <bps3D.hpp>
#endif

namespace esp {
namespace batched_sim {
Expand All @@ -21,6 +26,7 @@ struct CameraSensorConfig {
float hfov = -1.f;
};

#ifndef MAGNUM_RENDERER
struct BpsWrapper {
BpsWrapper(int numEnvs, const CameraSensorConfig& sensor0);
~BpsWrapper();
Expand All @@ -30,6 +36,7 @@ struct BpsWrapper {
std::unique_ptr<bps3D::Renderer> renderer_;
std::unique_ptr<bps3D::AssetLoader> loader_;
};
#endif

struct Robot {
Robot(const std::string& filepath, esp::sim::Simulator* sim);
Expand Down Expand Up @@ -67,7 +74,11 @@ class RobotInstanceSet {
RobotInstanceSet() = default;
RobotInstanceSet(Robot* robot,
int numEnvs,
#ifdef MAGNUM_RENDERER
MagnumRenderer& renderer_,
#else
std::vector<bps3D::Environment>* envs,
#endif
RolloutRecord* rollouts);

void updateLinkTransforms(int currRolloutStep);
Expand All @@ -82,7 +93,11 @@ class RobotInstanceSet {
btAlignedObjectArray<btQuaternion> scratch_q_;
btAlignedObjectArray<btVector3> scratch_m_;

#ifdef MAGNUM_RENDERER
MagnumRenderer* renderer_ = nullptr;
#else
std::vector<bps3D::Environment>* envs_;
#endif

std::vector<float> hackRewards_;
};
Expand Down Expand Up @@ -121,7 +136,9 @@ class BatchedSimulator {
void setActions(std::vector<float>&& actions);
void autoResetOrStepPhysics();

#ifndef MAGNUM_RENDERER
bps3D::Renderer& getBpsRenderer();
#endif

const std::vector<float>& getRewards();
const std::vector<bool>& getDones();
Expand All @@ -142,7 +159,11 @@ class BatchedSimulator {
int currRolloutStep_ = -1;
RolloutRecord rollouts_;
std::unique_ptr<esp::sim::Simulator> legacySim_;
#ifdef MAGNUM_RENDERER
Corrade::Containers::Optional<MagnumRenderer> renderer_;
#else
std::unique_ptr<BpsWrapper> bpsWrapper_;
#endif
std::vector<float> actions_;
int maxRolloutSteps_ = -1;
RewardCalculationContext rewardContext_;
Expand Down
14 changes: 14 additions & 0 deletions src/esp/batched_sim/BpsImporter.conf
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
depends=BasisImporter

[configuration]
# If enabled, imports just two meshes, one with all vertex and index data
# together and the other a MeshPrimitive::Meshlets describing views onto it
meshViews=false

# If enabled, combines all 2D textures together into a single 2D array texture
# with mip levels, throwing away levels above given size.
textureArrays=false
textureArrayMaxLevelSize=128

# Same as the format option in BasisImporter
basisFormat=
Loading

0 comments on commit 4693edb

Please sign in to comment.