@@ -62,6 +62,8 @@ GoalPlannerModule::GoalPlannerModule(
62
62
parameters_{parameters},
63
63
vehicle_info_{vehicle_info_util::VehicleInfoUtil (node).getVehicleInfo ()},
64
64
thread_safe_data_{mutex_, clock_},
65
+ is_lane_parking_cb_running_{false },
66
+ is_freespace_parking_cb_running_{false },
65
67
debug_stop_pose_with_info_{&stop_pose_}
66
68
{
67
69
LaneDepartureChecker lane_departure_checker{};
@@ -161,9 +163,18 @@ bool GoalPlannerModule::hasDeviatedFromLastPreviousModulePath() const
161
163
planner_data_->self_odometry ->pose .pose .position )) > 0.3 ;
162
164
}
163
165
166
+ bool GoalPlannerModule::hasDeviatedFromCurrentPreviousModulePath () const
167
+ {
168
+ return std::abs (motion_utils::calcLateralOffset (
169
+ getPreviousModuleOutput ().path .points ,
170
+ planner_data_->self_odometry ->pose .pose .position )) > 0.3 ;
171
+ }
172
+
164
173
// generate pull over candidate paths
165
174
void GoalPlannerModule::onTimer ()
166
175
{
176
+ const ScopedFlag flag (is_lane_parking_cb_running_);
177
+
167
178
if (getCurrentStatus () == ModuleStatus::IDLE) {
168
179
return ;
169
180
}
@@ -179,15 +190,19 @@ void GoalPlannerModule::onTimer()
179
190
180
191
// check if new pull over path candidates are needed to be generated
181
192
const bool need_update = std::invoke ([&]() {
193
+ if (hasDeviatedFromCurrentPreviousModulePath ()) {
194
+ RCLCPP_DEBUG (getLogger (), " has deviated from current previous module path" );
195
+ return false ;
196
+ }
182
197
if (thread_safe_data_.get_pull_over_path_candidates ().empty ()) {
183
198
return true ;
184
199
}
185
200
if (hasPreviousModulePathShapeChanged ()) {
186
- RCLCPP_ERROR (getLogger (), " has previous module path shape changed" );
201
+ RCLCPP_DEBUG (getLogger (), " has previous module path shape changed" );
187
202
return true ;
188
203
}
189
204
if (hasDeviatedFromLastPreviousModulePath () && !hasDecidedPath ()) {
190
- RCLCPP_ERROR (getLogger (), " has deviated from last previous module path" );
205
+ RCLCPP_DEBUG (getLogger (), " has deviated from last previous module path" );
191
206
return true ;
192
207
}
193
208
return false ;
@@ -276,6 +291,8 @@ void GoalPlannerModule::onTimer()
276
291
277
292
void GoalPlannerModule::onFreespaceParkingTimer ()
278
293
{
294
+ const ScopedFlag flag (is_freespace_parking_cb_running_);
295
+
279
296
if (getCurrentStatus () == ModuleStatus::IDLE) {
280
297
return ;
281
298
}
@@ -1554,27 +1571,9 @@ bool GoalPlannerModule::checkObjectsCollision(
1554
1571
}
1555
1572
1556
1573
/* Expand ego collision check polygon
1557
- * - `collision_check_margin` in all directions
1558
- * - `extra_stopping_margin` in the moving direction
1559
- * - `extra_lateral_margin` in external direction of path curve
1560
- *
1561
- *
1562
- * ^ moving direction
1563
- * x
1564
- * x
1565
- * x
1566
- * +----------------------+------x--+
1567
- * | | x |
1568
- * | +---------------+ | xx |
1569
- * | | | | xx |
1570
- * | | ego footprint |xxxxx |
1571
- * | | | | |
1572
- * | +---------------+ | extra_stopping_margin
1573
- * | margin | |
1574
- * +----------------------+ |
1575
- * | extra_lateral_margin |
1576
- * +--------------------------------+
1577
- *
1574
+ * - `collision_check_margin` is added in all directions.
1575
+ * - `extra_stopping_margin` adds stopping margin under deceleration constraints forward.
1576
+ * - `extra_lateral_margin` adds the lateral margin on curves.
1578
1577
*/
1579
1578
std::vector<Polygon2d> ego_polygons_expanded{};
1580
1579
const auto curvatures = motion_utils::calcCurvature (path.points );
@@ -1585,19 +1584,19 @@ bool GoalPlannerModule::checkObjectsCollision(
1585
1584
std::pow (p.point .longitudinal_velocity_mps , 2 ) * 0.5 / parameters_->maximum_deceleration ,
1586
1585
parameters_->object_recognition_collision_check_max_extra_stopping_margin );
1587
1586
1588
- double extra_lateral_margin = (-1 ) * curvatures.at (i) * p.point .longitudinal_velocity_mps *
1589
- std::abs (p.point .longitudinal_velocity_mps );
1590
- extra_lateral_margin =
1591
- std::clamp (extra_lateral_margin, -extra_stopping_margin, extra_stopping_margin);
1587
+ // The square is meant to imply centrifugal force, but it is not a very well-founded formula.
1588
+ // TODO(kosuke55): It is needed to consider better way because there is an inherently different
1589
+ // conception of the inside and outside margins.
1590
+ const double extra_lateral_margin = std::min (
1591
+ extra_stopping_margin,
1592
+ std::abs (curvatures.at (i) * std::pow (p.point .longitudinal_velocity_mps , 2 )));
1592
1593
1593
- const auto lateral_offset_pose =
1594
- tier4_autoware_utils::calcOffsetPose (p.point .pose , 0.0 , extra_lateral_margin / 2.0 , 0.0 );
1595
1594
const auto ego_polygon = tier4_autoware_utils::toFootprint (
1596
- lateral_offset_pose ,
1595
+ p. point . pose ,
1597
1596
planner_data_->parameters .base_link2front + collision_check_margin + extra_stopping_margin,
1598
1597
planner_data_->parameters .base_link2rear + collision_check_margin,
1599
1598
planner_data_->parameters .vehicle_width + collision_check_margin * 2.0 +
1600
- std::abs ( extra_lateral_margin) );
1599
+ extra_lateral_margin * 2.0 );
1601
1600
ego_polygons_expanded.push_back (ego_polygon);
1602
1601
}
1603
1602
0 commit comments