Skip to content
Snippets Groups Projects
Commit cc4ae0bb authored by Joaquim Casals Buñuel's avatar Joaquim Casals Buñuel
Browse files

Add profiling for keyFrame & capture callbacks

parent f3c3b10e
No related branches found
No related tags found
No related merge requests found
Pipeline #4876 passed
......@@ -76,6 +76,10 @@ IF(NOT BUILD_DOC)
OPTION(BUILD_DOC "Build Documentation" OFF)
ENDIF(NOT BUILD_DOC)
IF(PROFILING)
add_definitions(-DPROFILING)
message("Compiling with profiling options...")
ENDIF(PROFILING)
#############
## Testing ##
#############
......
......@@ -464,7 +464,23 @@ void Problem::keyFrameCallback(FrameBasePtr _keyframe_ptr, ProcessorBasePtr _pro
for (auto sensor : hardware_ptr_->getSensorList())
for (auto processor : sensor->getProcessorList())
if (processor && (processor != _processor_ptr) )
{
#ifdef PROFILING
auto start = std::chrono::high_resolution_clock::now();
#endif
processor->keyFrameCallback(_keyframe_ptr, _time_tolerance);
#ifdef PROFILING
auto stop = std::chrono::high_resolution_clock::now();
auto duration = std::chrono::duration_cast<std::chrono::microseconds>(stop - start);
WOLF_INFO("keyFrameCallback Prc_id: ", processor->id(),
" Prc_type: ", processor->getType(),
" Prc_name: ", processor->getName(),
" keyframe_id: ", _keyframe_ptr->id(),
" keyframe_type: ", _keyframe_ptr->getType(),
" timestamp: ", _keyframe_ptr->getTimeStamp(),
" microseconds: ", duration.count());
#endif
}
}
bool Problem::permitAuxFrame(ProcessorBasePtr _processor_ptr) const
......
......@@ -350,7 +350,22 @@ bool SensorBase::process(const CaptureBasePtr capture_ptr)
for (const auto processor : processor_list_)
{
#ifdef PROFILING
auto start = std::chrono::high_resolution_clock::now();
#endif
processor->captureCallback(capture_ptr);
#ifdef PROFILING
auto stop = std::chrono::high_resolution_clock::now();
auto duration = std::chrono::duration_cast<std::chrono::microseconds>(stop - start);
WOLF_INFO("captureCallback Prc_id: ", processor->id(),
" Prc_type: ", processor->getType(),
" Prc_name: ", processor->getName(),
" Cptr_id: ", capture_ptr->id(),
" Cptr_type: ", capture_ptr->getType(),
" timestamp: ", capture_ptr->getTimeStamp(),
" microseconds: ", duration.count());
#endif
}
return true;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment