Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
W
wolf_ros_node
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Deploy
Releases
Model registry
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
mobile_robotics
wolf_projects
wolf_ros
wolf_ros_node
Commits
94744b5a
Commit
94744b5a
authored
4 years ago
by
Joan Vallvé Navarro
Browse files
Options
Downloads
Patches
Plain Diff
working with corresponding branch in core
parent
14f594e6
No related branches found
No related tags found
1 merge request
!5
Draft: Resolve "Single thread + profiling"
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/node.cpp
+37
-28
37 additions, 28 deletions
src/node.cpp
with
37 additions
and
28 deletions
src/node.cpp
+
37
−
28
View file @
94744b5a
...
@@ -241,8 +241,8 @@ int main(int argc, char **argv)
...
@@ -241,8 +241,8 @@ int main(int argc, char **argv)
pthread_setschedparam(solver_thread.native_handle(), SCHED_FIFO, &Priority_Param);*/
pthread_setschedparam(solver_thread.native_handle(), SCHED_FIFO, &Priority_Param);*/
// Profiling
// Profiling
double
duration_viz
(
0
),
duration_solver
(
0
);
std
::
chrono
::
microseconds
duration_viz
(
0
);
unsigned
int
n_viz
(
0
)
,
n_solver
(
0
)
;
unsigned
int
n_viz
(
0
);
while
(
ros
::
ok
())
while
(
ros
::
ok
())
{
{
...
@@ -282,41 +282,50 @@ int main(int argc, char **argv)
...
@@ -282,41 +282,50 @@ int main(int argc, char **argv)
loopRate
.
sleep
();
loopRate
.
sleep
();
}
}
WOLF_DEBUG
(
"Node is shutting down outside loop... waiting for the thread to stop..."
);
WOLF_DEBUG
(
"Node is shutting down outside loop... waiting for the thread to stop..."
);
solver_thread
.
join
();
//
solver_thread.join();
WOLF_DEBUG
(
"thread stopped."
);
WOLF_DEBUG
(
"thread stopped."
);
// Profiling
// Profiling
ofstream
profiling_file
;
std
::
stringstream
profiling_str
;
profiling_file
.
open
(
"~/wolf_profiling.txt"
);
profiling_str
<<
"========== WOLF PROFILING ==========
\n
"
;
profiling_file
<<
"WOLF PROFILING:
\n
"
;
profiling_file
<<
"
\n\n
SOLVER:"
profiling_str
<<
"
\n
SOLVER:"
<<
"
\n\t
total time:"
<<
wolf_node
.
solver_
.
duration_manager_
+
wolf_node
.
solver_
.
duration_solver_
<<
" s"
<<
"
\n\t
total time: "
<<
1e-9
*
(
wolf_node
.
solver_
->
duration_manager_
+
wolf_node
.
solver_
->
duration_solver_
).
count
()
<<
" s"
<<
"
\n\t
manager time:"
<<
wolf_node
.
solver_
.
duration_manager_
<<
" s"
<<
"
\n\t
manager time: "
<<
1e-9
*
wolf_node
.
solver_
->
duration_manager_
.
count
()
<<
" s"
<<
"
\n\t
solver time:"
<<
wolf_node
.
solver_
.
duration_solver_
<<
" s"
<<
"
\n\t
solver time: "
<<
1e-9
*
wolf_node
.
solver_
->
duration_solver_
.
count
()
<<
" s"
<<
"
\n\t
executions:"
<<
wolf_node
.
solver_
.
n_solve_
<<
"
\n\t
executions: "
<<
wolf_node
.
solver_
->
n_solve_
<<
"
\n\t
average time:"
<<
(
wolf_node
.
solver_
.
duration_manager_
+
wolf_node
.
solver_
.
duration_solver_
)
/
wolf_node
.
solver_
.
n_solve_
<<
" s"
<<
"
\n\t
average time: "
<<
1e-9
*
(
wolf_node
.
solver_
->
duration_manager_
+
wolf_node
.
solver_
->
duration_solver_
).
count
()
/
wolf_node
.
solver_
->
n_solve_
<<
" s"
<<
"
\n\t
average manager time:"
<<
wolf_node
.
solver_
.
duration_manager_
/
wolf_node
.
solver_
.
n_solve_
<<
" s"
<<
"
\n\t
average manager time: "
<<
1e-9
*
wolf_node
.
solver_
->
duration_manager_
.
count
()
/
wolf_node
.
solver_
->
n_solve_
<<
" s"
<<
"
\n\t
average solver time:"
<<
wolf_node
.
solver_
.
duration_solver_
/
wolf_node
.
solver_
.
n_solve_
<<
" s"
<<
std
::
endl
;
<<
"
\n\t
average solver time: "
<<
1e-9
*
wolf_node
.
solver_
->
duration_solver_
.
count
()
/
wolf_node
.
solver_
->
n_solve_
<<
" s"
<<
std
::
endl
;
profiling_file
<<
"
\n\n
VISUALIZATION:"
<<
"
\n\t
total time:"
<<
duration_viz
<<
" s"
profiling_str
<<
"
\n\n
VISUALIZATION:"
<<
"
\n\t
executions:"
<<
n_viz
<<
"
\n\t
total time: "
<<
1e-9
*
duration_viz
.
count
()
<<
" s"
<<
"
\n\t
average time:"
<<
duration_viz
/
n_viz
<<
std
::
endl
;
<<
"
\n\t
executions: "
<<
n_viz
<<
"
\n\t
average time: "
<<
1e-9
*
duration_viz
.
count
()
/
n_viz
<<
std
::
endl
;
for
(
auto
sensor
:
wolf_node
.
problem_ptr_
->
getHardware
()
->
getSensorList
())
for
(
auto
sensor
:
wolf_node
.
problem_ptr_
->
getHardware
()
->
getSensorList
())
for
(
auto
proc
:
sensor
->
getProcessorList
())
for
(
auto
proc
:
sensor
->
getProcessorList
())
{
{
profiling_file
<<
"
\n\n
PROCESSOR "
<<
proc
->
getName
()
<<
":"
profiling_str
<<
"
\n\n
PROCESSOR "
<<
proc
->
getName
()
<<
":"
<<
"
\n\t
total time:"
<<
wolf_node
.
solver_
.
duration_manager_
+
wolf_node
.
solver_
.
duration_solver_
<<
" s"
<<
"
\n\t
total time: "
<<
1e-9
*
(
proc
->
duration_capture_
+
proc
->
duration_kf_
).
count
()
<<
" s"
<<
"
\n\t
proc. captures time:"
<<
wolf_node
.
solver_
.
duration_manager_
<<
" s"
<<
"
\n\t
Processing captures:"
<<
"
\n\t
proc. frames time:"
<<
wolf_node
.
solver_
.
duration_solver_
<<
" s"
<<
"
\n\t\t
total time: "
<<
1e-9
*
proc
->
duration_capture_
.
count
()
<<
" s"
<<
"
\n\t
executions:"
<<
wolf_node
.
solver_
.
n_solve_
<<
"
\n\t\t
captures processed: "
<<
proc
->
n_capture_callback_
<<
"
\n\t
average time:"
<<
(
wolf_node
.
solver_
.
duration_manager_
+
wolf_node
.
solver_
.
duration_solver_
)
/
wolf_node
.
solver_
.
n_solve_
<<
" s"
<<
"
\n\t\t
average time: "
<<
1e-9
*
proc
->
duration_capture_
.
count
()
/
proc
->
n_capture_callback_
<<
" s"
<<
"
\n\t
average proc. captures time:"
<<
wolf_node
.
solver_
.
duration_manager_
/
wolf_node
.
solver_
.
n_solve_
<<
" s"
<<
"
\n\t
Processing keyframes:"
<<
"
\n\t
average proc. frames time:"
<<
wolf_node
.
solver_
.
duration_solver_
/
wolf_node
.
solver_
.
n_solve_
<<
" s"
<<
std
::
endl
;
<<
"
\n\t\t
total time: "
<<
1e-9
*
proc
->
duration_kf_
.
count
()
<<
" s"
<<
"
\n\t\t
kf processed: "
<<
proc
->
n_kf_callback_
<<
"
\n\t\t
average time: "
<<
1e-9
*
proc
->
duration_kf_
.
count
()
/
proc
->
n_kf_callback_
<<
" s"
<<
std
::
endl
;
}
}
std
::
cout
<<
profiling_str
.
str
();
ofstream
profiling_file
;
profiling_file
.
open
(
std
::
string
(
std
::
getenv
(
"HOME"
))
+
"/wolf_profiling.txt"
);
if
(
not
profiling_file
.
is_open
())
ROS_ERROR
(
"Error in opening file to store profiling!"
);
profiling_file
<<
profiling_str
.
str
();
profiling_file
.
close
();
profiling_file
.
close
();
return
0
;
// file.close();
return
0
;
return
0
;
}
}
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment