Skip to content

Commit fa6540a

Browse files
authored
Merge pull request #1325 from tier4/v0.26.1+RT1-6338
feat(obstacle_cruise)!: type specified stop deccel limit and enabling abandon to stop
2 parents d54286f + 993f53e commit fa6540a

File tree

8 files changed

+270
-166
lines changed

8 files changed

+270
-166
lines changed

planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml

+12
Original file line numberDiff line numberDiff line change
@@ -217,3 +217,15 @@
217217
lpf_gain_slow_down_vel: 0.99 # low-pass filter gain for slow down velocity
218218
lpf_gain_lat_dist: 0.999 # low-pass filter gain for lateral distance from obstacle to ego's path
219219
lpf_gain_dist_to_slow_down: 0.7 # low-pass filter gain for distance to slow down start
220+
stop:
221+
type_specified_params:
222+
labels: # For the listed types, the node try to read the following type specified values
223+
- "default"
224+
- "unknown"
225+
# default: For the default type, which denotes the other types listed above, the following param is defined implicitly, and the other type-specified parameters are not defined.
226+
# limit_min_acc: common_param.yaml/limit.min_acc
227+
unknown:
228+
limit_min_acc: -1.2 # overwrite the deceleration limit, in usually, common_param.yaml/limit.min_acc is referred.
229+
sudden_object_acc_threshold: -1.1 # If a stop can be achieved by a deceleration smaller than this value, it is not considered as “sudden stop".
230+
sudden_object_dist_threshold: 1000.0 # If a stop distance is longer than this value, it is not considered as “sudden stop".
231+
abandon_to_stop: false # If true, the planner gives up to stop when it cannot avoid to run over while maintaining the deceleration limit.

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/common_structs.hpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -113,14 +113,15 @@ struct StopObstacle : public TargetObstacleInterface
113113
{
114114
StopObstacle(
115115
const std::string & arg_uuid, const rclcpp::Time & arg_stamp,
116-
const geometry_msgs::msg::Pose & arg_pose, const Shape & arg_shape,
117-
const double arg_lon_velocity, const double arg_lat_velocity,
116+
const ObjectClassification & object_classification, const geometry_msgs::msg::Pose & arg_pose,
117+
const Shape & arg_shape, const double arg_lon_velocity, const double arg_lat_velocity,
118118
const geometry_msgs::msg::Point arg_collision_point,
119119
const double arg_dist_to_collide_on_decimated_traj)
120120
: TargetObstacleInterface(arg_uuid, arg_stamp, arg_pose, arg_lon_velocity, arg_lat_velocity),
121121
shape(arg_shape),
122122
collision_point(arg_collision_point),
123-
dist_to_collide_on_decimated_traj(arg_dist_to_collide_on_decimated_traj)
123+
dist_to_collide_on_decimated_traj(arg_dist_to_collide_on_decimated_traj),
124+
classification(object_classification)
124125
{
125126
}
126127
Shape shape;
@@ -129,6 +130,7 @@ struct StopObstacle : public TargetObstacleInterface
129130
// calculateMarginFromObstacleOnCurve() and should be removed as it can be
130131
// replaced by ”dist_to_collide_on_decimated_traj”
131132
double dist_to_collide_on_decimated_traj;
133+
ObjectClassification classification;
132134
};
133135

134136
struct CruiseObstacle : public TargetObstacleInterface

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/node.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -266,8 +266,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
266266
bool is_driving_forward_{true};
267267
bool enable_slow_down_planning_{false};
268268

269-
// previous closest obstacle
270-
std::shared_ptr<StopObstacle> prev_closest_stop_obstacle_ptr_{nullptr};
269+
std::vector<StopObstacle> prev_closest_stop_obstacles_{};
271270

272271
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;
273272

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp

+82-1
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
#include "tier4_autoware_utils/ros/update_param.hpp"
2424
#include "tier4_autoware_utils/system/stop_watch.hpp"
2525

