Skip to content

Commit 6ded065

Browse files
authored
refactor(behavior_velocity): move inline functions to cpp and remove unused (#462)
Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
1 parent e5ae6ae commit 6ded065

File tree

6 files changed

+120
-136
lines changed

6 files changed

+120
-136
lines changed

planning/behavior_velocity_planner/include/scene_module/occlusion_spot/occlusion_spot_utils.hpp

+6-52
Original file line numberDiff line numberDiff line change
@@ -179,60 +179,14 @@ struct PossibleCollisionInfo
179179

180180
lanelet::ConstLanelet toPathLanelet(const PathWithLaneId & path);
181181
// Note : consider offset_from_start_to_ego and safety margin for collision here
182-
inline void handleCollisionOffset(
183-
std::vector<PossibleCollisionInfo> & possible_collisions, double offset, double margin)
184-
{
185-
for (auto & pc : possible_collisions) {
186-
pc.arc_lane_dist_at_collision.length -= offset;
187-
pc.arc_lane_dist_at_collision.length -= margin;
188-
}
189-
}
190-
191-
inline double offsetFromStartToEgo(
192-
const PathWithLaneId & path, const Pose & ego_pose, const int closest_idx)
193-
{
194-
double offset_from_ego_to_closest = 0;
195-
for (int i = 0; i < closest_idx; i++) {
196-
const auto & curr_p = path.points.at(i).point.pose.position;
197-
const auto & next_p = path.points.at(i + 1).point.pose.position;
198-
offset_from_ego_to_closest += tier4_autoware_utils::calcDistance2d(curr_p, next_p);
199-
}
200-
const double offset_from_closest_to_target =
201-
-planning_utils::transformRelCoordinate2D(ego_pose, path.points[closest_idx].point.pose)
202-
.position.x;
203-
return offset_from_ego_to_closest + offset_from_closest_to_target;
204-
}
205-
206-
inline void clipPathByLength(
207-
const PathWithLaneId & path, PathWithLaneId & clipped, const double max_length = 100.0)
208-
{
209-
double length_sum = 0;
210-
for (int i = 0; i < static_cast<int>(path.points.size()) - 1; i++) {
211-
length_sum += tier4_autoware_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1));
212-
if (length_sum > max_length) return;
213-
clipped.points.emplace_back(path.points.at(i));
214-
}
215-
}
216-
217-
inline bool isStuckVehicle(PredictedObject obj, const double min_vel)
218-
{
219-
if (
220-
obj.classification.at(0).label == ObjectClassification::CAR ||
221-
obj.classification.at(0).label == ObjectClassification::TRUCK ||
222-
obj.classification.at(0).label == ObjectClassification::BUS) {
223-
if (std::abs(obj.kinematics.initial_twist_with_covariance.twist.linear.x) < min_vel) {
224-
return true;
225-
}
226-
}
227-
return false;
228-
}
229-
void filterCollisionByRoadType(
230-
std::vector<PossibleCollisionInfo> & possible_collisions, const DetectionAreaIdx road_type);
182+
void handleCollisionOffset(std::vector<PossibleCollisionInfo> & possible_collisions, double offset);
183+
void clipPathByLength(
184+
const PathWithLaneId & path, PathWithLaneId & clipped, const double max_length = 100.0);
185+
bool isStuckVehicle(PredictedObject obj, const double min_vel);
186+
double offsetFromStartToEgo(
187+
const PathWithLaneId & path, const Pose & ego_pose, const int closest_idx);
231188
std::vector<PredictedObject> filterDynamicObjectByDetectionArea(
232189
std::vector<PredictedObject> & objs, const std::vector<Slice> polys);
233-
bool splineInterpolate(
234-
const PathWithLaneId & input, const double interval, PathWithLaneId * output,
235-
const rclcpp::Logger logger);
236190
std::vector<PredictedObject> getParkedVehicles(
237191
const PredictedObjects & dyn_objects, const PlannerParam & param,
238192
std::vector<Point> & debug_point);

planning/behavior_velocity_planner/include/scene_module/occlusion_spot/risk_predictive_braking.hpp

+5-67
Original file line numberDiff line numberDiff line change
@@ -34,87 +34,25 @@ int insertSafeVelocityToPath(
3434
const geometry_msgs::msg::Pose & in_pose, const double safe_vel, const PlannerParam & param,
3535
PathWithLaneId * inout_path);
3636

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-
4637
/**
4738
*
4839
* @param: longitudinal_distance: longitudinal distance to collision
4940
* @param: param: planner param
5041
* @return lateral distance
5142
**/
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);
7045

