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

feat(autoware_universe_utils): add TimeKeeper to track function's processing time #7754

Open
wants to merge 8 commits into
base: main
Choose a base branch
from

Conversation

takayuki5168
Copy link
Contributor

@takayuki5168 takayuki5168 commented Jun 30, 2024

Description

Added a class to track the function's processing time.

Terminal (when show_on_terminal is True) or ros2 topic echo /planning/scenario_planning/lane_driving/motion_planning/path_optimizer/debug/processing_time_detail --field data

[component_container_mt-32] ========================================
[component_container_mt-32] onPath (3.763ms)
[component_container_mt-32]     ├── generateOptimizedTrajectory (3.631ms)
[component_container_mt-32]     │   ├── optimizeTrajectory (3.341ms)
[component_container_mt-32]     │   │   └── optimizeTrajectory (3.338ms)
[component_container_mt-32]     │   │       ├── calcReferencePoints (0.951ms)
[component_container_mt-32]     │   │       │   ├── resampleReferencePoints (0.108ms)
[component_container_mt-32]     │   │       │   ├── updateFixedPoint (0.065ms)
[component_container_mt-32]     │   │       │   ├── updateBounds (0.066ms)
[component_container_mt-32]     │   │       │   ├── updateVehicleBounds (0.316ms)
[component_container_mt-32]     │   │       │   └── updateExtraPoints (0.171ms)
[component_container_mt-32]     │   │       ├── calcMatrix (0.049ms)
[component_container_mt-32]     │   │       ├── calcValueMatrix (0.01ms)
[component_container_mt-32]     │   │       ├── calcObjectiveMatrix (0.176ms)
[component_container_mt-32]     │   │       ├── calcConstraintMatrix (0.608ms)
[component_container_mt-32]     │   │       ├── calcOptimizedSteerAngles (1.473ms)
[component_container_mt-32]     │   │       │   ├── initOsqp (0.617ms)
[component_container_mt-32]     │   │       │   └── solveOsqp (0.596ms)
[component_container_mt-32]     │   │       ├── calcMPTPoints (0.013ms)
[component_container_mt-32]     │   │       └── publishDebugTrajectories (0.015ms)
[component_container_mt-32]     │   ├── applyInputVelocity (0.02ms)
[component_container_mt-32]     │   ├── insertZeroVelocityOutsideDrivableArea (0.254ms)
[component_container_mt-32]     │   └── publishDebugMarkerOfOptimization (0ms)
[component_container_mt-32]     ├── extendTrajectory (0.073ms)
[component_container_mt-32]     └── publishDebugData (0.001ms)

Related links

Parent Issue:

  • Link

How was this PR tested?

Notes for reviewers

None.

Interface changes

None.

Effects on system behavior

None.

…cessing time

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
@github-actions github-actions bot added component:planning Route planning, decision-making, and navigation. (auto-assigned) component:common Common packages from the autoware-common repository. (auto-assigned) labels Jun 30, 2024
Copy link

github-actions bot commented Jun 30, 2024

Thank you for contributing to the Autoware project!

🚧 If your pull request is in progress, switch it to draft mode.

Please ensure:

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
@yhisaki
Copy link
Contributor

yhisaki commented Jul 2, 2024

