mirror of
https://github.com/karma-riuk/hdr_esim.git
synced 2025-06-18 18:37:51 +02:00
Reformated the project to make it more readable (to me)
This commit is contained in:
@ -1,49 +1,55 @@
|
||||
#pragma once
|
||||
|
||||
#include <ze/common/macros.hpp>
|
||||
#include <esim/common/types.hpp>
|
||||
#include <ze/common/macros.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);
|
||||
//! 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() {}
|
||||
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;
|
||||
//! 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;
|
||||
|
||||
//! 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 {}
|
||||
|
||||
//! 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;
|
||||
|
||||
//! Sets the camera
|
||||
virtual void setCamera(const ze::Camera::Ptr& camera) = 0;
|
||||
//! Get the camera rig
|
||||
const ze::Camera::Ptr& getCamera() const {
|
||||
return camera_;
|
||||
}
|
||||
|
||||
//! Get the camera rig
|
||||
const ze::Camera::Ptr& getCamera() const { return camera_; }
|
||||
|
||||
protected:
|
||||
ze::Camera::Ptr camera_;
|
||||
};
|
||||
protected:
|
||||
ze::Camera::Ptr camera_;
|
||||
};
|
||||
|
||||
} // namespace event_camera_simulator
|
||||
|
@ -1,32 +1,35 @@
|
||||
#pragma once
|
||||
|
||||
#include <ze/common/macros.hpp>
|
||||
#include <esim/common/types.hpp>
|
||||
#include <ze/common/macros.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);
|
||||
//! 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() {}
|
||||
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;
|
||||
//! 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 height of the image plane
|
||||
virtual int getWidth() const = 0;
|
||||
|
||||
//! Get the width of the image plane
|
||||
virtual int getHeight() const = 0;
|
||||
//! Get the width of the image plane
|
||||
virtual int getHeight() const = 0;
|
||||
|
||||
protected:
|
||||
};
|
||||
protected:
|
||||
};
|
||||
|
||||
} // namespace event_camera_simulator
|
||||
|
@ -1,5 +1,3 @@
|
||||
#include <esim/rendering/renderer_base.hpp>
|
||||
|
||||
namespace event_camera_simulator {
|
||||
|
||||
} // namespace event_camera_simulator
|
||||
namespace event_camera_simulator {} // namespace event_camera_simulator
|
||||
|
@ -1,5 +1,3 @@
|
||||
#include <esim/rendering/simple_renderer_base.hpp>
|
||||
|
||||
namespace event_camera_simulator {
|
||||
|
||||
} // namespace event_camera_simulator
|
||||
namespace event_camera_simulator {} // namespace event_camera_simulator
|
||||
|
Reference in New Issue
Block a user