Skip to content

Commit

Permalink
initial commit
Browse files Browse the repository at this point in the history
  • Loading branch information
supitalp committed Oct 29, 2018
0 parents commit a8c2f0c
Show file tree
Hide file tree
Showing 208 changed files with 554,184 additions and 0 deletions.
19 changes: 19 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
## Features

- Accurate event simulation, guaranteed by the tight integration between the rendering engine and the event simulator
- IMU simulation
- Support for multi-camera systems
- Ground truth camera poses, IMU biases, angular/linear velocities, depth maps, and optic flow maps
- Support for camera distortion
- Different C+/C- contrast thresholds
- Basic noise simulation for event cameras (based on additive Gaussian noise on the contrast threshold)
- Motion blur simulation
- Publish to ROS and/or save data to rosbag

## Install

Installation instructions can be found in [our wiki](https://github.com/uzh-rpg/rpg_event_camera_simulator/wiki/Installation).

## Run

Specific instructions to run the simulator depending on the chosen rendering engine can be found in [our wiki](https://github.com/uzh-rpg/rpg_event_camera_simulator/wiki).
45 changes: 45 additions & 0 deletions dependencies.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
repositories:
catkin_simple:
type: git
url: [email protected]:catkin/catkin_simple.git
version: master
ze_oss:
type: git
url: [email protected]:uzh-rpg/ze_oss.git
version: master
gflags_catkin:
type: git
url: [email protected]:ethz-asl/gflags_catkin.git
version: master
glog_catkin:
type: git
url: [email protected]:ethz-asl/glog_catkin.git
version: master
eigen_catkin:
type: git
url: [email protected]:ethz-asl/eigen_catkin.git
version: master
eigen_checks:
type: git
url: [email protected]:ethz-asl/eigen_checks.git
version: master
minkindr:
type: git
url: [email protected]:ethz-asl/minkindr.git
version: master
minkindr_ros:
type: git
url: [email protected]:ethz-asl/minkindr_ros.git
version: master
yaml_cpp_catkin:
type: git
url: [email protected]:ethz-asl/yaml_cpp_catkin.git
version: master
rpg_dvs_ros:
type: git
url: [email protected]:uzh-rpg/rpg_dvs_ros.git
version: master
assimp_catkin:
type: git
url: [email protected]:uzh-rpg/assimp_catkin.git
version: master
4 changes: 4 additions & 0 deletions event_camera_simulator/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
*.txt.user
esim_ros/scripts/exp_*
*.swp
*.autosave
30 changes: 30 additions & 0 deletions event_camera_simulator/esim/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
cmake_minimum_required(VERSION 2.8.3)
project(esim)

find_package(catkin_simple REQUIRED)
find_package(OpenCV REQUIRED)
catkin_simple()

set(HEADERS
include/esim/esim/simulator.hpp
include/esim/esim/event_simulator.hpp
include/esim/esim/camera_simulator.hpp
)

set(SOURCES
src/simulator.cpp
src/event_simulator.cpp
src/camera_simulator.cpp
)

cs_add_library(${PROJECT_NAME} ${SOURCES} ${HEADERS})

##########
# GTESTS #
##########

catkin_add_gtest(test_event_simulator test/test_event_simulator.cpp)
target_link_libraries(test_event_simulator ${PROJECT_NAME} ${OpenCV_LIBRARIES})

cs_install()
cs_export()
72 changes: 72 additions & 0 deletions event_camera_simulator/esim/include/esim/esim/camera_simulator.hpp
Original file line number Diff line number Diff line change
@@ -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
54 changes: 54 additions & 0 deletions event_camera_simulator/esim/include/esim/esim/event_simulator.hpp
Original file line number Diff line number Diff line change
@@ -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 changes: 59 additions & 0 deletions event_camera_simulator/esim/include/esim/esim/simulator.hpp
Original file line number Diff line number Diff line change
@@ -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
20 changes: 20 additions & 0 deletions event_camera_simulator/esim/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<package format="2">
<name>esim</name>
<version>0.0.0</version>
<description>Event camera simulator, which can simulate events from a stream of images samplet at high frequency.</description>

<maintainer email="[email protected]">Henri Rebecq</maintainer>

<license>GPLv3</license>

<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend>catkin_simple</buildtool_depend>

<depend>esim_common</depend>
<depend>esim_data_provider</depend>
<depend>esim_visualization</depend>
<depend>gflags_catkin</depend>
<depend>glog_catkin</depend>

</package>
62 changes: 62 additions & 0 deletions event_camera_simulator/esim/src/camera_simulator.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
#include <esim/esim/camera_simulator.hpp>

namespace event_camera_simulator {

void ImageBuffer::addImage(Time t, const Image& img)
{
if(!data_.empty())
{
// Check that the image timestamps are monotonically increasing
CHECK_GT(t, data_.back().stamp);
}

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));

// Remove all the images with timestamp older than t - buffer_size_ns_
auto first_valid_element = std::lower_bound(data_.begin(), data_.end(), t - buffer_size_ns_,
[](ImageData lhs, Time rhs) -> bool { return lhs.stamp < rhs; });

data_.erase(data_.begin(), first_valid_element);
VLOG(3) << "first/last element in buffer: "
<< data_.front().stamp
<< " " << data_.back().stamp;
VLOG(3) << "number of images in the buffer: " << data_.size();

CHECK_LE(data_.back().stamp - data_.front().stamp, buffer_size_ns_);
}


bool CameraSimulator::imageCallback(const Image &img, Time time,
const ImagePtr& camera_image)
{
CHECK(camera_image);
CHECK_EQ(camera_image->size(), img.size());

buffer_->addImage(time, img);

static const Time initial_time = time;
if(time - initial_time < exposure_time_)
{
LOG_FIRST_N(WARNING, 1) << "The images do not cover a time span long enough to simulate the exposure time accurately.";
return false;
}

// 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())
{
*camera_image += ze::nanosecToMillisecTrunc(img.exposure_time) * img.image;
denom += ze::nanosecToMillisecTrunc(img.exposure_time);
}
*camera_image /= denom;
cv::Mat disp;
camera_image->convertTo(disp, CV_8U, 255);

return true;
}

} // namespace event_camera_simulator
Loading

0 comments on commit a8c2f0c

Please sign in to comment.