We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 0ec4899 commit a11a691Copy full SHA for a11a691
planning/behavior_velocity_intersection_module/src/object_manager.cpp
@@ -165,7 +165,7 @@ bool ObjectInfo::can_stop_before_ego_lane(
165
const auto stopline_p1 = stopline.front();
166
const auto stopline_p2 = stopline.back();
167
const tier4_autoware_utils::Point2d stopline_mid{
168
- stopline_p1.x() + stopline_p2.x() / 2.0, (stopline_p1.y() + stopline_p2.y()) / 2.0};
+ (stopline_p1.x() + stopline_p2.x()) / 2.0, (stopline_p1.y() + stopline_p2.y()) / 2.0};
169
const auto attention_lane_end = attention_lanelet.centerline().back();
170
const tier4_autoware_utils::LineString2d attention_lane_later_part(
171
{tier4_autoware_utils::Point2d{stopline_mid.x(), stopline_mid.y()},
0 commit comments