26+
#include <limits>
2627
#include <memory>
2728
#include <optional>
2829
#include <string>
@@ -42,7 +43,8 @@ class PlannerInterface
4243
vehicle_info_(vehicle_info),
4344
ego_nearest_param_(ego_nearest_param),
4445
debug_data_ptr_(debug_data_ptr),
45-
slow_down_param_(SlowDownParam(node))
46+
slow_down_param_(SlowDownParam(node)),
47+
stop_param_(StopParam(node, longitudinal_info))
4648
{
4749
stop_reasons_pub_ = node.create_publisher<StopReasonArray>("~/output/stop_reasons", 1);
4850
velocity_factors_pub_ =
@@ -91,6 +93,7 @@ class PlannerInterface
9193
updateCommonParam(parameters);
9294
updateCruiseParam(parameters);
9395
slow_down_param_.onParam(parameters);
96+
stop_param_.onParam(parameters, longitudinal_info_);
9497
}
9598

9699
Float32MultiArrayStamped getStopPlanningDebugMessage(const rclcpp::Time & current_time) const
@@ -333,6 +336,84 @@ class PlannerInterface
333336
double lpf_gain_dist_to_slow_down;
334337
};
335338
SlowDownParam slow_down_param_;
339+
struct StopParam
340+
{
341+
struct ObstacleSpecificParams
342+
{
343+
double limit_min_acc;
344+
double sudden_object_acc_threshold;
345+
double sudden_object_dist_threshold;
346+
bool abandon_to_stop;
347+
};
348+
const std::unordered_map<uint8_t, std::string> types_maps = {
349+
{ObjectClassification::UNKNOWN, "unknown"}, {ObjectClassification::CAR, "car"},
350+
{ObjectClassification::TRUCK, "truck"}, {ObjectClassification::BUS, "bus"},
351+
{ObjectClassification::TRAILER, "trailer"}, {ObjectClassification::MOTORCYCLE, "motorcycle"},
352+
{ObjectClassification::BICYCLE, "bicycle"}, {ObjectClassification::PEDESTRIAN, "pedestrian"}};
353+
std::unordered_map<std::string, ObstacleSpecificParams> type_specified_param_list;
354+
explicit StopParam(rclcpp::Node & node, const LongitudinalInfo & longitudinal_info)
355+
{
356+
const std::string param_prefix = "stop.type_specified_params.";
357+
std::vector<std::string> obstacle_labels{"default"};
358+
obstacle_labels =
359+
node.declare_parameter<std::vector<std::string>>(param_prefix + "labels", obstacle_labels);
360+
361+
for (const auto & type_str : obstacle_labels) {
362+
if (type_str != "default") {
363+
ObstacleSpecificParams param{
364+
node.declare_parameter<double>(param_prefix + type_str + ".limit_min_acc"),
365+
node.declare_parameter<double>(
366+
param_prefix + type_str + ".sudden_object_acc_threshold"),
367+
node.declare_parameter<double>(
368+
param_prefix + type_str + ".sudden_object_dist_threshold"),
369+
node.declare_parameter<bool>(param_prefix + type_str + ".abandon_to_stop")};
370+
371+
param.sudden_object_acc_threshold =
372+
std::min(param.sudden_object_acc_threshold, longitudinal_info.limit_min_accel);
373+
param.limit_min_acc = std::min(param.limit_min_acc, param.sudden_object_acc_threshold);
374+
375+
type_specified_param_list.emplace(type_str, param);
376+
}
377+
}
378+
}
379+
void onParam(
380+
const std::vector<rclcpp::Parameter> & parameters, const LongitudinalInfo & longitudinal_info)
381+
{
382+
const std::string param_prefix = "stop.type_specified_params.";
383+
for (auto & [type_str, param] : type_specified_param_list) {
384+
if (type_str == "default") {
385+
continue;
386+
}
387+
tier4_autoware_utils::updateParam<double>(
388+
parameters, param_prefix + type_str + ".limit_min_acc", param.limit_min_acc);
389+
tier4_autoware_utils::updateParam<double>(
390+
parameters, param_prefix + type_str + ".sudden_object_acc_threshold",
391+
param.sudden_object_acc_threshold);
392+
tier4_autoware_utils::updateParam<double>(
393+
parameters, param_prefix + type_str + ".sudden_object_dist_threshold",
394+
param.sudden_object_dist_threshold);
395+
tier4_autoware_utils::updateParam<bool>(
396+
parameters, param_prefix + type_str + ".abandon_to_stop", param.abandon_to_stop);
397+
398+
param.sudden_object_acc_threshold =
399+
std::min(param.sudden_object_acc_threshold, longitudinal_info.limit_min_accel);
400+
param.limit_min_acc = std::min(param.limit_min_acc, param.sudden_object_acc_threshold);
401+
}
402+
}
403+
std::string getParamType(const ObjectClassification label)
404+
{
405+
const auto type_str = types_maps.at(label.label);
406+
if (type_specified_param_list.count(type_str) == 0) {
407+
return "default";
408+
}
409+
return type_str;
410+
}
411+
ObstacleSpecificParams getParam(const ObjectClassification label)
412+
{
413+
return type_specified_param_list.at(getParamType(label));
414+
}
415+
};
416+
StopParam stop_param_;
336417
double moving_object_speed_threshold;
337418
double moving_object_hysteresis_range;
338419
std::vector<SlowDownOutput> prev_slow_down_output_;

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/utils.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,7 @@ PoseWithStamp getCurrentObjectPose(
3636
const PredictedObject & predicted_object, const rclcpp::Time & obj_base_time,
3737
const rclcpp::Time & current_time, const bool use_prediction);
3838