7146
/**
7247
* @param: v: ego velocity config
7348
* @param: ttc: time to collision
7449
* @return safe motion
7550
**/
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);
10452

105-
inline double calculateInsertVelocity(
53+
double calculateInsertVelocity(
10654
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);
11856

11957
} // namespace occlusion_spot_utils
12058
} // namespace behavior_velocity_planner

planning/behavior_velocity_planner/src/scene_module/occlusion_spot/occlusion_spot_utils.cpp

+46-15
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,52 @@ void calcSlowDownPointsForPossibleCollision(
146146
}
147147
}
148148

149+
void handleCollisionOffset(std::vector<PossibleCollisionInfo> & possible_collisions, double offset)
150+
{
151+
for (auto & pc : possible_collisions) {
152+
pc.arc_lane_dist_at_collision.length -= offset;
153+
}
154+
}
155+
156+
void clipPathByLength(
157+
const PathWithLaneId & path, PathWithLaneId & clipped, const double max_length)
158+
{
159+
double length_sum = 0;
160+
for (int i = 0; i < static_cast<int>(path.points.size()) - 1; i++) {
161+
length_sum += tier4_autoware_utils::calcDistance2d(path.points.at(i), path.points.at(i + 1));
162+
if (length_sum > max_length) return;
163+
clipped.points.emplace_back(path.points.at(i));
164+
}
165+
}
166+
167+
bool isStuckVehicle(PredictedObject obj, const double min_vel)
168+
{
169+
if (
170+
obj.classification.at(0).label == ObjectClassification::CAR ||
171+
obj.classification.at(0).label == ObjectClassification::TRUCK ||
172+
obj.classification.at(0).label == ObjectClassification::BUS) {
173+
if (std::abs(obj.kinematics.initial_twist_with_covariance.twist.linear.x) < min_vel) {
174+
return true;
175+
}
176+
}
177+
return false;
178+
}
179+
180+
double offsetFromStartToEgo(
181+
const PathWithLaneId & path, const Pose & ego_pose, const int closest_idx)
182+
{
183+
double offset_from_ego_to_closest = 0;
184+
for (int i = 0; i < closest_idx; i++) {
185+
const auto & curr_p = path.points.at(i).point.pose.position;
186+
const auto & next_p = path.points.at(i + 1).point.pose.position;
187+
offset_from_ego_to_closest += tier4_autoware_utils::calcDistance2d(curr_p, next_p);
188+
}
189+
const double offset_from_closest_to_target =
190+
-planning_utils::transformRelCoordinate2D(ego_pose, path.points[closest_idx].point.pose)
191+
.position.x;
192+
return offset_from_ego_to_closest + offset_from_closest_to_target;
193+
}
194+
149195
std::vector<PredictedObject> getParkedVehicles(
150196
const PredictedObjects & dyn_objects, const PlannerParam & param,
151197
std::vector<Point> & debug_point)
@@ -337,21 +383,6 @@ std::vector<PredictedObject> filterDynamicObjectByDetectionArea(
337383
return filtered_obj;
338384
}
339385

