@@ -61,7 +61,7 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
61
61
ego_data.pose = planner_data_->current_odometry ->pose ;
62
62
ego_data.path .points = path->points ;
63
63
ego_data.first_path_idx =
64
- motion_utils::findNearestSegmentIndex (ego_data. path . points , ego_data.pose .position );
64
+ motion_utils::findNearestSegmentIndex (path-> points , ego_data.pose .position );
65
65
motion_utils::removeOverlapPoints (ego_data.path .points );
66
66
ego_data.velocity = planner_data_->current_velocity ->twist .linear .x ;
67
67
ego_data.max_decel = -planner_data_->max_stop_acceleration_threshold ;
@@ -70,13 +70,13 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
70
70
const auto path_footprints = calculate_path_footprints (ego_data, params_);
71
71
const auto calculate_path_footprints_us = stopwatch.toc (" calculate_path_footprints" );
72
72
// Calculate lanelets to ignore and consider
73
- const auto path_lanelets = planning_utils::getLaneletsOnPath (
74
- ego_data.path , planner_data_->route_handler_ ->getLaneletMapPtr (),
75
- planner_data_->current_odometry ->pose );
73
+ stopwatch.tic (" calculate_lanelets" );
74
+ const auto path_lanelets = calculate_path_lanelets (ego_data, *planner_data_->route_handler_ );
76
75
const auto ignored_lanelets =
77
76
calculate_ignored_lanelets (ego_data, path_lanelets, *planner_data_->route_handler_ , params_);
78
77
const auto other_lanelets = calculate_other_lanelets (
79
78
ego_data, path_lanelets, ignored_lanelets, *planner_data_->route_handler_ , params_);
79
+ const auto calculate_lanelets_us = stopwatch.toc (" calculate_lanelets" );
80
80
81
81
debug_data_.footprints = path_footprints;
82
82
debug_data_.path_lanelets = path_lanelets;
@@ -93,6 +93,7 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
93
93
});
94
94
if (overlapped_lanelet_it != other_lanelets.end ()) {
95
95
debug_data_.current_overlapped_lanelets .push_back (*overlapped_lanelet_it);
96
+ // TODO(Maxime): we may want to just add the overlapped lane to the ignored lanelets
96
97
RCLCPP_DEBUG (logger_, " Ego is already overlapping a lane, skipping the module ()\n " );
97
98
return true ;
98
99
}
@@ -178,13 +179,15 @@ bool OutOfLaneModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
178
179
RCLCPP_DEBUG (
179
180
logger_,
180
181
" Total time = %2.2fus\n "
182
+ " \t calculate_lanelets = %2.0fus\n "
181
183
" \t calculate_path_footprints = %2.0fus\n "
182
184
" \t calculate_overlapping_ranges = %2.0fus\n "
183
185
" \t calculate_decisions = %2.0fus\n "
184
186
" \t calc_slowdown_points = %2.0fus\n "
185
187
" \t insert_slowdown_points = %2.0fus\n " ,
186
- total_time_us, calculate_path_footprints_us, calculate_overlapping_ranges_us,
187
- calculate_decisions_us, calc_slowdown_points_us, insert_slowdown_points_us);
188
+ total_time_us, calculate_lanelets_us, calculate_path_footprints_us,
189
+ calculate_overlapping_ranges_us, calculate_decisions_us, calc_slowdown_points_us,
190
+ insert_slowdown_points_us);
188
191
return true ;
189
192
}
190
193
0 commit comments