@@ -55,7 +55,7 @@ bool RunOutModule::modifyPathVelocity(
55
55
PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason)
56
56
{
57
57
// timer starts
58
- const auto t1_modify_path = std::chrono::system_clock::now ();
58
+ const auto t_start = std::chrono::system_clock::now ();
59
59
60
60
// set planner data
61
61
const auto current_vel = planner_data_->current_velocity ->twist .linear .x ;
@@ -65,20 +65,27 @@ bool RunOutModule::modifyPathVelocity(
65
65
// set height of debug data
66
66
debug_ptr_->setHeight (current_pose.position .z );
67
67
68
- // smooth velocity of the path to calculate time to collision accurately
69
- PathWithLaneId smoothed_path;
70
- if (!smoothPath (*path, smoothed_path, planner_data_)) {
71
- return true ;
72
- }
73
-
74
68
// extend path to consider obstacles after the goal
75
- const auto extended_smoothed_path =
76
- run_out_utils::extendPath (smoothed_path , planner_param_.vehicle_param .base_to_front );
69
+ const auto extended_path =
70
+ run_out_utils::extendPath (*path , planner_param_.vehicle_param .base_to_front );
77
71
78
72
// trim path ahead of the base_link to make calculation easier
79
73
const double trim_distance = planner_param_.run_out .detection_distance ;
80
- const auto trim_smoothed_path =
81
- run_out_utils::trimPathFromSelfPose (extended_smoothed_path, current_pose, trim_distance);
74
+ const auto trim_path =
75
+ run_out_utils::trimPathFromSelfPose (extended_path, current_pose, trim_distance);
76
+
77
+ // smooth velocity of the path to calculate time to collision accurately
78
+ PathWithLaneId extended_smoothed_path;
79
+ if (!smoothPath (trim_path, extended_smoothed_path, planner_data_)) {
80
+ return true ;
81
+ }
82
+
83
+ // record time for path processing
84
+ const auto t_path_processing = std::chrono::system_clock::now ();
85
+ const auto elapsed_path_processing =
86
+ std::chrono::duration_cast<std::chrono::microseconds>(t_path_processing - t_start);
87
+ debug_ptr_->setDebugValues (
88
+ DebugValues::TYPE::CALCULATION_TIME_PATH_PROCESSING, elapsed_path_processing.count () / 1000.0 );
82
89
83
90
// create abstracted dynamic obstacles from objects or points
84
91
dynamic_obstacle_creator_->setData (*planner_data_, planner_param_, *path, extended_smoothed_path);
@@ -87,18 +94,24 @@ bool RunOutModule::modifyPathVelocity(
87
94
88
95
// extract obstacles using lanelet information
89
96
const auto partition_excluded_obstacles =
90
- excludeObstaclesOutSideOfPartition (dynamic_obstacles, trim_smoothed_path , current_pose);
97
+ excludeObstaclesOutSideOfPartition (dynamic_obstacles, extended_smoothed_path , current_pose);
91
98
92
- // timer starts
93
- const auto t1_collision_check = std::chrono::system_clock::now ();
99
+ // record time for obstacle creation
100
+ const auto t_obstacle_creation = std::chrono::system_clock::now ();
101
+ const auto elapsed_obstacle_creation =
102
+ std::chrono::duration_cast<std::chrono::microseconds>(t_obstacle_creation - t_path_processing);
103
+ debug_ptr_->setDebugValues (
104
+ DebugValues::TYPE::CALCULATION_TIME_OBSTACLE_CREATION,
105
+ elapsed_obstacle_creation.count () / 1000.0 );
94
106
95
107
// detect collision with dynamic obstacles using velocity planning of ego
96
- const auto dynamic_obstacle = detectCollision (partition_excluded_obstacles, trim_smoothed_path);
108
+ const auto dynamic_obstacle =
109
+ detectCollision (partition_excluded_obstacles, extended_smoothed_path);
97
110
98
- // timer ends
99
- const auto t2_collision_check = std::chrono::system_clock::now ();
111
+ // record time for collision check
112
+ const auto t_collision_check = std::chrono::system_clock::now ();
100
113
const auto elapsed_collision_check =
101
- std::chrono::duration_cast<std::chrono::microseconds>(t2_collision_check - t1_collision_check );
114
+ std::chrono::duration_cast<std::chrono::microseconds>(t_collision_check - t_obstacle_creation );
102
115
debug_ptr_->setDebugValues (
103
116
DebugValues::TYPE::CALCULATION_TIME_COLLISION_CHECK, elapsed_collision_check.count () / 1000.0 );
104
117
@@ -107,7 +120,7 @@ bool RunOutModule::modifyPathVelocity(
107
120
// after a certain amount of time has elapsed since the ego stopped,
108
121
// approach the obstacle with slow velocity
109
122
insertVelocityForState (
110
- dynamic_obstacle, *planner_data_, planner_param_, trim_smoothed_path , *path);
123
+ dynamic_obstacle, *planner_data_, planner_param_, extended_smoothed_path , *path);
111
124
} else {
112
125
// just insert zero velocity for stopping
113
126
insertStoppingVelocity (dynamic_obstacle, current_pose, current_vel, current_acc, *path);
@@ -119,14 +132,19 @@ bool RunOutModule::modifyPathVelocity(
119
132
}
120
133
121
134
publishDebugValue (
122
- trim_smoothed_path , partition_excluded_obstacles, dynamic_obstacle, current_pose);
135
+ extended_smoothed_path , partition_excluded_obstacles, dynamic_obstacle, current_pose);
123
136
124
- // timer ends
125
- const auto t2_modify_path = std::chrono::system_clock::now ();
126
- const auto elapsed_modify_path =
127
- std::chrono::duration_cast<std::chrono::microseconds>(t2_modify_path - t1_modify_path );
137
+ // record time for collision check
138
+ const auto t_path_planning = std::chrono::system_clock::now ();
139
+ const auto elapsed_path_planning =
140
+ std::chrono::duration_cast<std::chrono::microseconds>(t_path_planning - t_collision_check );
128
141
debug_ptr_->setDebugValues (
129
- DebugValues::TYPE::CALCULATION_TIME, elapsed_modify_path.count () / 1000.0 );
142
+ DebugValues::TYPE::CALCULATION_TIME_PATH_PLANNING, elapsed_path_planning.count () / 1000.0 );
143
+
144
+ // record time for the function
145
+ const auto t_end = std::chrono::system_clock::now ();
146
+ const auto elapsed_all = std::chrono::duration_cast<std::chrono::microseconds>(t_end - t_start);
147
+ debug_ptr_->setDebugValues (DebugValues::TYPE::CALCULATION_TIME, elapsed_all.count () / 1000.0 );
130
148
131
149
return true ;
132
150
}
0 commit comments