Skip to content

behavior_velocity_planner sometimes crashes before intersection #1247

Closed
@VRichardJP

Description

Checklist

  • I've read the contribution guidelines.
  • I've searched other issues and no duplicate issues were found.
  • I'm convinced that this is not my fault but a bug.

Description

Yesterday, during test drive on private site, I observed behavior_velocity_planner crashes often when approaching an intersection. The crash cause is always an out-of-bound access input_path.points.at(stop_line_idx) here:

setDistance(tier4_autoware_utils::calcSignedArcLength(
input_path.points, planner_data_->current_pose.pose.position,
input_path.points.at(stop_line_idx).point.pose.position));

Expected behavior

No crash

Actual behavior

crash

Steps to reproduce

  1. Run behavior_velocity_planner on a lanelet map with intersections (manual driving is ok, simulator maybe too)

Versions

  • Ubuntu 20.04
  • galactic
  • private fork of main

Possible causes

To dig further, I recompiled behavior_velocity_planner module in Debug mode and ran it with gdb. Here is the full backtrace when the crash occurs:

[New Thread 0x7fff9907c700 (LWP 702884)]
[Thread 0x7fff9907c700 (LWP 702884) exited]
[INFO] [1657025745.719852065] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: ===== plan end =====
[INFO] [1657025745.720560310] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: ===== plan start =====
[INFO] [1657025745.720761729] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: lane_id = 764, state = GO
[INFO] [1657025745.723838402] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: stop line line is at path[0], ignore planning.
[INFO] [1657025745.723862781] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: ===== plan end =====
[INFO] [1657025745.724849081] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: ===== plan start =====
[INFO] [1657025745.725049964] [planning.scenario_planning.lane_driving.behavior_planning.behavior_velocity_planner.intersection_module]: lane_id = 765, state = GO
terminate called after throwing an instance of 'std::out_of_range'
  what():  vector::_M_range_check: __n (which is 81) >= this->size() (which is 81)
--Type <RET> for more, q to quit, c to continue without paging--

Thread 10 "component_conta" received signal SIGABRT, Aborted.
[Switching to Thread 0x7fffe67fc700 (LWP 700468)]
__GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
50	../sysdeps/unix/sysv/linux/raise.c: No such file or directory.
(gdb) bt
#0  __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
#1  0x00007ffff793f859 in __GI_abort () at abort.c:79
#2  0x00007ffff7bca911 in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#3  0x00007ffff7bd638c in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#4  0x00007ffff7bd63f7 in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#5  0x00007ffff7bd66a9 in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#6  0x00007ffff7bcd3ab in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#7  0x00007fffca949fb4 in std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId_<std::allocator<void> >, std::allocator<autoware_auto_planning_msgs::msg::PathPointWithLaneId_<std::allocator<void> > > >::_M_range_check(unsigned long) const (this=0x7fffe67f8838, __n=81)
    at /usr/include/c++/9/bits/stl_vector.h:1070
#8  0x00007fffca95540f in std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId_<std::allocator<void> >, std::allocator<autoware_auto_planning_msgs::msg::PathPointWithLaneId_<std::allocator<void> > > >::at(unsigned long) const
    (this=0x7fffe67f8838, __n=81) at /usr/include/c++/9/bits/stl_vector.h:1109
#9  0x00007fffcaac6666 in behavior_velocity_planner::IntersectionModule::modifyPathVelocity(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*, tier4_planning_msgs::msg::StopReason_<std::allocator<void> >*)
    (this=0x7fffb40320a0, path=0x7fffe67f9540, stop_reason=0x7fffe67f9200)
    at /home/sig/autoware/src/universe/autoware.universe/planning/behavior_velocity_planner/src/scene_module/intersection/scene_intersection.cpp:189
#10 0x00007fffca978653 in behavior_velocity_planner::SceneModuleManagerInterface--Type <RET> for more, q to quit, c to continue without paging--
::modifyPathVelocity(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*) (this=0x5555555bd070, path=0x7fffe67f9540)
    at /home/sig/autoware/src/universe/autoware.universe/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp:162
#11 0x00007fffca9795c4 in behavior_velocity_planner::SceneModuleManagerInterfaceWithRTC::plan(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*) (this=0x5555555bd070, path=0x7fffe67f9540)
    at /home/sig/autoware/src/universe/autoware.universe/planning/behavior_velocity_planner/include/scene_module/scene_module_interface.hpp:263
#12 0x00007fffca937e2d in behavior_velocity_planner::BehaviorVelocityPlannerManager::planPathVelocity(std::shared_ptr<behavior_velocity_planner::PlannerData const> const&, autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)
    (this=0x7fffb05dc7d0, planner_data=std::shared_ptr<const struct behavior_velocity_planner::PlannerData> (use count 12, weak count 0) = {...}, input_path_msg=...)
    at /home/sig/autoware/src/universe/autoware.universe/planning/behavior_velocity_planner/src/planner_manager.cpp:69
