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

Support for trail filters #50

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
28 commits
Select commit Hold shift + click to select a range
46fdc7a
Added bias_fo for Gen4 sensor called bias_fo_n.
AndreasAZiegler Nov 9, 2022
eb12479
Added serial and trigger_in_mode parameters.
AndreasAZiegler Nov 9, 2022
aaa899f
Warn that bias_pr is not supported for Gen4.1 and IMX636.
AndreasAZiegler Nov 9, 2022
7390be8
Fixed trigger pins config in nodelet mode.
AndreasAZiegler Nov 9, 2022
2225696
Added launch files for EVK1 and EVK2.
AndreasAZiegler Nov 9, 2022
5966670
Our bias settings:
AndreasAZiegler Nov 9, 2022
bf30a54
Allow to set the name of the node.
AndreasAZiegler Nov 10, 2022
01b37b2
Added sync_mode and name parameter.
AndreasAZiegler Nov 10, 2022
2dc5a4d
Added parameters to better control the node.
AndreasAZiegler Nov 10, 2022
ac91627
Added bias_fo_n
AndreasAZiegler Nov 10, 2022
4833918
Fixed typo.
AndreasAZiegler Nov 10, 2022
2a37cc7
Also start primary node since otherwise hardware sync signal is missing.
AndreasAZiegler Nov 10, 2022
c779836
Merge remote-tracking branch 'az/master'
AndreasAZiegler Nov 11, 2022
646cc51
Merge branch 'master' of github.com:AndreasAZiegler/metavision_ros_dr…
AndreasAZiegler Aug 8, 2024
88d5617
Added functionality th activate trail filters.
AndreasAZiegler Aug 8, 2024
84750ba
Reverted some old, unrelated changes.
AndreasAZiegler Aug 8, 2024
1e87077
Trail filter needs to be activated after the camera is configured.
AndreasAZiegler Aug 12, 2024
8d44769
Some refactoring.
AndreasAZiegler Aug 12, 2024
4035b74
Sync with main repo.
AndreasAZiegler Aug 12, 2024
be2ad3b
Merge branch 'master' of github.com:ros-event-camera/metavision_driver
AndreasAZiegler Aug 12, 2024
a525bb6
Merge branch 'master' into support-trail-filter
AndreasAZiegler Aug 12, 2024
c44e97a
Addressed PR feedback.
AndreasAZiegler Aug 12, 2024
717d865
Adressed PR feedback.
AndreasAZiegler Aug 13, 2024
0553c66
Applied style guide.
AndreasAZiegler Aug 13, 2024
2de480f
Changed log warn to bomb out.
AndreasAZiegler Aug 13, 2024
6a89fba
make BOMB_OUT_CERR available to ROS1
berndpfrommer Aug 13, 2024
97f98b4
add documentation, match trail filter types to SDK
berndpfrommer Aug 13, 2024
8280ece
removed extra newlines
berndpfrommer Aug 13, 2024
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
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -169,6 +169,10 @@ Parameters:
- ``erc_rate``: event rate control rate (Gen4 sensor) events/sec. Default: 100000000.
- ``mipi_frame_period``:: mipi frame period in usec. Only available on some sensors.
Tune this to get faster callback rates from the SDK to the ROS driver. For instance 1008 will give a callback every millisecond. Risk of data corruption when set too low! Default: -1 (not set).
- ``trail_filter``: enable/disable event trail filter. Default: False.
- ``trail_filter_type``: type of trail filter. Allowed values: ``trail``, ``stc_cut_trail``, ``stc_keep_trail``.
Default: ``trail``. See Metavision SDK documentation.
- ``trail_filter_threshold``: Filter threshold, see MetavisionSDK documentation. Default: 5000.
- ``sync_mode``: Used to synchronize the time stamps across multiple
cameras (tested for only 2). The cameras must be connected via a
sync cable, and two separate ROS driver nodes are started, see
Expand Down
15 changes: 8 additions & 7 deletions include/metavision_driver/logging.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,13 +76,6 @@
SS << __VA_ARGS__; \
throw(std::runtime_error(SS.str())); \
}
#define BOMB_OUT_CERR(...) \
{ \
std::cerr << __VA_ARGS__ << std::endl; \
std::stringstream SS; \
SS << __VA_ARGS__; \
throw(std::runtime_error(SS.str())); \
}
#define LOG_INFO_NAMED(...) \
{ \
RCLCPP_INFO_STREAM(rclcpp::get_logger(loggerName_), __VA_ARGS__); \
Expand Down Expand Up @@ -175,4 +168,12 @@

#endif // USING_ROS_1

#define BOMB_OUT_CERR(...) \
{ \
std::cerr << __VA_ARGS__ << std::endl; \
std::stringstream SS; \
SS << __VA_ARGS__; \
throw(std::runtime_error(SS.str())); \
}

#endif // METAVISION_DRIVER__LOGGING_H_
10 changes: 10 additions & 0 deletions include/metavision_driver/metavision_wrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,13 @@ class MetavisionWrapper
size_t maxQueueSize{0};
};

struct TrailFilter
{
bool enabled;
std::string type;
uint32_t threshold;
};

typedef std::map<std::string, std::map<std::string, int>> HardwarePinConfig;

explicit MetavisionWrapper(const std::string & loggerName);
Expand Down Expand Up @@ -112,6 +119,7 @@ class MetavisionWrapper
ercRate_ = rate;
}
void setMIPIFramePeriod(int usec) { mipiFramePeriod_ = usec; }
void setTrailFilter(const std::string & type, const uint32_t threshold, const bool state);

