@@ -88,8 +88,7 @@ bool SideShiftModule::isExecutionRequested() const
88
88
}
89
89
90
90
// If the desired offset has a non-zero value, return true as we want to execute the plan.
91
-
92
- const bool has_request = !isAlmostZero (requested_lateral_offset_);
91
+ const bool has_request = std::fabs (requested_lateral_offset_) >= 1.0e-4 ;
93
92
RCLCPP_DEBUG_STREAM (
94
93
getLogger (), " ESS::isExecutionRequested() : " << std::boolalpha << has_request);
95
94
@@ -119,14 +118,15 @@ bool SideShiftModule::canTransitSuccessState()
119
118
{
120
119
// Never return the FAILURE. When the desired offset is zero and the vehicle is in the original
121
120
// drivable area,this module can stop the computation and return SUCCESS.
121
+ constexpr double ZERO_THRESHOLD = 1.0e-4 ;
122
122
123
123
const auto isOffsetDiffAlmostZero = [this ]() noexcept {
124
124
const auto last_sp = path_shifter_.getLastShiftLine ();
125
125
if (last_sp) {
126
126
const auto length = std::fabs (last_sp.value ().end_shift_length );
127
127
const auto lateral_offset = std::fabs (requested_lateral_offset_);
128
128
const auto offset_diff = lateral_offset - length;
129
- if (! isAlmostZero (offset_diff)) {
129
+ if (std::fabs (offset_diff) >= ZERO_THRESHOLD ) {
130
130
lateral_offset_change_request_ = true ;
131
131
return false ;
132
132
}
@@ -135,7 +135,7 @@ bool SideShiftModule::canTransitSuccessState()
135
135
}();
136
136
137
137
const bool no_offset_diff = isOffsetDiffAlmostZero;
138
- const bool no_request = isAlmostZero (requested_lateral_offset_);
138
+ const bool no_request = std::fabs (requested_lateral_offset_) < ZERO_THRESHOLD ;
139
139
140
140
const auto no_shifted_plan = [&]() {
141
141
if (prev_output_.shift_length .empty ()) {
@@ -279,6 +279,11 @@ BehaviorModuleOutput SideShiftModule::plan()
279
279
ShiftedPath shifted_path;
280
280
path_shifter_.generate (&shifted_path);
281
281
282
+ if (shifted_path.path .points .empty ()) {
283
+ RCLCPP_ERROR (getLogger (), " Generated shift_path has no points" );
284
+ return {};
285
+ }
286
+
282
287
// Reset orientation
283
288
setOrientation (&shifted_path.path );
284
289
@@ -345,7 +350,8 @@ ShiftLine SideShiftModule::calcShiftLine() const
345
350
std::max (p->min_distance_to_start_shifting , ego_speed * p->time_to_start_shifting );
346
351
347
352
const double dist_to_end = [&]() {
348
- const double shift_length = requested_lateral_offset_ - getClosestShiftLength ();
353
+ const double shift_length =
354
+ requested_lateral_offset_ - getClosestShiftLength (prev_output_, getEgoPose ().position );
349
355
const double jerk_shifting_distance = autoware::motion_utils::calc_longitudinal_dist_from_jerk (
350
356
shift_length, p->shifting_lateral_jerk , std::max (ego_speed, p->min_shifting_speed ));
351
357
const double shifting_distance = std::max (jerk_shifting_distance, p->min_shifting_distance );
@@ -367,18 +373,6 @@ ShiftLine SideShiftModule::calcShiftLine() const
367
373
return shift_line;
368
374
}
369
375
370
- double SideShiftModule::getClosestShiftLength () const
371
- {
372
- if (prev_output_.shift_length .empty ()) {
373
- return 0.0 ;
374
- }
375
-
376
- const auto ego_point = planner_data_->self_odometry ->pose .pose .position ;
377
- const auto closest =
378
- autoware::motion_utils::findNearestIndex (prev_output_.path .points , ego_point);
379
- return prev_output_.shift_length .at (closest);
380
- }
381
-
382
376
BehaviorModuleOutput SideShiftModule::adjustDrivableArea (const ShiftedPath & path) const
383
377
{
384
378
BehaviorModuleOutput out;
0 commit comments