#13 0x00007fffca6f73d1 in behavior_velocity_planner::BehaviorVelocityPlannerNode::onTrigger(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)
    (this=0x7fffb05dbd60, input_path_msg=std::shared_ptr<const struct autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >> (use count 4, we--Type <RET> for more, q to quit, c to continue without paging--
ak count 0) = {...})
    at /home/sig/autoware/src/universe/autoware.universe/planning/behavior_velocity_planner/src/node.cpp:402
#14 0x00007fffca7d0e4f in std::__invoke_impl<void, void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*&)(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>), behavior_velocity_planner::BehaviorVelocityPlannerNode*&, std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const> >(std::__invoke_memfun_deref, void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*&)(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>), behavior_velocity_planner::BehaviorVelocityPlannerNode*&, std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>&&)
    (__f=
    @0x7fffb067b4f0: (void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*)(class behavior_velocity_planner::BehaviorVelocityPlannerNode * const, class std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)) 0x7fffca6f7178 <behavior_velocity_planner::BehaviorVelocityPlannerNode::onTrigger(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>, __t=@0x7fffb067b500: 0x7fffb05dbd60)
    at /usr/include/c++/9/bits/invoke.h:73
#15 0x00007fffca7c160f in std::__invoke<void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*&)(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>), behavior_velocity_planner::BehaviorV--Type <RET> for more, q to quit, c to continue without paging--
elocityPlannerNode*&, std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const> >(void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*&)(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>), behavior_velocity_planner::BehaviorVelocityPlannerNode*&, std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>&&) (__fn=
    @0x7fffb067b4f0: (void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*)(class behavior_velocity_planner::BehaviorVelocityPlannerNode * const, class std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)) 0x7fffca6f7178 <behavior_velocity_planner::BehaviorVelocityPlannerNode::onTrigger(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>)
    at /usr/include/c++/9/bits/invoke.h:95
#16 0x00007fffca7b215a in std::_Bind<void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*(behavior_velocity_planner::BehaviorVelocityPlannerNode*, std::_Placeholder<1>))(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>::__call<void, std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>&&, 0ul, 1ul>(std::tuple<std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>&&>&&, std::_Index_tuple<0ul, 1ul>)
    (this=0x7fffb067b4f0, __args=...) at /usr/include/c++/9/functional:400
#17 0x00007fffca79fd20 in std::_Bind<void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*(behavior_velocity_planner::BehaviorVelocityPlannerNode*, st--Type <RET> for more, q to quit, c to continue without paging--
d::_Placeholder<1>))(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>::operator()<std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>, void>(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>&&) (this=0x7fffb067b4f0) at /usr/include/c++/9/functional:484
#18 0x00007fffca7802d9 in std::_Function_handler<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>), std::_Bind<void (behavior_velocity_planner::BehaviorVelocityPlannerNode::*(behavior_velocity_planner::BehaviorVelocityPlannerNode*, std::_Placeholder<1>))(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)> >::_M_invoke(std::_Any_data const&, std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>&&)
    (__functor=..., __args#0=...) at /usr/include/c++/9/bits/std_function.h:300
#19 0x00007fffca90a13f in std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>::operator()(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>) const
    (this=0x7fffb067a6b0, __args#0=std::shared_ptr<const struct autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >> (empty) = {...})
    at /usr/include/c++/9/bits/std_function.h:688
#20 0x00007fffca8e47c5 in rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allo--Type <RET> for more, q to quit, c to continue without paging--
cator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}::operator()<std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>&>(std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>&) const (this=0x7fffe67fa320, callback=...)
    at /opt/ros/galactic/include/rclcpp/any_subscription_callback.hpp:255
#21 0x00007fffca915ed9 in std::__invoke_impl<void, rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>&>(std::__invoke_other, rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>)>&)
    (__f=...) at /usr/include/c++/9/bits/invoke.h:60
#22 0x00007fffca90a182 in std::__invoke<rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWith--Type <RET> for more, q to quit, c to continue without paging--
LaneId_<std::allocator<void> > const>)>&>(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, (std::__invoke_result&&)...) (__fn=...)
    at /usr/include/c++/9/bits/invoke.h:95
#23 0x00007fffca8e4850 in std::__detail::__variant::__gen_vtable_impl<true, std::__detail::__variant::_Multi_array<void (*)(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId--Type <RET> for more, q to quit, c to continue without paging--
_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&)>, std::tuple<std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_--Type <RET> for more, q to quit, c to continue without paging--
<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> > >, std::integer_sequence<unsigned long, 4ul> >::__visit_invoke_impl(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<--Type <RET> for more, q to quit, c to continue without paging--
void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >)
    (__visitor=..., __vars#0=std::variant<> [no contained value])
    at /usr/include/c++/9/variant:981
#24 0x00007fffca8e4893 in std::__detail::__variant::__gen_vtable_impl<true, std::__detail::__variant::_Multi_array<void (*)(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::P--Type <RET> for more, q to quit, c to continue without paging--
athWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&)>, std::tuple<std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo --Type <RET> for more, q to quit, c to continue without paging--
const&)> > >, std::integer_sequence<unsigned long, 4ul> >::__do_visit_invoke(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >)
--Type <RET> for more, q to quit, c to continue without paging--
    (__visitor=..., __vars#0=std::variant<> [no contained value])
    at /usr/include/c++/9/variant:989
#25 0x00007fffca8e48d6 in std::__detail::__variant::__gen_vtable_impl<true, std::__detail::__variant::_Multi_array<void (*)(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_plan--Type <RET> for more, q to quit, c to continue without paging--
ning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&)>, std::tuple<std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> > >, std::integer_sequence<unsigned long, 4ul> >::__visit_invoke(rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std:--Type <RET> for more, q to quit, c to continue without paging--
:allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >)
    (__visitor=..., __vars#0=std::variant<> [no contained value])
    at /usr/include/c++/9/variant:1005
--Type <RET> for more, q to quit, c to continue without paging--
#26 0x00007fffca8e515d in std::__do_visit<false, true, rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&>(rclcpp::AnySubscriptionCall--Type <RET> for more, q to quit, c to continue without paging--
back<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&) (__visitor=...)
    at /usr/include/c++/9/variant:1652