add new msg
tier4/tier4_autoware_msgs#137

Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
void TimeNode::construct_time_tree_msg(
tier4_debug_msgs::msg::TimeTree & time_tree_msg, const int parent_id)
{
auto time_node_msg = std::make_shared<tier4_debug_msgs::msg::TimeNode>();
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Any reason to use shared_ptr?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it's my mistake. i fixed it.

Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
@yhisaki
Copy link
Contributor

yhisaki commented Jul 4, 2024

msg

- id: 1
  name: onPath
  processing_time: 8.648
  parent_id: 0
- id: 2
  name: generateOptimizedTrajectory
  processing_time: 8.437
  parent_id: 1
- id: 3
  name: optimizeTrajectory
  processing_time: 7.938
  parent_id: 2
- id: 4
  name: optimizeTrajectory
  processing_time: 7.932
  parent_id: 3
- id: 5
  name: calcReferencePoints
  processing_time: 2.127
  parent_id: 4
- id: 6
  name: resampleReferencePoints
  processing_time: 0.139
  parent_id: 5
- id: 7
  name: updateFixedPoint
  processing_time: 0.091
  parent_id: 5
- id: 8
  name: updateBounds
  processing_time: 0.128
  parent_id: 5
- id: 9
  name: updateVehicleBounds
  processing_time: 0.837
  parent_id: 5
- id: 10
  name: updateExtraPoints
  processing_time: 0.596
  parent_id: 5
- id: 11
  name: calcMatrix
  processing_time: 0.092
  parent_id: 4
- id: 12
  name: calcValueMatrix
  processing_time: 0.023
  parent_id: 4
- id: 13
  name: calcObjectiveMatrix
  processing_time: 0.641
  parent_id: 4
- id: 14
  name: calcConstraintMatrix
  processing_time: 1.876
  parent_id: 4
- id: 15
  name: calcOptimizedSteerAngles
  processing_time: 3.025
  parent_id: 4
- id: 16
  name: initOsqp
  processing_time: 1.349
  parent_id: 15
- id: 17
  name: solveOsqp
  processing_time: 1.153
  parent_id: 15
- id: 18
  name: calcMPTPoints
  processing_time: 0.022
  parent_id: 4
- id: 19
  name: publishDebugTrajectories
  processing_time: 0.036
  parent_id: 4
- id: 20
  name: applyInputVelocity
  processing_time: 0.042
  parent_id: 2
- id: 21
  name: insertZeroVelocityOutsideDrivableArea
  processing_time: 0.436
  parent_id: 2
- id: 22
  name: publishDebugMarkerOfOptimization
  processing_time: 0.0
  parent_id: 2
- id: 23
  name: extendTrajectory
  processing_time: 0.125
  parent_id: 1
- id: 24
  name: publishDebugData
  processing_time: 0.003
  parent_id: 1
---

terminal output

[component_container_mt-32] ========================================
[component_container_mt-32] onPath (3.763ms)
[component_container_mt-32]     ├── generateOptimizedTrajectory (3.631ms)
[component_container_mt-32]     │   ├── optimizeTrajectory (3.341ms)
[component_container_mt-32]     │   │   └── optimizeTrajectory (3.338ms)
[component_container_mt-32]     │   │       ├── calcReferencePoints (0.951ms)
[component_container_mt-32]     │   │       │   ├── resampleReferencePoints (0.108ms)
[component_container_mt-32]     │   │       │   ├── updateFixedPoint (0.065ms)
[component_container_mt-32]     │   │       │   ├── updateBounds (0.066ms)
[component_container_mt-32]     │   │       │   ├── updateVehicleBounds (0.316ms)
[component_container_mt-32]     │   │       │   └── updateExtraPoints (0.171ms)
[component_container_mt-32]     │   │       ├── calcMatrix (0.049ms)
[component_container_mt-32]     │   │       ├── calcValueMatrix (0.01ms)
[component_container_mt-32]     │   │       ├── calcObjectiveMatrix (0.176ms)
[component_container_mt-32]     │   │       ├── calcConstraintMatrix (0.608ms)
[component_container_mt-32]     │   │       ├── calcOptimizedSteerAngles (1.473ms)
[component_container_mt-32]     │   │       │   ├── initOsqp (0.617ms)
[component_container_mt-32]     │   │       │   └── solveOsqp (0.596ms)
[component_container_mt-32]     │   │       ├── calcMPTPoints (0.013ms)
[component_container_mt-32]     │   │       └── publishDebugTrajectories (0.015ms)
[component_container_mt-32]     │   ├── applyInputVelocity (0.02ms)
[component_container_mt-32]     │   ├── insertZeroVelocityOutsideDrivableArea (0.254ms)
[component_container_mt-32]     │   └── publishDebugMarkerOfOptimization (0ms)
[component_container_mt-32]     ├── extendTrajectory (0.073ms)
[component_container_mt-32]     └── publishDebugData (0.001ms)

@takayuki5168 takayuki5168 added the tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Jul 4, 2024
@takayuki5168 takayuki5168 marked this pull request as ready for review July 4, 2024 08:57
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
component:common Common packages from the autoware-common repository. (auto-assigned) component:planning Route planning, decision-making, and navigation. (auto-assigned) tag:run-build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants