Skip to content

Commit

Permalink
removed runtime analysis
Browse files Browse the repository at this point in the history
  • Loading branch information
Tim Lakemann committed Feb 1, 2024
1 parent f181d3f commit 72c55a4
Showing 1 changed file with 1 addition and 63 deletions.
64 changes: 1 addition & 63 deletions src/blink_processor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,6 @@
#include <fstream>


#include <chrono>
using namespace std::chrono;

namespace uvdar{

/**
Expand Down Expand Up @@ -149,12 +146,6 @@ namespace uvdar{
std::vector<ros::Publisher> pub_AMI_all_seq_info;
std::vector<ros::Publisher> pub_estimated_framerate_;

std::vector<ros::Publisher> pub_AMI_fill_;
std::vector<ros::Publisher> pub_AMI_result_;

std::vector<ros::Publisher> pub_4dht_fill_;
std::vector<ros::Publisher> pub_4dht_result_;

using points_seen_callback_t = boost::function<void (const uvdar_core::ImagePointsWithFloatStampedConstPtr&)>;
std::vector<points_seen_callback_t> cals_points_seen_;
std::vector<points_seen_callback_t> cals_sun_points_;
Expand Down Expand Up @@ -197,10 +188,6 @@ namespace uvdar{
std::vector<std::string> _ami_logging_topics_;
std::vector<std::string> _ami_all_seq_info_topics;

std::vector<std::string> _runtime_AMI_fill_;
std::vector<std::string> _runtime_AMI_result_;
std::vector<std::string> _runtime_4dht_fill_;
std::vector<std::string> _runtime_4dht_result_;

bool _manchester_code_;
bool _use_4DHT_;
Expand Down Expand Up @@ -317,14 +304,6 @@ namespace uvdar{
nh_.param("ami_logging_topics", _ami_logging_topics_, _ami_logging_topics_);
nh_.param("ami_all_seq_info_topics", _ami_all_seq_info_topics, _ami_all_seq_info_topics);

nh_.param("runtime_AMI_fill", _runtime_AMI_fill_, _runtime_AMI_fill_);
nh_.param("runtime_AMI_results", _runtime_AMI_result_, _runtime_AMI_result_);

nh_.param("runtime_4dht_fill", _runtime_4dht_fill_, _runtime_4dht_fill_);
nh_.param("runtime_4dht_results", _runtime_4dht_result_, _runtime_4dht_result_);



param_loader.loadParam("sequence_file", _sequence_file, std::string());
param_loader.loadParam("manchester_code", _manchester_code_, bool(false));
param_loader.loadParam("use_4DHT", _use_4DHT_, bool(false));
Expand Down Expand Up @@ -517,14 +496,6 @@ namespace uvdar{
if(!_use_4DHT_){
pub_ami_logging_.push_back(nh_.advertise<uvdar_core::AMIDataForLogging>(_ami_logging_topics_[i], 1));
pub_AMI_all_seq_info.push_back(nh_.advertise<uvdar_core::AMIAllSequences>(_ami_all_seq_info_topics[i], 1));

pub_AMI_fill_.push_back(nh_.advertise<std_msgs::Float32>(_runtime_AMI_fill_[i], 1));
pub_AMI_result_.push_back(nh_.advertise<std_msgs::Float32>(_runtime_AMI_result_[i], 1));

}else{
pub_4dht_fill_.push_back(nh_.advertise<std_msgs::Float32>(_runtime_4dht_fill_[i], 1));
pub_4dht_result_.push_back(nh_.advertise<std_msgs::Float32>(_runtime_4dht_result_[i], 1));

}
}
}
Expand Down Expand Up @@ -612,30 +583,14 @@ namespace uvdar{
}

if(!_use_4DHT_){
auto start = high_resolution_clock::now();
ami_[img_index]->processBuffer(pts_msg);
auto stop = high_resolution_clock::now();
if(_pub_tracking_stats_){
auto duration = duration_cast<microseconds>(stop - start);
std_msgs::Float32 msg_duration;
msg_duration.data = duration.count();
pub_AMI_fill_[img_index].publish(msg_duration);
}

}else{
std::vector<cv::Point2i> points;
for (auto& point : pts_msg->points) {
points.push_back(cv::Point2d(point.x, point.y));
}
auto start = high_resolution_clock::now();
ht4dbt_trackers_[img_index]->insertFrame(points);
auto stop = high_resolution_clock::now();
if(_pub_tracking_stats_){
auto duration = duration_cast<microseconds>(stop - start);
std_msgs::Float32 msg_duration;
msg_duration.data = duration.count();
pub_4dht_fill_[img_index].publish(msg_duration);
}
}

if ((!_use_camera_for_visualization_) || ((!_gui_) && (!_publish_visualization_))){
Expand All @@ -660,15 +615,7 @@ namespace uvdar{
ros::Time local_last_sample_time = blink_data_[img_index].last_sample_time;
{
std::scoped_lock lock(*(blink_data_[img_index].mutex_retrieved_blinkers));
auto start = high_resolution_clock::now();
blink_data_[img_index].retrieved_blinkers = ami_[img_index]->getResults();
auto stop = high_resolution_clock::now();
auto duration = duration_cast<microseconds>(stop - start);
std_msgs::Float32 msg_duration;
msg_duration.data = duration.count();
if(_pub_tracking_stats_){
pub_AMI_result_[img_index].publish(msg_duration);
}

int valid_signal_cnt = 0 , invalid_signal_cnt = 0;
for (auto& signal : blink_data_[img_index].retrieved_blinkers) {
Expand Down Expand Up @@ -804,18 +751,9 @@ namespace uvdar{
{

std::scoped_lock lock(*(blink_data_[image_index].mutex_retrieved_blinkers));


auto start = high_resolution_clock::now();
blink_data_[image_index].retrieved_blinkers_4DHT = ht4dbt_trackers_[image_index]->getResults();
blink_data_[image_index].pitch_4DHT = ht4dbt_trackers_[image_index]->getPitch();
blink_data_[image_index].yaw_4DHT = ht4dbt_trackers_[image_index]->getYaw(); auto stop = high_resolution_clock::now();
auto duration = duration_cast<microseconds>(stop - start);
std_msgs::Float32 msg_duration;
msg_duration.data = duration.count();
pub_4dht_result_[image_index].publish(msg_duration);


blink_data_[image_index].yaw_4DHT = ht4dbt_trackers_[image_index]->getYaw();

}

Expand Down

0 comments on commit 72c55a4

Please sign in to comment.