Skip to content

Commit

Permalink
feat(map_based_prediction): use different time horizon
Browse files Browse the repository at this point in the history
Signed-off-by: Mamoru Sobue <[email protected]>
  • Loading branch information
soblin committed May 30, 2024
1 parent b93f173 commit 69ebedf
Show file tree
Hide file tree
Showing 7 changed files with 124 additions and 100 deletions.
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@
/**:
ros__parameters:
enable_delay_compensation: true
prediction_time_horizon: 10.0 #[s]
prediction_time_horizon:
vehicle: 15.0 #[s]
pedestrian: 10.0 #[s]
unknown: 10.0 #[s]
lateral_control_time_horizon: 5.0 #[s]
prediction_sampling_delta_time: 0.5 #[s]
min_velocity_for_map_based_prediction: 1.39 #[m/s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,13 @@ struct PredictedRefPath
Maneuver maneuver;
};

struct PredictionTimeHorizon
{
double vehicle;
double pedestrian;
double unknown;
};

using LaneletsData = std::vector<LaneletData>;
using ManeuverProbability = std::unordered_map<Maneuver, float>;
using autoware_auto_mapping_msgs::msg::HADMapBin;
Expand Down Expand Up @@ -170,7 +177,7 @@ class MapBasedPredictionNode : public rclcpp::Node

// Parameters
bool enable_delay_compensation_;
double prediction_time_horizon_;
PredictionTimeHorizon prediction_time_horizon_;
double lateral_control_time_horizon_;
double prediction_time_horizon_rate_for_validate_lane_length_;
double prediction_sampling_time_interval_;
Expand Down Expand Up @@ -253,7 +260,7 @@ class MapBasedPredictionNode : public rclcpp::Node
const std::string & object_id, std::unordered_map<std::string, TrackedObject> & current_users);
std::vector<PredictedRefPath> getPredictedReferencePath(
const TrackedObject & object, const LaneletsData & current_lanelets_data,
const double object_detected_time);
const double object_detected_time, const double time_horizon);
Maneuver predictObjectManeuver(
const TrackedObject & object, const LaneletData & current_lanelet_data,
const double object_detected_time);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,21 +80,24 @@ using PosePath = std::vector<geometry_msgs::msg::Pose>;
class PathGenerator
{
public:
PathGenerator(
const double time_horizon, const double lateral_time_horizon,
const double sampling_time_interval, const double min_crosswalk_user_velocity);
PathGenerator(const double sampling_time_interval, const double min_crosswalk_user_velocity);

PredictedPath generatePathForNonVehicleObject(const TrackedObject & object) const;
PredictedPath generatePathForNonVehicleObject(
const TrackedObject & object, const double duration) const;

PredictedPath generatePathForLowSpeedVehicle(const TrackedObject & object) const;
PredictedPath generatePathForLowSpeedVehicle(
const TrackedObject & object, const double duration) const;

PredictedPath generatePathForOffLaneVehicle(const TrackedObject & object) const;
PredictedPath generatePathForOffLaneVehicle(
const TrackedObject & object, const double duration) const;

PredictedPath generatePathForOnLaneVehicle(
const TrackedObject & object, const PosePath & ref_paths, const double speed_limit = 0.0) const;
const TrackedObject & object, const PosePath & ref_paths, const double duration,
const double lateral_duration, const double speed_limit = 0.0) const;

PredictedPath generatePathForCrosswalkUser(
const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk) const;
const TrackedObject & object, const CrosswalkEdgePoints & reachable_crosswalk,
const double duration) const;

PredictedPath generatePathToTargetPoint(
const TrackedObject & object, const Eigen::Vector2d & point) const;
Expand All @@ -111,22 +114,21 @@ class PathGenerator

private:
// Parameters
double time_horizon_;
double lateral_time_horizon_;
double sampling_time_interval_;
double min_crosswalk_user_velocity_;
bool use_vehicle_acceleration_;
double acceleration_exponential_half_life_;

// Member functions
PredictedPath generateStraightPath(const TrackedObject & object) const;
PredictedPath generateStraightPath(const TrackedObject & object, const double duration) const;

PredictedPath generatePolynomialPath(
const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0) const;
const TrackedObject & object, const PosePath & ref_path, const double duration,
const double lateral_duration, const double speed_limit = 0.0) const;

FrenetPath generateFrenetPath(
const FrenetPoint & current_point, const FrenetPoint & target_point,
const double max_length) const;
const FrenetPoint & current_point, const FrenetPoint & target_point, const double max_length,
const double duration, const double lateral_duration) const;
Eigen::Vector3d calcLatCoefficients(
const FrenetPoint & current_point, const FrenetPoint & target_point, const double T) const;
Eigen::Vector2d calcLonCoefficients(
Expand All @@ -140,7 +142,8 @@ class PathGenerator
const PosePath & ref_path) const;

FrenetPoint getFrenetPoint(
const TrackedObject & object, const PosePath & ref_path, const double speed_limit = 0.0) const;
const TrackedObject & object, const PosePath & ref_path, const double duration,
const double speed_limit = 0.0) const;
};
} // namespace map_based_prediction

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,23 @@
"description": "flag to enable the time delay compensation for the position of the object"
},
"prediction_time_horizon": {
"type": "number",
"default": "10.0",
"description": "predict time duration for predicted path"
"properties": {
"vehicle": {
"type": "number",
"default": "15.0",
"description": "predict time duration for predicted path of vehicle"
},
"pedestrian": {
"type": "number",
"default": "10.0",
"description": "predict time duration for predicted path of pedestrian"
},
"unknown": {
"type": "number",
"default": "10.0",
"description": "predict time duration for predicted path of unknown"
}
}
},
"lateral_control_time_horizon": {
"type": "number",
Expand Down
57 changes: 31 additions & 26 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -766,7 +766,10 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
google::InstallFailureSignalHandler();
}
enable_delay_compensation_ = declare_parameter<bool>("enable_delay_compensation");
prediction_time_horizon_ = declare_parameter<double>("prediction_time_horizon");
prediction_time_horizon_.vehicle = declare_parameter<double>("prediction_time_horizon.vehicle");
prediction_time_horizon_.pedestrian =
declare_parameter<double>("prediction_time_horizon.pedestrian");
prediction_time_horizon_.unknown = declare_parameter<double>("prediction_time_horizon.unknown");
lateral_control_time_horizon_ =
declare_parameter<double>("lateral_control_time_horizon"); // [s] for lateral control point
prediction_sampling_time_interval_ = declare_parameter<double>("prediction_sampling_delta_time");
Expand Down Expand Up @@ -840,8 +843,7 @@ MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_
"crosswalk_with_signal.timeout_set_for_no_intention_to_walk");

path_generator_ = std::make_shared<PathGenerator>(
prediction_time_horizon_, lateral_control_time_horizon_, prediction_sampling_time_interval_,
min_crosswalk_user_velocity_);
prediction_sampling_time_interval_, min_crosswalk_user_velocity_);

Check warning on line 846 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

MapBasedPredictionNode::MapBasedPredictionNode increases from 95 to 97 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

path_generator_->setUseVehicleAcceleration(use_vehicle_acceleration_);
path_generator_->setAccelerationHalfLife(acceleration_exponential_half_life_);
Expand Down Expand Up @@ -1050,8 +1052,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt

// For off lane obstacles
if (current_lanelets.empty()) {
PredictedPath predicted_path =
path_generator_->generatePathForOffLaneVehicle(transformed_object);
PredictedPath predicted_path = path_generator_->generatePathForOffLaneVehicle(
transformed_object, prediction_time_horizon_.vehicle);
predicted_path.confidence = 1.0;
if (predicted_path.path.empty()) break;

Expand All @@ -1066,8 +1068,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
transformed_object.kinematics.twist_with_covariance.twist.linear.x,
transformed_object.kinematics.twist_with_covariance.twist.linear.y);
if (std::fabs(abs_obj_speed) < min_velocity_for_map_based_prediction_) {
PredictedPath predicted_path =
path_generator_->generatePathForLowSpeedVehicle(transformed_object);
PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle(
transformed_object, prediction_time_horizon_.vehicle);
predicted_path.confidence = 1.0;
if (predicted_path.path.empty()) break;

Expand All @@ -1079,13 +1081,14 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt

// Get Predicted Reference Path for Each Maneuver and current lanelets
// return: <probability, paths>
const auto ref_paths =
getPredictedReferencePath(transformed_object, current_lanelets, objects_detected_time);
const auto ref_paths = getPredictedReferencePath(
transformed_object, current_lanelets, objects_detected_time,
prediction_time_horizon_.vehicle);

// If predicted reference path is empty, assume this object is out of the lane
if (ref_paths.empty()) {
PredictedPath predicted_path =
path_generator_->generatePathForLowSpeedVehicle(transformed_object);
PredictedPath predicted_path = path_generator_->generatePathForLowSpeedVehicle(
transformed_object, prediction_time_horizon_.vehicle);
predicted_path.confidence = 1.0;
if (predicted_path.path.empty()) break;

Expand Down Expand Up @@ -1120,7 +1123,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt

for (const auto & ref_path : ref_paths) {
PredictedPath predicted_path = path_generator_->generatePathForOnLaneVehicle(
yaw_fixed_transformed_object, ref_path.path, ref_path.speed_limit);
yaw_fixed_transformed_object, ref_path.path, prediction_time_horizon_.vehicle,
lateral_control_time_horizon_, ref_path.speed_limit);
if (predicted_path.path.empty()) continue;

if (!check_lateral_acceleration_constraints_) {
Expand Down Expand Up @@ -1183,8 +1187,8 @@ void MapBasedPredictionNode::objectsCallback(const TrackedObjects::ConstSharedPt
}
default: {
auto predicted_unknown_object = convertToPredictedObject(transformed_object);
PredictedPath predicted_path =
path_generator_->generatePathForNonVehicleObject(transformed_object);
PredictedPath predicted_path = path_generator_->generatePathForNonVehicleObject(
transformed_object, prediction_time_horizon_.unknown);

Check warning on line 1191 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::objectsCallback already has high cyclomatic complexity, and now it increases in Lines of Code from 215 to 217. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
predicted_path.confidence = 1.0;

predicted_unknown_object.kinematics.predicted_paths.push_back(predicted_path);
Expand Down Expand Up @@ -1337,7 +1341,8 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
{
auto predicted_object = convertToPredictedObject(object);
{
PredictedPath predicted_path = path_generator_->generatePathForNonVehicleObject(object);
PredictedPath predicted_path =
path_generator_->generatePathForNonVehicleObject(object, prediction_time_horizon_.pedestrian);
predicted_path.confidence = 1.0;

predicted_object.kinematics.predicted_paths.push_back(predicted_path);
Expand Down Expand Up @@ -1388,7 +1393,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(

if (hasPotentialToReach(
object, edge_points.front_center_point, edge_points.front_right_point,
edge_points.front_left_point, prediction_time_horizon_ * 2.0,
edge_points.front_left_point, prediction_time_horizon_.pedestrian * 2.0,
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) {
PredictedPath predicted_path =
path_generator_->generatePathToTargetPoint(object, edge_points.front_center_point);
Expand All @@ -1398,7 +1403,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(

if (hasPotentialToReach(
object, edge_points.back_center_point, edge_points.back_right_point,
edge_points.back_left_point, prediction_time_horizon_ * 2.0,
edge_points.back_left_point, prediction_time_horizon_.pedestrian * 2.0,
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_)) {
PredictedPath predicted_path =
path_generator_->generatePathToTargetPoint(object, edge_points.back_center_point);
Expand All @@ -1422,27 +1427,27 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(

const auto reachable_first = hasPotentialToReach(
object, edge_points.front_center_point, edge_points.front_right_point,
edge_points.front_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_,
max_crosswalk_user_delta_yaw_threshold_for_lanelet_);
edge_points.front_left_point, prediction_time_horizon_.pedestrian,
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_);
const auto reachable_second = hasPotentialToReach(
object, edge_points.back_center_point, edge_points.back_right_point,
edge_points.back_left_point, prediction_time_horizon_, min_crosswalk_user_velocity_,
max_crosswalk_user_delta_yaw_threshold_for_lanelet_);
edge_points.back_left_point, prediction_time_horizon_.pedestrian,
min_crosswalk_user_velocity_, max_crosswalk_user_delta_yaw_threshold_for_lanelet_);

if (!reachable_first && !reachable_second) {
continue;
}

const auto reachable_crosswalk = isReachableCrosswalkEdgePoints(
object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_,
object, crosswalk, edge_points, lanelet_map_ptr_, prediction_time_horizon_.pedestrian,
min_crosswalk_user_velocity_);

if (!reachable_crosswalk) {
continue;
}

PredictedPath predicted_path =
path_generator_->generatePathForCrosswalkUser(object, reachable_crosswalk.get());
PredictedPath predicted_path = path_generator_->generatePathForCrosswalkUser(
object, reachable_crosswalk.get(), prediction_time_horizon_.pedestrian);

Check warning on line 1450 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser already has high cyclomatic complexity, and now it increases in Lines of Code from 106 to 107. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
predicted_path.confidence = 1.0;

if (predicted_path.path.empty()) {
Expand Down Expand Up @@ -1740,7 +1745,7 @@ void MapBasedPredictionNode::updateRoadUsersHistory(

std::vector<PredictedRefPath> MapBasedPredictionNode::getPredictedReferencePath(
const TrackedObject & object, const LaneletsData & current_lanelets_data,
const double object_detected_time)
const double object_detected_time, const double time_horizon)
{
const double obj_vel = std::hypot(
object.kinematics.twist_with_covariance.twist.linear.x,
Expand All @@ -1752,7 +1757,7 @@ std::vector<PredictedRefPath> MapBasedPredictionNode::getPredictedReferencePath(
object.kinematics.acceleration_with_covariance.accel.linear.x,
object.kinematics.acceleration_with_covariance.accel.linear.y)
: 0.0;
const double t_h = prediction_time_horizon_;
const double t_h = time_horizon;
const double λ = std::log(2) / acceleration_exponential_half_life_;

auto get_search_distance_with_decaying_acc = [&]() -> double {
Expand Down
Loading

0 comments on commit 69ebedf

Please sign in to comment.