Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Modify for event_integration #2

Draft
wants to merge 1 commit into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions davis_ros_driver/include/davis_ros_driver/driver.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
// This file is part of DVS-ROS - the RPG DVS ROS Package
// modified to publish events integrated into event frames
// first two channels representing positive and negative, third channel is zero

#pragma once

Expand All @@ -11,8 +13,6 @@
#include <boost/date_time/posix_time/posix_time.hpp>

// messages
#include <dvs_msgs/Event.h>
#include <dvs_msgs/EventArray.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Time.h>
#include <sensor_msgs/Imu.h>
Expand Down Expand Up @@ -50,7 +50,7 @@ class DavisRosDriver {
const uint32_t current_exposure) const;

ros::NodeHandle nh_;
ros::Publisher event_array_pub_;
ros::Publisher event_frame_pub_;
ros::Publisher camera_info_pub_;
ros::Publisher imu_pub_;
ros::Publisher image_pub_;
Expand Down
54 changes: 24 additions & 30 deletions davis_ros_driver/src/driver.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
// This file is part of DVS-ROS - the RPG DVS ROS Package
// modified to publish events integrated into event frames
// first two channels representing positive and negative, third channel is zero

#include "davis_ros_driver/driver.h"
#include "davis_ros_driver/driver_utils.h"
Expand Down Expand Up @@ -51,7 +53,7 @@ DavisRosDriver::DavisRosDriver(ros::NodeHandle & nh, ros::NodeHandle nh_private)
if (ns == "/")
ns = "/dvs";

event_array_pub_ = nh_.advertise<dvs_msgs::EventArray>(ns + "/events", 10);
event_frame_pub_ = nh_.advertise<sensor_msgs::Image>(ns + "/event_frame", 1);
camera_info_pub_ = nh_.advertise<sensor_msgs::CameraInfo>(ns + "/camera_info", 1);
imu_pub_ = nh_.advertise<sensor_msgs::Imu>(ns + "/imu", 10);
image_pub_ = nh_.advertise<sensor_msgs::Image>(ns + "/image_raw", 1);
Expand Down Expand Up @@ -635,7 +637,13 @@ void DavisRosDriver::readout()

boost::posix_time::ptime next_send_time = boost::posix_time::microsec_clock::local_time();

dvs_msgs::EventArrayPtr event_array_msg;
sensor_msgs::Image event_frame_msg;
event_frame_msg.encoding = "rgb8";
event_frame_msg.width = davis_info_.dvsSizeX;
event_frame_msg.height = davis_info_.dvsSizeY;
event_frame_msg.step = event_frame_msg.width * 3;
event_frame_msg.data.resize(event_frame_msg.height * event_frame_msg.step);
std::fill(event_frame_msg.data.begin(), event_frame_msg.data.end(), 0);

while (running_)
{
Expand All @@ -662,12 +670,6 @@ void DavisRosDriver::readout()
// Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet.
if (type == POLARITY_EVENT)
{
if (!event_array_msg)
{
event_array_msg = dvs_msgs::EventArrayPtr(new dvs_msgs::EventArray());
event_array_msg->height = davis_info_.dvsSizeY;
event_array_msg->width = davis_info_.dvsSizeX;
}

caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader;

Expand All @@ -677,39 +679,31 @@ void DavisRosDriver::readout()
// Get full timestamp and addresses of first event.
caerPolarityEvent event = caerPolarityEventPacketGetEvent(polarity, j);

dvs_msgs::Event e;
e.x = caerPolarityEventGetX(event);
e.y = caerPolarityEventGetY(event);
e.ts = reset_time_
+ ros::Duration().fromNSec(caerPolarityEventGetTimestamp64(event, polarity) * 1000);
e.polarity = caerPolarityEventGetPolarity(event);
int e_x = caerPolarityEventGetX(event);
int e_y = caerPolarityEventGetY(event);
bool e_polarity = caerPolarityEventGetPolarity(event);
int pos = e_y * event_frame_msg.step + e_x * 3 + e_polarity;
Comment on lines +682 to +685
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe move the variable declarations outside of the loop to the beginning of the method? Not sure if it will make a big difference as the compiler should be smart enough to optimize.


if(j == 0)
{
event_array_msg->header.stamp = e.ts;
}
if (event_frame_msg.data[pos] < 255) // prevent overflow
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should there be an else statement with some warning in case of Overflow happening.

event_frame_msg.data[pos]++; // feed this into model
// event_frame_msg.data[pos] = 255 // use this for display purpose (visualize)
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@aamini use this line if you want to visualize the event input at the same time. This doesn't influence the event+RGB model, but it may mess up the old event model that takes in normalized event_frames rather than one-hot event_frames.


event_array_msg->events.push_back(e);
if (j == 0)
event_frame_msg.header.stamp = reset_time_
+ ros::Duration().fromNSec(caerPolarityEventGetTimestamp64(event, polarity) * 1000);
}

// throttle event messages
// throttle event messages NOTE: WE DON'T CARE ABOUT max_event
if (boost::posix_time::microsec_clock::local_time() > next_send_time ||
current_config_.streaming_rate == 0 ||
(current_config_.max_events != 0 && event_array_msg->events.size() > current_config_.max_events)
)
current_config_.streaming_rate == 0)
{
event_array_pub_.publish(event_array_msg);
event_frame_pub_.publish(event_frame_msg);
std::fill(event_frame_msg.data.begin(), event_frame_msg.data.end(), 0);

if (current_config_.streaming_rate > 0)
{
next_send_time += delta_;
}
if (current_config_.max_events != 0 && event_array_msg->events.size() > current_config_.max_events)
{
next_send_time = boost::posix_time::microsec_clock::local_time() + delta_;
}

event_array_msg.reset();
}

if (camera_info_manager_->isCalibrated())
Expand Down