--Type <RET> for more, q to quit, c to continue without paging--
#27 0x00007fffca8e51be in std::visit<rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&>(rclcpp::AnySubscriptionCallback<autoware_auto--Type <RET> for more, q to quit, c to continue without paging--
_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)::{lambda(auto:1&&)#1}&&, std::variant<std::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&)>, std::variant<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const, rclcpp::MessageInfo const&)>, std::variant<void (std::unique_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > > >)>, std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<std::function>)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, rclcpp::MessageInfo const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const&)>, std::variant<void (std::variant<void (std::default_delete<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> const, rclcpp::MessageInfo const&)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::variant<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)> >&) (__visitor=...)
    at /usr/include/c++/9/variant:1663
--Type <RET> for more, q to quit, c to continue without paging--
#28 0x00007fffca8e5297 in rclcpp::AnySubscriptionCallback<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)
    (this=0x7fffb067a6b0, message=std::shared_ptr<struct autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >> (use count 4, weak count 0) = {...}, message_info=...)
    at /opt/ros/galactic/include/rclcpp/any_subscription_callback.hpp:238
#29 0x00007fffca8ca38f in rclcpp::Subscription<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void> > >::handle_message(std::shared_ptr<void>&, rclcpp::MessageInfo const&)
    (this=0x7fffb067a5d0, message=std::shared_ptr<void> (use count 4, weak count 0) = {...}, message_info=...)
    at /opt/ros/galactic/include/rclcpp/subscription.hpp:284
#30 0x00007ffff7e6c014 in  () at /opt/ros/galactic/lib/librclcpp.so
#31 0x00007ffff7e6c8e4 in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () at /opt/ros/galactic/lib/librclcpp.so
#32 0x00007ffff7e6d015 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () at /opt/ros/galactic/lib/librclcpp.so
#33 0x00007ffff7e734bb in rclcpp::executors::MultiThreadedExecutor::run(unsigned long) () at /opt/ros/galactic/lib/librclcpp.so
--Type <RET> for more, q to quit, c to continue without paging--
#34 0x00007ffff7c02de4 in  () at /lib/x86_64-linux-gnu/libstdc++.so.6
#35 0x00007ffff787b609 in start_thread (arg=<optimized out>)
    at pthread_create.c:477
#36 0x00007ffff7a3c133 in clone ()
    at ../sysdeps/unix/sysv/linux/x86_64/clone.S:9

The problem is obvious when the you look at the variable state:

  • stop_line_idx is 81
  • input_path, which is a copy of original path, has 81 points (so input_path.at(stop_line_idx) is out-of-bound)
  • path, which has been modified, has now 82 points
(gdb) p stop_line_idx
$1 = 81
(gdb) p input_path
$2 = {header = {stamp = {sec = 1657025745, nanosec = 378799051}, 
    frame_id = "map"}, points = std::vector of length 81, capacity 81 = {{
      point = {pose = {position = {x = 75667.275612449826, 
            y = 31099.669794013098, z = 4.1541047011132282}, orientation = {
            x = 0, y = 0, z = 0.6809399879432364, w = 0.73233921977446015}}, 
        longitudinal_velocity_mps = 4.16666651, lateral_velocity_mps = 0, 
        heading_rate_rps = 0, is_final = false}, 
      lane_ids = std::vector of length 1, capacity 1 = {767}}, {point = {
        pose = {position = {x = 75667.397233333337, y = 31101.339633333337, 
            z = 4.1439500000000002}, orientation = {x = 0, y = 0, 
            z = 0.68093998794346955, w = 0.73233921977424343}}, 
        longitudinal_velocity_mps = 4.16666651, lateral_velocity_mps = 0, 
        heading_rate_rps = 0, is_final = false}, 
      lane_ids = std::vector of length 1, capacity 1 = {767}}, {point = {
        pose = {position = {x = 75667.698449999996, y = 31105.475299999998, 
            z = 4.1188000000000002}, orientation = {x = 0, y = 0, 
            z = 0.6782572080599496, w = 0.734824577511342}}, 
        longitudinal_velocity_mps = 4.16666651, lateral_velocity_mps = 0, 
        heading_rate_rps = 0, is_final = false}, 
      lane_ids = std::vector of length 2, capacity 2 = {767, 764}}, {point = {
        pose = {position = {x = 75668.044550000006, y = 31109.791250000002, 
            z = 4.1712749999999996}, orientation = {x = 0, y = 0, 
            z = 0.678257208062362, w = 0.73482457750911534}}, 
--Type <RET> for more, q to quit, c to continue without paging--q
Quit
(gdb) p input_path.points.size()
$3 = 81
(gdb) p path
$4 = (autoware_auto_planning_msgs::msg::PathWithLaneId *) 0x7fffe67f9540
(gdb) p *path
$5 = {header = {stamp = {sec = 1657025745, nanosec = 378799051}, 
    frame_id = "map"}, points = std::vector of length 82, capacity 146 = {{
      point = {pose = {position = {x = 75667.275612449826, 
            y = 31099.669794013098, z = 4.1541047011132282}, orientation = {
            x = 0, y = 0, z = 0.6809399879432364, w = 0.73233921977446015}}, 
        longitudinal_velocity_mps = 4.16666651, lateral_velocity_mps = 0, 
        heading_rate_rps = 0, is_final = false}, 
      lane_ids = std::vector of length 1, capacity 1 = {767}}, {point = {
        pose = {position = {x = 75667.397233333337, y = 31101.339633333337, 
            z = 4.1439500000000002}, orientation = {x = 0, y = 0, 
            z = 0.68093998794346955, w = 0.73233921977424343}}, 
        longitudinal_velocity_mps = 4.16666651, lateral_velocity_mps = 0, 
        heading_rate_rps = 0, is_final = false}, 
      lane_ids = std::vector of length 1, capacity 1 = {767}}, {point = {
        pose = {position = {x = 75667.698449999996, y = 31105.475299999998, 
            z = 4.1188000000000002}, orientation = {x = 0, y = 0, 
            z = 0.6782572080599496, w = 0.734824577511342}}, 
        longitudinal_velocity_mps = 4.16666651, lateral_velocity_mps = 0, 
        heading_rate_rps = 0, is_final = false}, 
      lane_ids = std::vector of length 2, capacity 2 = {767, 764}}, {point = {
        pose = {position = {x = 75668.044550000006, y = 31109.791250000002, 
            z = 4.1712749999999996}, orientation = {x = 0, y = 0, 
            z = 0.678257208062362, w = 0.73482457750911534}}, 
--Type <RET> for more, q to quit, c to continue without paging--q
Quit
(gdb) p path->points.size()
$6 = 82
(gdb) 

The stop_line_idx is initialized here, and seems to be only suited for path and not input_path:

if (!util::generateStopLine(
lane_id_, conflicting_areas, planner_data_, planner_param_.stop_line_margin, path, *path,
&stop_line_idx, &pass_judge_line_idx, &first_idx_inside_lane, logger_.get_child("util"))) {
RCLCPP_WARN_SKIPFIRST_THROTTLE(logger_, *clock_, 1000 /* ms */, "setStopLineIdx fail");
RCLCPP_DEBUG(logger_, "===== plan end =====");
return false;
}

A simple fix is to get rid of input_path and replace it by path, however I am not sure it is the correct solution. The code logic is beyond my understanding.

Additional context

No response

Metadata

Assignees

Labels

priority:highHigh urgency and importance.type:bugSoftware flaws or errors.

Type

No type

Projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions