Skip to content

Commit

Permalink
Auto stash before merge of "master" and "origin/master"
Browse files Browse the repository at this point in the history
  • Loading branch information
Davide committed Dec 19, 2019
1 parent b1d08f4 commit 795ec4f
Show file tree
Hide file tree
Showing 12 changed files with 367 additions and 96 deletions.
100 changes: 100 additions & 0 deletions .clang-format
@@ -0,0 +1,100 @@
---
Language: Cpp
# BasedOnStyle: WebKit
AccessModifierOffset: -4
AlignAfterOpenBracket: Align
AlignConsecutiveAssignments: true
AlignConsecutiveDeclarations: false
AlignEscapedNewlinesLeft: true
AlignOperands: true
AlignTrailingComments: true
AllowAllParametersOfDeclarationOnNextLine: true
AllowShortBlocksOnASingleLine: true
AllowShortCaseLabelsOnASingleLine: false
AllowShortFunctionsOnASingleLine: Empty
AllowShortIfStatementsOnASingleLine: false
AllowShortLoopsOnASingleLine: false
# AlwaysBreakAfterDefinitionReturnType: None
AlwaysBreakAfterReturnType: None
AlwaysBreakBeforeMultilineStrings: false
AlwaysBreakTemplateDeclarations: true
BinPackArguments: true
BinPackParameters: true
BraceWrapping:
AfterClass: false
AfterControlStatement: false
AfterEnum: false
AfterFunction: true
AfterNamespace: false
AfterObjCDeclaration: false
AfterStruct: false
AfterUnion: false
BeforeCatch: false
BeforeElse: false
IndentBraces: false
BreakBeforeBinaryOperators: None
BreakBeforeBraces: Attach
BreakBeforeInheritanceComma: false
BreakBeforeTernaryOperators: false
BreakConstructorInitializers: AfterColon
# BreakAfterJavaFieldAnnotations: false
BreakStringLiterals: true
ColumnLimit: 120
CommentPragmas: '^ IWYU pragma:'
CompactNamespaces: false
ConstructorInitializerAllOnOneLineOrOnePerLine: true
ConstructorInitializerIndentWidth: 4
ContinuationIndentWidth: 4
Cpp11BracedListStyle: true
DerivePointerAlignment: false
DisableFormat: false
ExperimentalAutoDetectBinPacking: false
FixNamespaceComments: true
ForEachMacros: [ foreach, Q_FOREACH, BOOST_FOREACH ]
IncludeCategories:
- Regex: '^"(llvm|llvm-c|clang|clang-c)/'
Priority: 2
- Regex: '^(<|"(gtest|isl|json)/)'
Priority: 3
- Regex: '.*'
Priority: 1
IncludeIsMainRegex: '$'
IndentCaseLabels: false
IndentWidth: 4
IndentWrappedFunctionNames: true
# JavaScriptQuotes: Leave
# JavaScriptWrapImports: true
KeepEmptyLinesAtTheStartOfBlocks: false
MacroBlockBegin: ''
MacroBlockEnd: ''
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
# ObjCBlockIndentWidth: 4
# ObjCSpaceAfterProperty: true
# ObjCSpaceBeforeProtocolList: true
PenaltyBreakBeforeFirstCallParameter: 19
PenaltyBreakComment: 300
PenaltyBreakFirstLessLess: 120
PenaltyBreakString: 1000
PenaltyExcessCharacter: 1000000
PenaltyReturnTypeOnItsOwnLine: 60
PointerAlignment: Right
ReflowComments: true
SortIncludes: false
SortUsingDeclarations: false
SpaceAfterCStyleCast: false
SpaceAfterTemplateKeyword: false
SpaceBeforeAssignmentOperators: true
SpaceBeforeParens: ControlStatements
SpaceInEmptyParentheses: false
SpacesBeforeTrailingComments: 1
SpacesInAngles: false
SpacesInContainerLiterals: false
SpacesInCStyleCastParentheses: false
SpacesInParentheses: false
SpacesInSquareBrackets: false
Standard: Cpp11
TabWidth: 4
UseTab: Never
...

2 changes: 1 addition & 1 deletion prophesee_ros_driver/CMakeLists.txt
Expand Up @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3)
project(prophesee_ros_driver)

## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)
add_compile_options(-std=c++14)


