mirror of
https://github.com/karma-riuk/hdr_esim.git
synced 2025-07-05 02:18:13 +02:00
initial commit
This commit is contained in:
@ -0,0 +1,72 @@
|
||||
#pragma once
|
||||
|
||||
#include <esim/common/types.hpp>
|
||||
#include <deque>
|
||||
#include <ze/common/time_conversions.hpp>
|
||||
|
||||
namespace event_camera_simulator {
|
||||
|
||||
class ImageBuffer
|
||||
{
|
||||
public:
|
||||
ZE_POINTER_TYPEDEFS(ImageBuffer);
|
||||
|
||||
struct ImageData
|
||||
{
|
||||
ImageData(Image img, Time stamp, Duration exposure_time)
|
||||
: image(img),
|
||||
stamp(stamp),
|
||||
exposure_time(exposure_time) {}
|
||||
|
||||
Image image;
|
||||
Time stamp;
|
||||
Duration exposure_time; // timestamp since last image (0 if this is the first image)
|
||||
};
|
||||
|
||||
using ExposureImage = std::pair<Duration, Image>;
|
||||
|
||||
// Rolling image buffer of mazimum size 'buffer_size_ns'.
|
||||
ImageBuffer(Duration buffer_size_ns)
|
||||
: buffer_size_ns_(buffer_size_ns) {}
|
||||
|
||||
void addImage(Time t, const Image& img);
|
||||
|
||||
std::deque<ImageData> getRawBuffer() const { return data_; }
|
||||
|
||||
size_t size() const { return data_.size(); }
|
||||
|
||||
Duration getExposureTime() const { return buffer_size_ns_; }
|
||||
|
||||
private:
|
||||
Duration buffer_size_ns_;
|
||||
std::deque<ImageData> data_;
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
* The CameraSimulator takes as input a sequence of stamped images,
|
||||
* assumed to be sampled at a "sufficiently high" framerate and with
|
||||
* floating-point precision, and treats each image as a measure of
|
||||
* irradiance.
|
||||
* From this, it simulates a real camera, including motion blur.
|
||||
*
|
||||
* @TODO: simulate a non-linear camera response curve, shot noise, etc.
|
||||
*/
|
||||
class CameraSimulator
|
||||
{
|
||||
public:
|
||||
CameraSimulator(double exposure_time_ms)
|
||||
: exposure_time_(ze::secToNanosec(exposure_time_ms / 1000.0))
|
||||
{
|
||||
buffer_.reset(new ImageBuffer(exposure_time_));
|
||||
}
|
||||
|
||||
bool imageCallback(const Image& img, Time time,
|
||||
const ImagePtr &camera_image);
|
||||
|
||||
private:
|
||||
ImageBuffer::Ptr buffer_;
|
||||
const Duration exposure_time_;
|
||||
};
|
||||
|
||||
} // namespace event_camera_simulator
|
@ -0,0 +1,54 @@
|
||||
#pragma once
|
||||
|
||||
#include <esim/common/types.hpp>
|
||||
|
||||
namespace event_camera_simulator {
|
||||
|
||||
/*
|
||||
* The EventSimulator takes as input a sequence of stamped images,
|
||||
* assumed to be sampled at a "sufficiently high" framerate,
|
||||
* and simulates the principle of operation of an idea event camera
|
||||
* with a constant contrast threshold C.
|
||||
* Pixel-wise intensity values are linearly interpolated in time.
|
||||
*
|
||||
* The pixel-wise voltages are reset with the values from the first image
|
||||
* which is passed to the simulator.
|
||||
*/
|
||||
class EventSimulator
|
||||
{
|
||||
public:
|
||||
|
||||
struct Config
|
||||
{
|
||||
double Cp;
|
||||
double Cm;
|
||||
double sigma_Cp;
|
||||
double sigma_Cm;
|
||||
Duration refractory_period_ns;
|
||||
bool use_log_image;
|
||||
double log_eps;
|
||||
};
|
||||
|
||||
using TimestampImage = cv::Mat_<ze::real_t>;
|
||||
|
||||
EventSimulator(const Config& config)
|
||||
: config_(config),
|
||||
is_initialized_(false),
|
||||
current_time_(0)
|
||||
{}
|
||||
|
||||
void init(const Image& img, Time time);
|
||||
Events imageCallback(const Image& img, Time time);
|
||||
|
||||
private:
|
||||
bool is_initialized_;
|
||||
Time current_time_;
|
||||
Image ref_values_;
|
||||
Image last_img_;
|
||||
TimestampImage last_event_timestamp_;
|
||||
cv::Size size_;
|
||||
|
||||
Config config_;
|
||||
};
|
||||
|
||||
} // namespace event_camera_simulator
|
59
event_camera_simulator/esim/include/esim/esim/simulator.hpp
Normal file
59
event_camera_simulator/esim/include/esim/esim/simulator.hpp
Normal file
@ -0,0 +1,59 @@
|
||||
#pragma once
|
||||
|
||||
#include <esim/esim/event_simulator.hpp>
|
||||
#include <esim/esim/camera_simulator.hpp>
|
||||
#include <esim/visualization/publisher_interface.hpp>
|
||||
|
||||
namespace event_camera_simulator {
|
||||
|
||||
/* The Simulator forwards the simulated images / depth maps
|
||||
* from the data provider to multiple, specialized camera simulators, such as:
|
||||
* (i) event camera simulators that simulate events based on sequences of images
|
||||
* (ii) camera simulators that simulate real cameras
|
||||
* (including motion blur, camera response function, noise, etc.)
|
||||
*
|
||||
* The Simulator then forwards the simulated data to one or more publishers.
|
||||
*/
|
||||
class Simulator
|
||||
{
|
||||
public:
|
||||
Simulator(size_t num_cameras,
|
||||
const EventSimulator::Config& event_sim_config,
|
||||
double exposure_time_ms)
|
||||
: num_cameras_(num_cameras),
|
||||
exposure_time_(ze::millisecToNanosec(exposure_time_ms))
|
||||
{
|
||||
for(size_t i=0; i<num_cameras_; ++i)
|
||||
{
|
||||
event_simulators_.push_back(EventSimulator(event_sim_config));
|
||||
camera_simulators_.push_back(CameraSimulator(exposure_time_ms));
|
||||
}
|
||||
}
|
||||
|
||||
~Simulator();
|
||||
|
||||
void addPublisher(const Publisher::Ptr& publisher)
|
||||
{
|
||||
CHECK(publisher);
|
||||
publishers_.push_back(std::move(publisher));
|
||||
}
|
||||
|
||||
void dataProviderCallback(const SimulatorData& sim_data);
|
||||
|
||||
void publishData(const SimulatorData &sim_data,
|
||||
const EventsVector &events,
|
||||
const ImagePtrVector &camera_images);
|
||||
|
||||
private:
|
||||
size_t num_cameras_;
|
||||
std::vector<EventSimulator> event_simulators_;
|
||||
|
||||
std::vector<CameraSimulator> camera_simulators_;
|
||||
Duration exposure_time_;
|
||||
|
||||
std::vector<Publisher::Ptr> publishers_;
|
||||
|
||||
ImagePtrVector corrupted_camera_images_;
|
||||
};
|
||||
|
||||
} // namespace event_camera_simulator
|
Reference in New Issue
Block a user