Skip to content

Commit 565589c

Browse files
feat(obstacle_cruise)!: type specified stop deccel limit and enabling abandon to stop (#7121)
* add abandon function Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 2b0de17 commit 565589c

File tree

8 files changed

+271
-144
lines changed

8 files changed

+271
-144
lines changed

planning/obstacle_cruise_planner/config/obstacle_cruise_planner.param.yaml

+12
Original file line numberDiff line numberDiff line change
@@ -218,3 +218,15 @@
218218
lpf_gain_slow_down_vel: 0.99 # low-pass filter gain for slow down velocity
219219
lpf_gain_lat_dist: 0.999 # low-pass filter gain for lateral distance from obstacle to ego's path
220220
lpf_gain_dist_to_slow_down: 0.7 # low-pass filter gain for distance to slow down start
221+
stop:
222+
type_specified_params:
223+
labels: # For the listed types, the node try to read the following type specified values
224+
- "default"
225+
- "unknown"
226+
# 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.
227+
# limit_min_acc: common_param.yaml/limit.min_acc
228+
unknown:
229+
limit_min_acc: -1.2 # overwrite the deceleration limit, in usually, common_param.yaml/limit.min_acc is referred.
230+
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".
231+
sudden_object_dist_threshold: 1000.0 # If a stop distance is longer than this value, it is not considered as “sudden stop".
232+
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
@@ -272,8 +272,7 @@ class ObstacleCruisePlannerNode : public rclcpp::Node
272272
bool is_driving_forward_{true};
273273
bool enable_slow_down_planning_{false};
274274

275-
// previous closest obstacle
276-
std::shared_ptr<StopObstacle> prev_closest_stop_obstacle_ptr_{nullptr};
275+
std::vector<StopObstacle> prev_closest_stop_obstacles_{};
277276

278277
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;
279278

planning/obstacle_cruise_planner/include/obstacle_cruise_planner/planner_interface.hpp

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

26+
#include <algorithm>
27+
#include <limits>
2628
#include <memory>
2729
#include <optional>
2830
#include <string>
@@ -42,7 +44,8 @@ class PlannerInterface
4244
vehicle_info_(vehicle_info),
4345
ego_nearest_param_(ego_nearest_param),
4446
debug_data_ptr_(debug_data_ptr),
45-
slow_down_param_(SlowDownParam(node))
47+
slow_down_param_(SlowDownParam(node)),
48+
stop_param_(StopParam(node, longitudinal_info))
4649
{
4750
stop_reasons_pub_ = node.create_publisher<StopReasonArray>("~/output/stop_reasons", 1);
4851
velocity_factors_pub_ =
@@ -91,6 +94,7 @@ class PlannerInterface
9194
updateCommonParam(parameters);
9295
updateCruiseParam(parameters);
9396
slow_down_param_.onParam(parameters);
97+
stop_param_.onParam(parameters, longitudinal_info_);
9498
}
9599

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

12551255
const auto [tangent_vel, normal_vel] = projectObstacleVelocityToTrajectory(traj_points, obstacle);
1256-
return StopObstacle{
1257-
obstacle.uuid, obstacle.stamp, obstacle.pose, obstacle.shape,
1258-
tangent_vel, normal_vel, collision_point->first, collision_point->second};
1256+
return StopObstacle{obstacle.uuid, obstacle.stamp, obstacle.classification,
1257+
obstacle.pose, obstacle.shape, tangent_vel,
1258+
normal_vel, collision_point->first, collision_point->second};
12591259
}
12601260

