Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(map_based_prediction): update lane change decision logic #2822

Merged
merged 11 commits into from
Feb 16, 2023
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@
sigma_yaw_angle_deg: 5.0 #[angle degree]
object_buffer_time_length: 2.0 #[s]
history_time_length: 1.0 #[s]
dist_ratio_threshold_to_left_bound: -0.5 #[ratio]
dist_ratio_threshold_to_right_bound: 0.5 #[ratio
diff_dist_threshold_to_left_bound: 0.29 #[m]
diff_dist_threshold_to_right_bound: -0.29 #[m]
dist_threshold_for_lane_change_detection: 1.0 #[m]
time_threshold_for_lane_change_detection: 5.0 #[s]
cutoff_freq_of_velocity_for_lane_change_detection: 0.1 #[Hz]
reference_path_resolution: 0.5 #[m]
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,16 @@

namespace map_based_prediction
{
struct LateralKinematicsToLanelet
{
double dist_from_left_boundary;
double dist_from_right_boundary;
double left_lateral_velocity;
double right_lateral_velocity;
double filtered_left_lateral_velocity;
double filtered_right_lateral_velocity;
};

struct ObjectData
{
std_msgs::msg::Header header;
Expand All @@ -57,6 +67,8 @@ struct ObjectData
geometry_msgs::msg::Pose pose;
geometry_msgs::msg::Twist twist;
double time_delay;
// for lane change prediction
std::unordered_map<lanelet::ConstLanelet, LateralKinematicsToLanelet> lateral_kinematics_set;
};

enum class Maneuver {
Expand Down Expand Up @@ -133,10 +145,9 @@ class MapBasedPredictionNode : public rclcpp::Node
double sigma_yaw_angle_deg_;
double object_buffer_time_length_;
double history_time_length_;
double dist_ratio_threshold_to_left_bound_;
double dist_ratio_threshold_to_right_bound_;
double diff_dist_threshold_to_left_bound_;
double diff_dist_threshold_to_right_bound_;
double dist_threshold_to_bound_;
double time_threshold_to_bound_;
purewater0901 marked this conversation as resolved.
Show resolved Hide resolved
double cutoff_freq_of_velocity_lpf_;
double reference_path_resolution_;

// Stop watch
Expand Down
Loading