Skip to content

Commit

Permalink
update params
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Aug 13, 2022
1 parent 6a1088d commit 2116899
Show file tree
Hide file tree
Showing 8 changed files with 23 additions and 27 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ struct Param
{
double delay_time;
double footprint_margin;
double max_deceleration;
double maximum_deceleration;
double resample_interval;
double search_radius;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,7 @@
pull_over_minimum_velocity: 0.3
margin_from_boundary: 0.5
decide_path_distance: 10.0
max_deceleration: 0.5
enable_shift_parking: true
enable_arc_forward_parking: true
enable_arc_backward_parking: false
maximum_deceleration: 0.5
# goal research
search_priority: "efficient_path" # "efficient_path" or "close_goal"
enable_goal_research: true
Expand All @@ -25,14 +22,16 @@
theta_size: 360
obstacle_threshold: 60
# shift path
enable_shift_parking: true
pull_over_sampling_num: 4
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
maximum_deceleration: 1.0
after_pull_over_straight_distance: 5.0
before_pull_over_straight_distance: 5.0
# parallel parking path
enable_arc_forward_parking: true
enable_arc_backward_parking: false
after_forward_parking_straight_distance: 2.0
after_backward_parking_straight_distance: 2.0
forward_parking_velocity: 0.3
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,7 @@
pull_over_minimum_velocity: 0.3
margin_from_boundary: 0.5
decide_path_distance: 10.0
max_deceleration: 0.5
enable_shift_parking: true
enable_arc_forward_parking: true
enable_arc_backward_parking: false
maximum_deceleration: 0.5
# goal research
search_priority: "efficient_path" # "efficient_path" or "close_goal"
enable_goal_research: true
Expand All @@ -25,14 +22,16 @@
theta_size: 360
obstacle_threshold: 60
# shift path
enable_shift_parking: true
pull_over_sampling_num: 4
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
maximum_deceleration: 1.0
after_pull_over_straight_distance: 5.0
before_pull_over_straight_distance: 5.0
# parallel parking path
enable_arc_forward_parking: true
enable_arc_backward_parking: false
after_forward_parking_straight_distance: 2.0
after_backward_parking_straight_distance: 2.0
forward_parking_velocity: 0.3
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,7 @@ struct PullOverParameters
double th_stopped_time_sec;
double margin_from_boundary;
double decide_path_distance;
double max_deceleration;
bool enable_shift_parking;
bool enable_arc_forward_parking;
bool enable_arc_backward_parking;
double maximum_deceleration;
// goal research
std::string search_priority; // "efficient_path" or "close_goal"
bool enable_goal_research;
Expand All @@ -72,16 +69,18 @@ struct PullOverParameters
double theta_size;
double obstacle_threshold;
// shift path
bool enable_shift_parking;
int pull_over_sampling_num;
double maximum_lateral_jerk;
double minimum_lateral_jerk;
double deceleration_interval;
double pull_over_velocity;
double pull_over_minimum_velocity;
double maximum_deceleration;
double after_pull_over_straight_distance;
double before_pull_over_straight_distance;
// parallel parking
bool enable_arc_forward_parking;
bool enable_arc_backward_parking;
double after_forward_parking_straight_distance;
double after_backward_parking_straight_distance;
double forward_parking_velocity;
Expand All @@ -90,7 +89,7 @@ struct PullOverParameters
double backward_parking_lane_departure_margin;
double arc_path_interval;
double max_steer_rad;
// hazard. Not used now.
// hazard
double hazard_on_threshold_dis;
double hazard_on_threshold_vel;
// check safety with dynamic objects. Not used now.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ struct ParallelParkingParameters
double forward_parking_lane_departure_margin;
double departing_lane_departure_margin;
double arc_path_interval;
double max_deceleration;
double maximum_deceleration;
double max_steer_rad;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -371,10 +371,7 @@ PullOverParameters BehaviorPathPlannerNode::getPullOverParam()
p.th_stopped_time_sec = dp("th_stopped_time_sec", 2.0);
p.margin_from_boundary = dp("margin_from_boundary", 0.3);
p.decide_path_distance = dp("decide_path_distance", 10.0);
p.max_deceleration = dp("max_deceleration", 0.5);
p.enable_shift_parking = dp("enable_shift_parking", true);
p.enable_arc_forward_parking = dp("enable_arc_forward_parking", true);
p.enable_arc_backward_parking = dp("enable_arc_backward_parking", false);
p.maximum_deceleration = dp("maximum_deceleration", 0.5);
// goal research
p.search_priority = dp("search_priority", "efficient_path");
p.enable_goal_research = dp("enable_goal_research", true);
Expand All @@ -387,16 +384,18 @@ PullOverParameters BehaviorPathPlannerNode::getPullOverParam()
p.theta_size = dp("theta_size", 360);
p.obstacle_threshold = dp("obstacle_threshold", 90);
// shift path
p.enable_shift_parking = dp("enable_shift_parking", true);
p.pull_over_sampling_num = dp("pull_over_sampling_num", 4);
p.maximum_lateral_jerk = dp("maximum_lateral_jerk", 3.0);
p.minimum_lateral_jerk = dp("minimum_lateral_jerk", 1.0);
p.deceleration_interval = dp("deceleration_interval", 10.0);
p.pull_over_velocity = dp("pull_over_velocity", 8.3);
p.pull_over_minimum_velocity = dp("pull_over_minimum_velocity", 0.3);
p.maximum_deceleration = dp("maximum_deceleration", 1.0);
p.after_pull_over_straight_distance = dp("after_pull_over_straight_distance", 3.0);
p.before_pull_over_straight_distance = dp("before_pull_over_straight_distance", 3.0);
// parallel parking
p.enable_arc_forward_parking = dp("enable_arc_forward_parking", true);
p.enable_arc_backward_parking = dp("enable_arc_backward_parking", false);
p.after_forward_parking_straight_distance = dp("after_forward_parking_straight_distance", 0.5);
p.after_backward_parking_straight_distance = dp("after_backward_parking_straight_distance", 0.5);
p.forward_parking_velocity = dp("forward_parking_velocity", 1.0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ ParallelParkingParameters PullOverModule::getGeometricPullOutParameters() const
params.backward_parking_lane_departure_margin =
parameters_.backward_parking_lane_departure_margin;
params.arc_path_interval = parameters_.arc_path_interval;
params.max_deceleration = parameters_.max_deceleration;
params.maximum_deceleration = parameters_.maximum_deceleration;
params.max_steer_rad = parameters_.max_steer_rad;

return params;
Expand Down Expand Up @@ -334,7 +334,7 @@ bool PullOverModule::isLongEnoughToParkingStart(

const double current_vel = planner_data_->self_odometry->twist.twist.linear.x;
const double current_to_stop_distance =
std::pow(current_vel, 2) / parameters_.max_deceleration / 2;
std::pow(current_vel, 2) / parameters_.maximum_deceleration / 2;

// once stopped, it cannot start again if start_pose is close.
// so need enough distance to restart
Expand Down Expand Up @@ -730,7 +730,7 @@ PathWithLaneId PullOverModule::getStopPath()

const double current_vel = planner_data_->self_odometry->twist.twist.linear.x;
const double current_to_stop_distance =
std::pow(current_vel, 2) / parameters_.max_deceleration / 2;
std::pow(current_vel, 2) / parameters_.maximum_deceleration / 2;
const auto arclength_current_pose =
lanelet::utils::getArcCoordinates(status_.current_lanes, current_pose).length;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ bool GeometricParallelParking::isEnoughDistanceToStart(const Pose & start_pose)

// not enoght to stop with max deceleration
const double current_vel = util::l2Norm(planner_data_->self_odometry->twist.twist.linear);
const double stop_distance = std::pow(current_vel, 2) / parameters_.max_deceleration / 2;
const double stop_distance = std::pow(current_vel, 2) / parameters_.maximum_deceleration / 2;
if (current_to_start.position.x < stop_distance) {
return false;
}
Expand Down

0 comments on commit 2116899

Please sign in to comment.