12611261
std::optional<SlowDownObstacle> ObstacleCruisePlannerNode::createSlowDownObstacle(
@@ -1386,50 +1386,36 @@ void ObstacleCruisePlannerNode::checkConsistency(
13861386
const rclcpp::Time & current_time, const PredictedObjects & predicted_objects,
13871387
std::vector<StopObstacle> & stop_obstacles)
13881388
{
1389-
const auto current_closest_stop_obstacle =
1390-
obstacle_cruise_utils::getClosestStopObstacle(stop_obstacles);
1391-
1392-
if (!prev_closest_stop_obstacle_ptr_) {
1393-
if (current_closest_stop_obstacle) {
1394-
prev_closest_stop_obstacle_ptr_ =
1395-
std::make_shared<StopObstacle>(*current_closest_stop_obstacle);
1389+
for (const auto & prev_closest_stop_obstacle : prev_closest_stop_obstacles_) {
1390+
const auto predicted_object_itr = std::find_if(
1391+
predicted_objects.objects.begin(), predicted_objects.objects.end(),
1392+
[&prev_closest_stop_obstacle](const PredictedObject & po) {
1393+
return tier4_autoware_utils::toHexString(po.object_id) == prev_closest_stop_obstacle.uuid;
1394+
});
1395+
// If previous closest obstacle disappear from the perception result, do nothing anymore.
1396+
if (predicted_object_itr == predicted_objects.objects.end()) {
1397+
continue;
13961398
}
1397-
return;
1398-
}
13991399

1400-
const auto predicted_object_itr = std::find_if(
1401-
predicted_objects.objects.begin(), predicted_objects.objects.end(),
1402-
[&](PredictedObject predicted_object) {
1403-
return tier4_autoware_utils::toHexString(predicted_object.object_id) ==
1404-
prev_closest_stop_obstacle_ptr_->uuid;
1405-
});
1406-
// If previous closest obstacle disappear from the perception result, do nothing anymore.
1407-
if (predicted_object_itr == predicted_objects.objects.end()) {
1408-
return;
1409-
}
1410-
1411-
const auto is_disappeared_from_stop_obstacle = std::none_of(
1412-
stop_obstacles.begin(), stop_obstacles.end(),
1413-
[&](const auto & obstacle) { return obstacle.uuid == prev_closest_stop_obstacle_ptr_->uuid; });
1414-
if (is_disappeared_from_stop_obstacle) {
1415-
// re-evaluate as a stop candidate, and overwrite the current decision if "maintain stop"
1416-
// condition is satisfied
1417-
const double elapsed_time = (current_time - prev_closest_stop_obstacle_ptr_->stamp).seconds();
1418-
if (
1419-
predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x <
1420-
behavior_determination_param_.obstacle_velocity_threshold_from_stop_to_cruise &&
1421-
elapsed_time < behavior_determination_param_.stop_obstacle_hold_time_threshold) {
1422-
stop_obstacles.push_back(*prev_closest_stop_obstacle_ptr_);
1423-
return;
1400+
const auto is_disappeared_from_stop_obstacle = std::none_of(
1401+
stop_obstacles.begin(), stop_obstacles.end(),
1402+
[&prev_closest_stop_obstacle](const StopObstacle & so) {
1403+
return so.uuid == prev_closest_stop_obstacle.uuid;
1404+
});
1405+
if (is_disappeared_from_stop_obstacle) {
1406+
// re-evaluate as a stop candidate, and overwrite the current decision if "maintain stop"
1407+
// condition is satisfied
1408+
const double elapsed_time = (current_time - prev_closest_stop_obstacle.stamp).seconds();
1409+
if (
1410+
predicted_object_itr->kinematics.initial_twist_with_covariance.twist.linear.x <
1411+
behavior_determination_param_.obstacle_velocity_threshold_from_stop_to_cruise &&
1412+
elapsed_time < behavior_determination_param_.stop_obstacle_hold_time_threshold) {
1413+
stop_obstacles.push_back(prev_closest_stop_obstacle);
1414+
}
14241415
}
14251416
}
14261417

1427-
if (current_closest_stop_obstacle) {
1428-
prev_closest_stop_obstacle_ptr_ =
1429-
std::make_shared<StopObstacle>(*current_closest_stop_obstacle);
1430-
} else {
1431-
prev_closest_stop_obstacle_ptr_ = nullptr;
1432-
}
1418+
prev_closest_stop_obstacles_ = obstacle_cruise_utils::getClosestStopObstacles(stop_obstacles);
14331419
}
14341420

14351421
bool ObstacleCruisePlannerNode::isObstacleCrossing(

0 commit comments

Comments
 (0)