340-
void filterCollisionByRoadType(
341-
std::vector<PossibleCollisionInfo> & possible_collisions, const DetectionAreaIdx area)
342-
{
343-
std::pair<int, int> focus_length = area.get();
344-
for (auto it = possible_collisions.begin(); it != possible_collisions.end();) {
345-
const auto & pc_len = it->arc_lane_dist_at_collision.length;
346-
if (focus_length.first < pc_len && pc_len < focus_length.second) {
347-
it++;
348-
} else {
349-
// -----erase-----|start------target-------end|----erase---
350-
it = possible_collisions.erase(it);
351-
}
352-
}
353-
}
354-
355386
void createPossibleCollisionsInDetectionArea(
356387
const std::vector<Slice> & detection_area_polygons,
357388
std::vector<PossibleCollisionInfo> & possible_collisions, const grid_map::GridMap & grid,

planning/behavior_velocity_planner/src/scene_module/occlusion_spot/risk_predictive_braking.cpp

+61
Original file line numberDiff line numberDiff line change
@@ -105,5 +105,66 @@ int insertSafeVelocityToPath(
105105
return 0;
106106
}
107107

108+
double calculateLateralDistanceFromTTC(
109+
const double longitudinal_distance, const PlannerParam & param)
110+
{
111+
const auto & v = param.v;
112+
const auto & p = param;
113+
double v_min = 1.0;
114+
const double lateral_buffer = 0.5;
115+
const double min_distance = p.half_vehicle_width + lateral_buffer;
116+
const double max_distance = p.detection_area.max_lateral_distance;
117+
if (longitudinal_distance <= 0) return min_distance;
118+
if (v_min < param.v.min_allowed_velocity) v_min = param.v.min_allowed_velocity;
119+
// use min velocity if ego velocity is below min allowed
120+
const double v0 = (v.v_ego > v_min) ? v.v_ego : v_min;
121+
// here is a part where ego t(ttc) can be replaced by calculation of velocity smoother or ?
122+
double t = longitudinal_distance / v0;
123+
double lateral_distance = t * param.pedestrian_vel + p.half_vehicle_width;
124+
return std::min(max_distance, std::max(min_distance, lateral_distance));
125+
}
126+
127+
SafeMotion calculateSafeMotion(const Velocity & v, const double ttc)
128+
{
129+
SafeMotion sm;
130+
const double j_max = v.safety_ratio * v.max_stop_jerk;
131+
const double a_max = v.safety_ratio * v.max_stop_accel;
132+
const double t1 = v.delay_time;
133+
double t2 = a_max / j_max;
134+
double & v_safe = sm.safe_velocity;
135+
double & stop_dist = sm.stop_dist;
136+
if (ttc <= t1) {
137+
// delay
138+
v_safe = 0;
139+
stop_dist = 0;
140+
} else if (ttc <= t2 + t1) {
141+
// delay + const jerk
142+
t2 = ttc - t1;
143+
v_safe = -0.5 * j_max * t2 * t2;
144+
stop_dist = v_safe * t1 - j_max * t2 * t2 * t2 / 6;
145+
} else {
146+
const double t3 = ttc - t2 - t1;
147+
// delay + const jerk + const accel
148+
const double v2 = -0.5 * j_max * t2 * t2;
149+
v_safe = v2 - a_max * t3;
150+
stop_dist = v_safe * t1 - j_max * t2 * t2 * t2 / 6 + v2 * t3 - 0.5 * a_max * t3 * t3;
151+
}
152+
stop_dist += v.safe_margin;
153+
return sm;
154+
}
155+
156+
double calculateInsertVelocity(
157+
const double min_allowed_vel, const double safe_vel, const double min_vel,
158+
const double original_vel)
159+
{
160+
const double max_vel_noise = 0.05;
161+
// ensure safe velocity doesn't exceed maximum allowed pbs deceleration
162+
double cmp_safe_vel = std::max(min_allowed_vel + max_vel_noise, safe_vel);
163+
// ensure safe path velocity is also above ego min velocity
164+
cmp_safe_vel = std::max(cmp_safe_vel, min_vel);
165+
// ensure we only lower the original velocity (and do not increase it)
166+
cmp_safe_vel = std::min(cmp_safe_vel, original_vel);
167+
return cmp_safe_vel;
168+
}
108169
} // namespace occlusion_spot_utils
109170
} // namespace behavior_velocity_planner

planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ bool OcclusionSpotModule::modifyPathVelocity(
9999
logger_, *clock_, 3000, "num possible collision:" << possible_collisions.size());
100100
utils::calcSlowDownPointsForPossibleCollision(0, interp_path, 0.0, possible_collisions);
101101
// Note: Consider offset from path start to ego here
102-
utils::handleCollisionOffset(possible_collisions, offset_from_start_to_ego, 0.0);
102+
utils::handleCollisionOffset(possible_collisions, offset_from_start_to_ego);
103103
// apply safe velocity using ebs and pbs deceleration
104104
utils::applySafeVelocityConsideringPossibleCollision(path, possible_collisions, param_);
105105
// these debug topics needs computation resource

planning/behavior_velocity_planner/src/scene_module/occlusion_spot/scene_occlusion_spot_in_public_road.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ bool OcclusionSpotInPublicModule::modifyPathVelocity(
9393
interp_path, param_, offset_from_start_to_ego, filtered_obj);
9494
utils::calcSlowDownPointsForPossibleCollision(0, interp_path, 0.0, possible_collisions);
9595
// Note: Consider offset from path start to ego here
96-
utils::handleCollisionOffset(possible_collisions, offset_from_start_to_ego, 0.0);
96+
utils::handleCollisionOffset(possible_collisions, offset_from_start_to_ego);
9797
// apply safe velocity using ebs and pbs deceleration
9898
utils::applySafeVelocityConsideringPossibleCollision(path, possible_collisions, param_);
9999
if (param_.debug) {

0 commit comments

Comments
 (0)