mirror of
https://github.com/karma-riuk/hdr_esim.git
synced 2025-07-02 08:58:14 +02:00
Added the possibility to get the hdr rgb images from a data provider.
For now only made it work with 'from_folder' and 'opengl_renderer'
This commit is contained in:
@ -11,12 +11,16 @@ namespace event_camera_simulator {
|
||||
ZE_POINTER_TYPEDEFS(ImageBuffer);
|
||||
|
||||
struct ImageData {
|
||||
ImageData(Image img, Time stamp, Duration exposure_time)
|
||||
ImageData(
|
||||
Image img, ImageRGB img_rgb, Time stamp, Duration exposure_time
|
||||
)
|
||||
: image(img),
|
||||
image_rgb(img_rgb),
|
||||
stamp(stamp),
|
||||
exposure_time(exposure_time) {}
|
||||
|
||||
Image image;
|
||||
ImageRGB image_rgb;
|
||||
Time stamp;
|
||||
Duration exposure_time; // timestamp since last image (0 if this is
|
||||
// the first image)
|
||||
@ -27,7 +31,7 @@ namespace event_camera_simulator {
|
||||
// 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);
|
||||
void addImage(Time t, const Image& img, const ImageRGB& img_rgb);
|
||||
|
||||
std::deque<ImageData> getRawBuffer() const {
|
||||
return data_;
|
||||
@ -63,7 +67,10 @@ namespace event_camera_simulator {
|
||||
}
|
||||
|
||||
bool imageCallback(
|
||||
const Image& img, Time time, const ImagePtr& camera_image
|
||||
const Image& img,
|
||||
const ImageRGB& img_rgb,
|
||||
Time time,
|
||||
const ImagePtr& camera_image
|
||||
);
|
||||
|
||||
private:
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include <esim/esim/camera_simulator.hpp>
|
||||
#include <fstream>
|
||||
#include <iomanip>
|
||||
#include <iostream>
|
||||
#include <ostream>
|
||||
#include <ze/common/file_utils.hpp>
|
||||
|
||||
@ -12,7 +13,8 @@ static std::ofstream exposures_file_;
|
||||
|
||||
namespace event_camera_simulator {
|
||||
|
||||
void ImageBuffer::addImage(Time t, const Image& img) {
|
||||
void
|
||||
ImageBuffer::addImage(Time t, const Image& img, const ImageRGB& img_rgb) {
|
||||
if (!data_.empty()) {
|
||||
// Check that the image timestamps are monotonically increasing
|
||||
CHECK_GT(t, data_.back().stamp);
|
||||
@ -21,7 +23,9 @@ namespace event_camera_simulator {
|
||||
Duration exposure_time = data_.empty() ? 0 : t - data_.back().stamp;
|
||||
VLOG(2) << "Adding image to buffer with stamp: " << t
|
||||
<< " and exposure time " << exposure_time;
|
||||
data_.push_back(ImageData(img.clone(), t, exposure_time));
|
||||
data_.push_back(
|
||||
ImageData(img.clone(), img_rgb.clone(), t, exposure_time)
|
||||
);
|
||||
|
||||
// Remove all the images with timestamp older than t - buffer_size_ns_
|
||||
auto first_valid_element = std::lower_bound(
|
||||
@ -40,12 +44,16 @@ namespace event_camera_simulator {
|
||||
}
|
||||
|
||||
bool CameraSimulator::imageCallback(
|
||||
const Image& img, Time time, const ImagePtr& camera_image
|
||||
const Image& img,
|
||||
const ImageRGB& img_rgb,
|
||||
Time time,
|
||||
const ImagePtr& camera_image
|
||||
) {
|
||||
CHECK(camera_image);
|
||||
CHECK_EQ(camera_image->size(), img.size());
|
||||
CHECK_EQ(img_rgb.size(), img.size());
|
||||
|
||||
buffer_->addImage(time, img);
|
||||
buffer_->addImage(time, img, img_rgb);
|
||||
|
||||
static const Time initial_time = time;
|
||||
if (time - initial_time < exposure_time_) {
|
||||
@ -55,10 +63,15 @@ namespace event_camera_simulator {
|
||||
return false;
|
||||
}
|
||||
|
||||
ImageRGB rgb(img.rows, img.cols, CV_32FC3);
|
||||
rgb.setTo(0.);
|
||||
|
||||
// average all the images in the buffer to simulate motion blur
|
||||
camera_image->setTo(0);
|
||||
ze::real_t denom = 0.;
|
||||
for (const ImageBuffer::ImageData& img : buffer_->getRawBuffer()) {
|
||||
rgb +=
|
||||
ze::nanosecToMillisecTrunc(img.exposure_time) * img.image_rgb;
|
||||
*camera_image +=
|
||||
ze::nanosecToMillisecTrunc(img.exposure_time) * img.image;
|
||||
denom += ze::nanosecToMillisecTrunc(img.exposure_time);
|
||||
@ -70,7 +83,7 @@ namespace event_camera_simulator {
|
||||
ss << hdr_output_folder << "/frames/frame_" << std::setfill('0')
|
||||
<< std::setw(5) << frame_number++ << ".exr";
|
||||
std::string frame_path = ss.str();
|
||||
cv::imwrite(frame_path, *camera_image);
|
||||
cv::imwrite(frame_path, rgb);
|
||||
|
||||
// ze::openOutputFileStream(
|
||||
// ze::joinPath(output_folder, "exposures.csv"),
|
||||
|
@ -46,6 +46,7 @@ namespace event_camera_simulator {
|
||||
camera_simulator_success =
|
||||
camera_simulators_[i].imageCallback(
|
||||
*sim_data.images[i],
|
||||
*sim_data.images_rgb[i],
|
||||
time,
|
||||
corrupted_camera_images_[i]
|
||||
);
|
||||
|
Reference in New Issue
Block a user