initial commit

This commit is contained in:
Henri Rebecq
2018-10-29 17:53:15 +01:00
commit a8c2f0ca43
208 changed files with 554184 additions and 0 deletions

View File

@ -0,0 +1,22 @@
cmake_minimum_required(VERSION 2.8.3)
project(esim_rendering)
find_package(catkin_simple REQUIRED)
find_package(OpenCV REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
catkin_simple()
set(HEADERS
include/esim/rendering/renderer_base.hpp
include/esim/rendering/simple_renderer_base.hpp
)
set(SOURCES
src/renderer_base.cpp
src/simple_renderer_base.cpp
)
cs_add_library(${PROJECT_NAME} ${SOURCES} ${HEADERS})
cs_install()
cs_export()

View File

@ -0,0 +1,49 @@
#pragma once
#include <ze/common/macros.hpp>
#include <esim/common/types.hpp>
namespace event_camera_simulator {
//! Represents a rendering engine that generates images (and other outputs,
//! such as depth maps, or optical flow maps) given a scene and a camera position.
class Renderer
{
public:
ZE_POINTER_TYPEDEFS(Renderer);
Renderer() {}
//! Render an image at a given pose.
virtual void render(const Transformation& T_W_C,
const std::vector<Transformation>& T_W_OBJ,
const ImagePtr& out_image,
const DepthmapPtr& out_depthmap) const = 0;
//! Returns true if the rendering engine can compute optic flow, false otherwise
virtual bool canComputeOpticFlow() const = 0;
//! Render an image + depth map + optic flow map at a given pose,
//! given the camera linear and angular velocity
virtual void renderWithFlow(const Transformation& T_W_C,
const LinearVelocity& v_WC,
const AngularVelocity& w_WC,
const std::vector<Transformation>& T_W_OBJ,
const std::vector<LinearVelocity>& linear_velocity_obj,
const std::vector<AngularVelocity>& angular_velocity_obj,
const ImagePtr& out_image,
const DepthmapPtr& out_depthmap,
const OpticFlowPtr& optic_flow_map) const {}
//! Sets the camera
virtual void setCamera(const ze::Camera::Ptr& camera) = 0;
//! Get the camera rig
const ze::Camera::Ptr& getCamera() const { return camera_; }
protected:
ze::Camera::Ptr camera_;
};
} // namespace event_camera_simulator

View File

@ -0,0 +1,32 @@
#pragma once
#include <ze/common/macros.hpp>
#include <esim/common/types.hpp>
namespace event_camera_simulator {
//! Represents a rendering engine that generates images + optic flow maps
//! The rendering engine takes care of managing the environment and camera trajectory in the environment
class SimpleRenderer
{
public:
ZE_POINTER_TYPEDEFS(SimpleRenderer);
SimpleRenderer() {}
//! Render an image + optic flow map at a given time t.
//! The rendering engine takes care of generating the camera trajectory, etc.
virtual bool render(const Time t,
const ImagePtr& out_image,
const OpticFlowPtr& optic_flow_map) const = 0;
//! Get the height of the image plane
virtual int getWidth() const = 0;
//! Get the width of the image plane
virtual int getHeight() const = 0;
protected:
};
} // namespace event_camera_simulator

View File

@ -0,0 +1,20 @@
<?xml version="1.0"?>
<package format="2">
<name>esim_rendering</name>
<version>0.0.0</version>
<description>Rendering engines for the event camera simulator.</description>
<maintainer email="rebecq@ifi.uzh.ch">Henri Rebecq</maintainer>
<license>GPLv3</license>
<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend>catkin_simple</buildtool_depend>
<depend>esim_common</depend>
<depend>ze_common</depend>
<depend>ze_cameras</depend>
<depend>gflags_catkin</depend>
<depend>glog_catkin</depend>
</package>

View File

@ -0,0 +1,5 @@
#include <esim/rendering/renderer_base.hpp>
namespace event_camera_simulator {
} // namespace event_camera_simulator

View File

@ -0,0 +1,5 @@
#include <esim/rendering/simple_renderer_base.hpp>
namespace event_camera_simulator {
} // namespace event_camera_simulator