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

chore(map_based_prediction): prediction param to yaml #771

Merged
merged 2 commits into from
Aug 25, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,10 @@
sigma_yaw_angle_deg: 5.0 #[angle degree]
object_buffer_time_length: 2.0 #[s]
history_time_length: 1.0 #[s]
# parameter for shoulder lane prediction
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8

# parameters for lc prediction
lane_change_detection:
method: "lat_diff_distance" # choose from "lat_diff_distance" or "time_to_change_lane"
time_to_change_lane:
Expand Down
42 changes: 20 additions & 22 deletions perception/map_based_prediction/src/map_based_prediction_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -227,7 +227,7 @@
for (auto & candidate : right_lane_candidates) {
// exclude self lanelet
if (candidate == current_lanelet) continue;
// if candidate has linestring as leftbound, assign it to output

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

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (leftbound)
if (candidate.leftBound() == current_lanelet.rightBound()) {
output_lanelets.push_back(candidate);
}
Expand All @@ -254,7 +254,7 @@
for (auto & candidate : left_lane_candidates) {
// exclude self lanelet
if (candidate == current_lanelet) continue;
// if candidate has linestring as rightbound, assign it to output

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

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (rightbound)
if (candidate.rightBound() == current_lanelet.leftBound()) {
output_lanelets.push_back(candidate);
}
Expand Down Expand Up @@ -287,7 +287,7 @@
lanelet::ConstLanelets possible_lanelets;
possible_lanelets.push_back(lanelet);
lanelet::routing::LaneletPaths possible_paths;
// need to init path with constlanelets

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

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (constlanelets)
lanelet::routing::LaneletPath possible_path(possible_lanelets);
possible_paths.push_back(possible_path);
return possible_paths;
Expand Down Expand Up @@ -550,7 +550,7 @@
label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE) {
// if object is within road lanelet and satisfies yaw constraints
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
const float high_speed_threshold = 25.0 / 18.0 * 5.0; // High speed bycicle 25 km/h

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

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (bycicle)
const bool high_speed_object =
object.kinematics.twist_with_covariance.twist.linear.x > high_speed_threshold;

Expand Down Expand Up @@ -589,33 +589,31 @@
MapBasedPredictionNode::MapBasedPredictionNode(const rclcpp::NodeOptions & node_options)
: Node("map_based_prediction", node_options), debug_accumulated_time_(0.0)
{
enable_delay_compensation_ = declare_parameter("enable_delay_compensation", true);
prediction_time_horizon_ = declare_parameter("prediction_time_horizon", 10.0);
prediction_sampling_time_interval_ = declare_parameter("prediction_sampling_delta_time", 0.5);
enable_delay_compensation_ = declare_parameter<bool>("enable_delay_compensation");
prediction_time_horizon_ = declare_parameter<double>("prediction_time_horizon");
prediction_sampling_time_interval_ = declare_parameter<double>("prediction_sampling_delta_time");
min_velocity_for_map_based_prediction_ =
declare_parameter("min_velocity_for_map_based_prediction", 1.0);
min_crosswalk_user_velocity_ = declare_parameter("min_crosswalk_user_velocity", 1.0);
declare_parameter<double>("min_velocity_for_map_based_prediction");
min_crosswalk_user_velocity_ = declare_parameter<double>("min_crosswalk_user_velocity");
dist_threshold_for_searching_lanelet_ =
declare_parameter("dist_threshold_for_searching_lanelet", 3.0);
declare_parameter<double>("dist_threshold_for_searching_lanelet");
delta_yaw_threshold_for_searching_lanelet_ =
declare_parameter("delta_yaw_threshold_for_searching_lanelet", 0.785);
sigma_lateral_offset_ = declare_parameter("sigma_lateral_offset", 0.5);
sigma_yaw_angle_deg_ = declare_parameter("sigma_yaw_angle_deg", 5.0);
object_buffer_time_length_ = declare_parameter("object_buffer_time_length", 2.0);
history_time_length_ = declare_parameter("history_time_length", 1.0);
declare_parameter<double>("delta_yaw_threshold_for_searching_lanelet");
sigma_lateral_offset_ = declare_parameter<double>("sigma_lateral_offset");
sigma_yaw_angle_deg_ = declare_parameter<double>("sigma_yaw_angle_deg");
object_buffer_time_length_ = declare_parameter<double>("object_buffer_time_length");
history_time_length_ = declare_parameter<double>("history_time_length");
{ // lane change detection
lane_change_detection_method_ = declare_parameter<std::string>("lane_change_detection.method");

// lane change detection by time_to_change_lane
dist_threshold_to_bound_ = declare_parameter(
"lane_change_detection.time_to_change_lane.dist_threshold_for_lane_change_detection",
1.0); // 1m
time_threshold_to_bound_ = declare_parameter(
"lane_change_detection.time_to_change_lane.time_threshold_for_lane_change_detection",
5.0); // 5 sec
cutoff_freq_of_velocity_lpf_ = declare_parameter(
"lane_change_detection.time_to_change_lane.cutoff_freq_of_velocity_for_lane_change_detection",
0.1); // 0.1Hz
dist_threshold_to_bound_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.dist_threshold_for_lane_change_detection"); // 1m
time_threshold_to_bound_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.time_threshold_for_lane_change_detection");
cutoff_freq_of_velocity_lpf_ = declare_parameter<double>(
"lane_change_detection.time_to_change_lane.cutoff_freq_of_velocity_for_lane_change_"
"detection");

// lane change detection by lat_diff_distance
dist_ratio_threshold_to_left_bound_ = declare_parameter<double>(
Expand All @@ -630,11 +628,11 @@
num_continuous_state_transition_ =
declare_parameter<int>("lane_change_detection.num_continuous_state_transition");
}
reference_path_resolution_ = declare_parameter("reference_path_resolution", 0.5);
reference_path_resolution_ = declare_parameter<double>("reference_path_resolution");
/* prediction path will disabled when the estimated path length exceeds lanelet length. This
* parameter control the estimated path length = vx * th * (rate) */
prediction_time_horizon_rate_for_validate_lane_length_ =
declare_parameter("prediction_time_horizon_rate_for_validate_lane_length", 0.8);
declare_parameter<double>("prediction_time_horizon_rate_for_validate_shoulder_lane_length");

path_generator_ = std::make_shared<PathGenerator>(
prediction_time_horizon_, prediction_sampling_time_interval_, min_crosswalk_user_velocity_);
Expand Down
Loading