@@ -34,87 +34,25 @@ int insertSafeVelocityToPath(
34
34
const geometry_msgs::msg::Pose & in_pose, const double safe_vel, const PlannerParam & param,
35
35
PathWithLaneId * inout_path);
36
36
37
- // @brief calculates the maximum velocity allowing to decelerate within the given distance
38
- inline double calculateMinSlowDownVelocity (
39
- const double v0, const double len, const double a_max, const double safe_vel)
40
- {
41
- // if target velocity is inserted backward return current velocity as limit
42
- if (len < 0 ) return safe_vel;
43
- return std::sqrt (std::max (std::pow (v0, 2.0 ) - 2.0 * std::abs (a_max) * len, 0.0 ));
44
- }
45
-
46
37
/* *
47
38
*
48
39
* @param: longitudinal_distance: longitudinal distance to collision
49
40
* @param: param: planner param
50
41
* @return lateral distance
51
42
**/
52
- inline double calculateLateralDistanceFromTTC (
53
- const double longitudinal_distance, const PlannerParam & param)
54
- {
55
- const auto & v = param.v ;
56
- const auto & p = param;
57
- double v_min = 1.0 ;
58
- const double lateral_buffer = 0.5 ;
59
- const double min_distance = p.half_vehicle_width + lateral_buffer;
60
- const double max_distance = p.detection_area .max_lateral_distance ;
61
- if (longitudinal_distance <= 0 ) return min_distance;
62
- if (v_min < param.v .min_allowed_velocity ) v_min = param.v .min_allowed_velocity ;
63
- // use min velocity if ego velocity is below min allowed
64
- const double v0 = (v.v_ego > v_min) ? v.v_ego : v_min;
65
- // here is a part where ego t(ttc) can be replaced by calculation of velocity smoother or ?
66
- double t = longitudinal_distance / v0;
67
- double lateral_distance = t * param.pedestrian_vel + p.half_vehicle_width ;
68
- return std::min (max_distance, std::max (min_distance, lateral_distance));
69
- }
43
+ double calculateLateralDistanceFromTTC (
44
+ const double longitudinal_distance, const PlannerParam & param);
70
45
71
46
/* *
72
47
* @param: v: ego velocity config
73
48
* @param: ttc: time to collision
74
49
* @return safe motion
75
50
**/
76
- inline SafeMotion calculateSafeMotion (const Velocity & v, const double ttc)
77
- {
78
- SafeMotion sm;
79
- const double j_max = v.safety_ratio * v.max_stop_jerk ;
80
- const double a_max = v.safety_ratio * v.max_stop_accel ;
81
- const double t1 = v.delay_time ;
82
- double t2 = a_max / j_max;
83
- double & v_safe = sm.safe_velocity ;
84
- double & stop_dist = sm.stop_dist ;
85
- if (ttc <= t1) {
86
- // delay
87
- v_safe = 0 ;
88
- stop_dist = 0 ;
89
- } else if (ttc <= t2 + t1) {
90
- // delay + const jerk
91
- t2 = ttc - t1;
92
- v_safe = -0.5 * j_max * t2 * t2;
93
- stop_dist = v_safe * t1 - j_max * t2 * t2 * t2 / 6 ;
94
- } else {
95
- const double t3 = ttc - t2 - t1;
96
- // delay + const jerk + const accel
97
- const double v2 = -0.5 * j_max * t2 * t2;
98
- v_safe = v2 - a_max * t3;
99
- stop_dist = v_safe * t1 - j_max * t2 * t2 * t2 / 6 + v2 * t3 - 0.5 * a_max * t3 * t3;
100
- }
101
- stop_dist += v.safe_margin ;
102
- return sm;
103
- }
51
+ SafeMotion calculateSafeMotion (const Velocity & v, const double ttc);
104
52
105
- inline double calculateInsertVelocity (
53
+ double calculateInsertVelocity (
106
54
const double min_allowed_vel, const double safe_vel, const double min_vel,
107
- const double original_vel)
108
- {
109
- const double max_vel_noise = 0.05 ;
110
- // ensure safe velocity doesn't exceed maximum allowed pbs deceleration
111
- double cmp_safe_vel = std::max (min_allowed_vel + max_vel_noise, safe_vel);
112
- // ensure safe path velocity is also above ego min velocity
113
- cmp_safe_vel = std::max (cmp_safe_vel, min_vel);
114
- // ensure we only lower the original velocity (and do not increase it)
115
- cmp_safe_vel = std::min (cmp_safe_vel, original_vel);
116
- return cmp_safe_vel;
117
- }
55
+ const double original_vel);
118
56
119
57
} // namespace occlusion_spot_utils
120
58
} // namespace behavior_velocity_planner
0 commit comments