bool triggerActive() const
{
Expand Down Expand Up @@ -139,6 +147,7 @@ class MetavisionWrapper
const std::string & mode_in, const std::string & mode_out, const int period,
const double duty_cycle);
void configureEventRateController(const std::string & mode, const int rate);
void activateTrailFilter();
void configureMIPIFramePeriod(int usec, const std::string & sensorName);
void printStatistics();
// ------------ variables
Expand Down Expand Up @@ -168,6 +177,7 @@ class MetavisionWrapper
HardwarePinConfig hardwarePinConfig_;
std::string ercMode_;
int ercRate_;
TrailFilter trailFilter_;
int mipiFramePeriod_{-1};
std::string loggerName_{"driver"};
std::vector<int> roi_;
Expand Down
3 changes: 3 additions & 0 deletions launch/driver_node.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,9 @@ def launch_setup(context, *args, **kwargs):
"serial": LaunchConfig("serial"),
"erc_mode": "enabled",
"erc_rate": 100000000,
"trail_filter": False,
"trail_filter_type": "stc_trail_cut",
"trail_filter_threshold": 5000,
# 'roi': [0, 0, 100, 100],
# valid: 'external', 'loopback', 'disabled'
"trigger_in_mode": "external",
Expand Down
13 changes: 13 additions & 0 deletions src/driver_ros2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -317,6 +317,19 @@ void DriverROS2::configureWrapper(const std::string & name)
this->get_parameter_or("sync_mode", syncMode, std::string("standalone"));
wrapper_->setSyncMode(syncMode);
LOG_INFO("sync mode: " << syncMode);
bool trailFilter;
this->get_parameter_or("trail_filter", trailFilter, false);
std::string trailFilterType;
this->get_parameter_or("trail_filter_type", trailFilterType, std::string("trail"));
int trailFilterThreshold;
this->get_parameter_or("trail_filter_threshold", trailFilterThreshold, 0);
if (trailFilter) {
LOG_INFO(
"Using tail filter in " << trailFilterType << " mode with threshold "
<< trailFilterThreshold);
wrapper_->setTrailFilter(
trailFilterType, static_cast<uint32_t>(trailFilterThreshold), trailFilter);
}
std::vector<int64_t> roi_long;
this->get_parameter_or("roi", roi_long, std::vector<int64_t>());
std::vector<int> r(roi_long.begin(), roi_long.end());
Expand Down
41 changes: 41 additions & 0 deletions src/metavision_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@

#include "metavision_driver/metavision_wrapper.h"

#include "metavision_driver/logging.h"

#ifdef USING_METAVISION_3
#include <metavision/hal/facilities/i_device_control.h>
#include <metavision/hal/facilities/i_erc.h>
Expand All @@ -23,6 +25,7 @@
#include <metavision/hal/facilities/i_erc_module.h>
#endif

#include <metavision/hal/facilities/i_event_trail_filter_module.h>
#include <metavision/hal/facilities/i_hw_identification.h>
#include <metavision/hal/facilities/i_hw_register.h>
#include <metavision/hal/facilities/i_plugin_software_info.h>
Expand Down Expand Up @@ -62,6 +65,11 @@ static const std::map<std::string, Metavision::I_TriggerIn::Channel> channelMap
static const std::map<std::string, uint32_t> sensorToMIPIAddress = {
{"IMX636", 0xB028}, {"Gen3.1", 0x1508}};

static const std::map<std::string, Metavision::I_EventTrailFilterModule::Type> trailFilterMap = {
{"trail", Metavision::I_EventTrailFilterModule::Type::TRAIL},
{"stc_cut_trail", Metavision::I_EventTrailFilterModule::Type::STC_CUT_TRAIL},
{"stc_keep_trail", Metavision::I_EventTrailFilterModule::Type::STC_KEEP_TRAIL}};

static std::string to_lower(const std::string upper)
{
std::string lower(upper);
Expand Down Expand Up @@ -119,6 +127,14 @@ int MetavisionWrapper::setBias(const std::string & name, int val)
return (now);
}

void MetavisionWrapper::setTrailFilter(
const std::string & type, const uint32_t threshold, const bool state)
{
trailFilter_.enabled = state;
trailFilter_.type = type;
trailFilter_.threshold = threshold;
}

bool MetavisionWrapper::initialize(bool useMultithreading, const std::string & biasFile)
{
biasFile_ = biasFile;
Expand Down Expand Up @@ -428,8 +444,33 @@ void MetavisionWrapper::setDecodingEvents(bool decodeEvents)
}
}

void MetavisionWrapper::activateTrailFilter()
{
Metavision::I_EventTrailFilterModule * i_trail_filter =
cam_.get_device().get_facility<Metavision::I_EventTrailFilterModule>();

const auto it = trailFilterMap.find(trailFilter_.type);
if (it == trailFilterMap.end()) {
BOMB_OUT_CERR("unknown trail filter type " << trailFilter_.type);
}
AndreasAZiegler marked this conversation as resolved.
Show resolved Hide resolved

// Set filter type
if (!i_trail_filter->set_type(it->second)) {
LOG_WARN_NAMED("cannot set type of trail filter!")
}
if (!i_trail_filter->set_threshold(trailFilter_.threshold)) {
LOG_WARN_NAMED("cannot set threshold of trail filter!")
}

i_trail_filter->enable(trailFilter_.enabled);
}

bool MetavisionWrapper::startCamera(CallbackHandler * h)
{
if (trailFilter_.enabled) {
activateTrailFilter();
}

try {
callbackHandler_ = h;
if (useMultithreading_) {
Expand Down
Loading