39-
std::optional<StopObstacle> getClosestStopObstacle(
40-
const std::vector<StopObstacle> & stop_obstacles);
39+
std::vector<StopObstacle> getClosestStopObstacles(const std::vector<StopObstacle> & stop_obstacles);
4140

4241
template <class T>
4342
size_t getIndexWithLongitudinalOffset(

planning/obstacle_cruise_planner/src/node.cpp

+28-64
Original file line numberDiff line numberDiff line change
@@ -1239,9 +1239,9 @@ std::optional<StopObstacle> ObstacleCruisePlannerNode::createStopObstacle(
12391239
}
12401240

12411241
const auto [tangent_vel, normal_vel] = projectObstacleVelocityToTrajectory(traj_points, obstacle);
1242-
return StopObstacle{
1243-
obstacle.uuid, obstacle.stamp, obstacle.pose, obstacle.shape,
1244-
tangent_vel, normal_vel, collision_point->first, collision_point->second};
1242+
return StopObstacle{obstacle.uuid, obstacle.stamp, obstacle.classification,
1243+
obstacle.pose, obstacle.shape, tangent_vel,
1244+
normal_vel, collision_point->first, collision_point->second};
12451245
}
12461246

12471247
std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacle(
@@ -1372,72 +1372,36 @@ void ObstacleCruisePlannerNode::checkConsistency(
13721372
const rclcpp::Time & current_time, const PredictedObjects & predicted_objects,
13731373
std::vector<StopObstacle> & stop_obstacles)
13741374
{
1375-
const auto current_closest_stop_obstacle =
1376-
obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles);
1377-
1378-
// If previous closest obstacle ptr is not set
1379-
if (!prev_closest_stop_obstacle_ptr_) {
1380-
if (current_closest_stop_obstacle) {
1381-
prev_closest_stop_obstacle_ptr_ =
1382-
std::make_shared<StopObstacle>(*current_closest_stop_obstacle);
1375+
for (const auto & prev_closest_stop_obstacle : prev_closest_stop_obstacles_) {
1376+
const auto predicted_object_itr = std::find_if(
1377+
predicted_objects.objects.begin(), predicted_objects.objects.end(),
1378+
[&prev_closest_stop_obstacle](const PredictedObject & po) {
1379+
return tier4_autoware_utils::toHexString(po.object_id) == prev_closest_stop_obstacle.uuid;
1380+
});
1381+
// If previous closest obstacle disappear from the perception result, do nothing anymore.
1382+
if (predicted_object_itr == predicted_objects.objects.end()) {
1383+
continue;
13831384
}
1384-
return;
1385-
}
1386-
1387-
// Put previous closest target obstacle if necessary
1388-
const auto predicted_object_itr = std::find_if(
1389-
predicted_objects.objects.begin(), predicted_objects.objects.end(),
1390-
[&](PredictedObject predicted_object) {
1391-
return tier4_autoware_utils::toHexString(predicted_object.object_id) ==
1392-
prev_closest_stop_obstacle_ptr_->uuid;
1393-
});
1394-
1395-
// If previous closest obstacle is not in the current perception lists
1396-
// just return the current target obstacles
1397-
if (predicted_object_itr == predicted_objects.objects.end()) {
1398-
return;
1399-
}
14001385

1401-
// Previous closest obstacle is in the perception lists
1402-
const auto obstacle_itr = std::find_if(
1403-
stop_obstacles.begin(), stop_obstacles.end(),
1404-
[&](const auto & obstacle) { return obstacle.uuid == prev_closest_stop_obstacle_ptr_->uuid; });
1405-
1406-
// Previous closest obstacle is both in the perception lists and target obstacles
1407-
if (obstacle_itr != stop_obstacles.end()) {
1408-
if (current_closest_stop_obstacle) {
1409-
if ((current_closest_stop_obstacle->uuid == prev_closest_stop_obstacle_ptr_->uuid)) {
1410-
// prev_closest_obstacle is current_closest_stop_obstacle just return the target
1411-
// obstacles(in target obstacles)
1412-
prev_closest_stop_obstacle_ptr_ =
1413-
std::make_shared<StopObstacle>(*current_closest_stop_obstacle);
1414-
} else {
1415-
// New obstacle becomes new stop obstacle
1416-
prev_closest_stop_obstacle_ptr_ =
1417-
std::make_shared<StopObstacle>(*current_closest_stop_obstacle);
1386+
const auto is_disappeared_from_stop_obstacle = std::none_of(
1387+
stop_obstacles.begin(), stop_obstacles.end(),
1388+
[&prev_closest_stop_obstacle](const StopObstacle & so) {
1389+
return so.uuid == prev_closest_stop_obstacle.uuid;
1390+
});
1391+
if (is_disappeared_from_stop_obstacle) {
1392+
// re-evaluate as a stop candidate, and overwrite the current decision if "maintain stop"
1393+
// condition is satisfied
1394+
const double elapsed_time = (current_time - prev_closest_stop_obstacle.stamp).seconds();
1395+
if (
1396+
predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x <
1397+
behavior_determination_param_.obstacle_velocity_threshold_from_stop_to_cruise &&
1398+
elapsed_time < behavior_determination_param_.stop_obstacle_hold_time_threshold) {
1399+
stop_obstacles.push_back(prev_closest_stop_obstacle);
14181400
}
1419-
} else {
1420-
// Previous closest stop obstacle becomes cruise obstacle
1421-
prev_closest_stop_obstacle_ptr_ = nullptr;
1422-
}
1423-
} else {
1424-
// prev obstacle is not in the target obstacles, but in the perception list
1425-
const double elapsed_time = (current_time - prev_closest_stop_obstacle_ptr_->stamp).seconds();
1426-
if (
1427-
predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x <
1428-
behavior_determination_param_.obstacle_velocity_threshold_from_stop_to_cruise &&
1429-
elapsed_time < behavior_determination_param_.stop_obstacle_hold_time_threshold) {
1430-
stop_obstacles.push_back(*prev_closest_stop_obstacle_ptr_);
1431-
return;
1432-
}
1433-
1434-
if (current_closest_stop_obstacle) {
1435-
prev_closest_stop_obstacle_ptr_ =
1436-
std::make_shared<StopObstacle>(*current_closest_stop_obstacle);
1437-
} else {
1438-
prev_closest_stop_obstacle_ptr_ = nullptr;
14391401
}
14401402
}
1403+
1404+
prev_closest_stop_obstacles_ = obstacle_cruise_utils::getClosestStopObstacles(stop_obstacles);
14411405
}
14421406

14431407
bool ObstacleCruisePlannerNode::isObstacleCrossing(

0 commit comments

Comments
 (0)