execute_process(COMMAND lsb_release -cs OUTPUT_VARIABLE RELEASE_CODENAME OUTPUT_STRIP_TRAILING_WHITESPACE)
Expand Down
29 changes: 29 additions & 0 deletions prophesee_ros_driver/cfg/gen3_low_sensitive_settings.bias
@@ -0,0 +1,29 @@
% subsystem_ID 2415920387
% system_ID 21
300 % bias_latchout_or_pu % v
100 % bias_reqx_or_pu % v
1200 % bias_req_pux % v
1300 % bias_req_puy % v
500 % bias_del_reqx_or % v
800 % bias_sendreq_pdx % v
500 % bias_sendreq_pdy % v
400 % bias_del_ack_array % v
200 % bias_del_timeout % v
400 % bias_inv % v
1500 % bias_refr % v
500 % bias_clk % v
1800 % bias_hpf % v
430 % bias_tail % i
230 % bias_out % i
370 % bias_hyst % i
1397 % bias_vrefl % v
1700 % bias_vrefh % v
1000 % bias_cas % v
191 % bias_diff_off % v
439 % bias_diff_on % v
300 % bias_diff % v
1720 % bias_fo % v
1500 % bias_pr % v
1500 % bias_bulk % v
1600 % bias_overflow % v
200 % bias_buf % v
29 changes: 29 additions & 0 deletions prophesee_ros_driver/cfg/gen3_lower_bg_noise.bias
@@ -0,0 +1,29 @@
% subsystem_ID 2415920387
% system_ID 21
300 % bias_latchout_or_pu % v
100 % bias_reqx_or_pu % v
1200 % bias_req_pux % v
1300 % bias_req_puy % v
500 % bias_del_reqx_or % v
800 % bias_sendreq_pdx % v
500 % bias_sendreq_pdy % v
400 % bias_del_ack_array % v
200 % bias_del_timeout % v
400 % bias_inv % v
1500 % bias_refr % v
500 % bias_clk % v
1800 % bias_hpf % v
430 % bias_tail % i
230 % bias_out % i
370 % bias_hyst % i
1397 % bias_vrefl % v
1700 % bias_vrefh % v
1000 % bias_cas % v
213 % bias_diff_off % v
411 % bias_diff_on % v
300 % bias_diff % v
1720 % bias_fo % v
1500 % bias_pr % v
1500 % bias_bulk % v
1600 % bias_overflow % v
200 % bias_buf % v
Expand Up @@ -80,7 +80,7 @@ class CDFrameGenerator {
///
/// \return Timestamp in microseconds
inline Prophesee::timestamp ros_timestamp_in_us(const ros::Time &ts) const {
return static_cast<Prophesee::timestamp>(ts.toNSec()/1000.00);
return static_cast<Prophesee::timestamp>(ts.toNSec() / 1000.00);
};

private:
Expand Down
Expand Up @@ -10,6 +10,7 @@
#include <sensor_msgs/CameraInfo.h>

#include <prophesee_driver.h>
#include <prophesee_core/algos/core/activity_noise_filter_algorithm.h>

#include "log_tone_mapper.h"

Expand All @@ -28,7 +29,6 @@ class PropheseeWrapperPublisher {
void startPublishing();

private:

/// \brief Opens the camera
bool openCamera();

Expand Down Expand Up @@ -61,6 +61,16 @@ class PropheseeWrapperPublisher {
/// Used to access data from a camera
Prophesee::Camera camera_;

/// \brief Instance of Events Array
///
/// Accumulated Array of events
std::vector<Prophesee::EventCD> event_buffer_;

/// \brief Frame reconstruction in gray scale
///
/// Gray level fram from tone mapper reconstruction
cv::Mat graylevel_frame_;

/// \brief Instance of LogToneMapper class
///
/// Used to reconstract gray-levels from CD and EM data and apply tone mapping
Expand All @@ -69,14 +79,17 @@ class PropheseeWrapperPublisher {
/// \brief Message for publishing the camera info
sensor_msgs::CameraInfo cam_info_msg_;

/// \brief Pointer for the Activity Filter Instance
std::shared_ptr< Prophesee::ActivityNoiseFilterAlgorithm<> > activity_filter_;

/// \brief Path to the file with the camera settings (biases)
std::string biases_file_;

/// \brief Camera name in string format
std::string camera_name_;

/// \brief Camera string time
ros::Time start_timestamp_;
/// \brief Wall time stamps
ros::Time start_timestamp_, last_timestamp_;

/// \brief Maximum events rate, in kEv/s
int max_event_rate_;
Expand All @@ -90,10 +103,30 @@ class PropheseeWrapperPublisher {
/// \brief If showing gray-level frames
bool publish_graylevels_;

/// \brief If showing IMU events
/// \brief If showing IMU events
bool publish_imu_;

static constexpr double GRAVITY = 9.81; /** Mean gravity value at Earth surface [m/s^2] **/
/// \brief Events rate (configuration)
/// Desirable rate in Hz for the events
double event_streaming_rate_;

/// \brief Actvity Filter Temporal depth (configuration)
/// Desirable Temporal depth in micro seconds
int activity_filter_temporal_depth_;

/// \brief delta_time for packages cd_events
/// Time step for packaging events in an array
ros::Duration event_delta_t_;

/// \brief Event buffer time stamps
ros::Time event_buffer_start_time_, event_buffer_current_time_;

/// \brief Mean gravity value at Earth surface [m/s^2]
static constexpr double GRAVITY = 9.81;

/// \brief delta time of cd events fixed by Prophesee driver
/// The delta time is set to a fixed number of 64 microseconds (1e-06)
static constexpr double EVENT_DEFAULT_DELTA_T = 6.4e-05;
};

#endif /* PROPHESEE_ROS_PUBLISHER_H_ */
Expand Up @@ -45,12 +45,12 @@ class PropheseeWrapperViewer {
/// It gets width and height of the sensor and calls init() function
///
/// @param msg : ROS message with the camera info
void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg);
void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg);

/// \brief Callback triggered when data are received from gray-level frame topic
///
/// @param msg ROS message with teh gray-level frame
void glFrameCallback(const sensor_msgs::ImageConstPtr& msg);
void glFrameCallback(const sensor_msgs::ImageConstPtr &msg);

/// \brief Initializes the frame generators and the displayers
///
Expand All @@ -59,7 +59,7 @@ class PropheseeWrapperViewer {
///
/// It initializes CD frame generator with the sensor's width and height.
/// It also creates the displayers.
bool init(const unsigned int& sensor_width, const unsigned int& sensor_height);
bool init(const unsigned int &sensor_width, const unsigned int &sensor_height);

/// \brief Creates a displayer
///
Expand All @@ -68,8 +68,8 @@ class PropheseeWrapperViewer {
/// @param sensor_height : Height of the window
/// @param shift_x : Position (x shift) of the window
/// @param shift_y : Position (y shift) of the window
void create_window(const std::string &window_name, const unsigned int& sensor_width,
const unsigned int& sensor_height, const int &shift_x=0, const int &shift_y=0);
void create_window(const std::string &window_name, const unsigned int &sensor_width,
const unsigned int &sensor_height, const int &shift_x = 0, const int &shift_y = 0);

/// \brief Node handler - the access point to communication with ROS
ros::NodeHandle nh_;
Expand Down
11 changes: 9 additions & 2 deletions prophesee_ros_driver/launch/prophesee_publisher.launch
Expand Up @@ -7,13 +7,20 @@
<param name="publish_imu" value="true" />

<!-- Path to the file with the camera settings -->
<param name="bias_file" value="" />
<param name="bias_file" value=""/>

<!-- Maximum event rate in kEv/s -->
<!-- Maximum event rate in kEv/s. With 0 does not set any limit-->
<param name="max_event_rate" value="6000" />

<!-- Streaming rate in Hz for the events array. By default is 64 microseconds or max 100 events in array -->
<param name="event_streaming_rate" value="0" />

<!-- Graylevel frame rate in fps -->
<param name="graylevel_frame_rate" value="30" />

<!-- Activity filter temporal depth in microseconds -->
<param name="activity_filter_temporal_depth" value="0" />

</node>

</launch>
23 changes: 9 additions & 14 deletions prophesee_ros_driver/src/cd_frame_generator.cpp
Expand Up @@ -6,20 +6,19 @@

#include "cd_frame_generator.h"

CDFrameGenerator::CDFrameGenerator() {
}
CDFrameGenerator::CDFrameGenerator() {}

CDFrameGenerator::~CDFrameGenerator() {
stop();
}

void CDFrameGenerator::init(long width, long height) {
width_ = width;
height_ = height;
pix_count_ = height_ * width_;
width_ = width;
height_ = height;
pix_count_ = height_ * width_;
ts_history_.resize(pix_count_);

frame_ = cv::Mat(height_, width_, CV_8UC1, cv::Scalar(128));
frame_ = cv::Mat(height_, width_, CV_8UC1, cv::Scalar(128));
frame_to_show_ = cv::Mat(height_, width_, CV_8UC1, cv::Scalar(128));

initialized_ = true;
Expand All @@ -40,9 +39,7 @@ void CDFrameGenerator::add_events(const prophesee_event_msgs::EventArray::ConstP
}

if (should_process) {
{
thread_should_process_ = true;
}
{ thread_should_process_ = true; }
thread_cond_.notify_one();
}

Expand All @@ -56,8 +53,8 @@ void CDFrameGenerator::reset() {
{
std::unique_lock<std::mutex> lock_process(processing_mutex_);
thread_should_process_ = false;
last_ts_ = 0;
last_process_ts_ = 0;
last_ts_ = 0;
last_process_ts_ = 0;

// Clean the queues with events
events_queue_front_.clear();
Expand Down Expand Up @@ -165,9 +162,7 @@ bool CDFrameGenerator::stop() {
return false;
}

{
thread_should_stop_ = true;
}
{ thread_should_stop_ = true; }

thread_cond_.notify_one();
thread_.join();
Expand Down

0 comments on commit 795ec4f

Please sign in to comment.