autowarefoundation / autoware.universe

https://autowarefoundation.github.io/autoware.universe/
Apache License 2.0
882 stars 570 forks source link

`behavior_planning_container` dies from the start of the driving #5657

Closed Kim-mins closed 4 months ago

Kim-mins commented 7 months ago

Checklist

Description

Hi team, I'm currently running Autoware on Carla, and I found the behavior_planning_container dies from the the start of the driving sometimes. Here are the videos for better description: [video: rviz] [video: frontview]

According to the [launch.log] file, I could see the log below regarding the error from behavior_planning_container module:

1700705716.2011483 [ERROR] [component_container_mt-60]: process has died [pid 6806, exit code -11, cmd '/opt/ros/humble/lib/rclcpp_components/component_container_mt --ros-args -r __node:=behavior_planning_container -r __ns:=/planning/scenario_planning/lane_driving/behavior_planning -p use_sim_time:=True -p wheel_radius:=0.383 -p wheel_width:=0.235 -p wheel_base:=2.79 -p wheel_tread:=1.64 -p front_overhang:=1.0 -p rear_overhang:=1.1 -p left_overhang:=0.128 -p right_overhang:=0.128 -p vehicle_height:=2.5 -p max_steer_angle:=0.7'].

Expected behavior

I expect the ego vehicle to make proper trajectory continuously.

Actual behavior

The car cannot plan the trajectory due to the error.

Steps to reproduce

From docker image [ghcr.io/autowarefoundation/autoware-universe:humble-20230715-prebuilt-cuda-amd64], I ran Autoware and replayed the situation with the [rosbag file] (It may requires ros2 bag reindex <bag file> before the replay)

Versions

Possible causes

I cannot pinpoint the error location, but it seems the error is from behavior_planning_container according to the launch.log file above.

Additional context

No response

VRichardJP commented 7 months ago

A simple way to dig more information is to start the container with gdb and see where it crashes.

Until recently the behavior planner launch was python based and you could do this:

    container = ComposableNodeContainer(
        name="behavior_planning_container",
        namespace="",
        package="rclcpp_components",
        executable=LaunchConfiguration("container_executable"),
        composable_node_descriptions=[
            behavior_path_planner_component,
            behavior_velocity_planner_component,
            glog_component,
        ],
        output="screen",
        prefix="gnome-terminal -- gdb -ex=run --args",  # << add this line
    )

If you updated the code recently, it is possible you only have this xml launch file:

https://github.com/autowarefoundation/autoware.universe/blob/c171d1c80c13d64da73e5cdf9c81c19df5d29e95/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml#L114C4-L114C18

To which you can add launch_prefix="gnome-terminal -- gdb -ex=run --args" to the node_container (or maybe just prefix=..., I am not so sure about the node_container syntax)

Kim-mins commented 7 months ago

Thank you for the response @VRichardJP!!

I'm currently running a bit old version now, so I could find the python file and modified it as you told. Here's a new [launch.log] file, but I could not get any detailed information about behavior_path_planner when I replayed the log file. Can another component be the cause of the error? Or should I run the driving again for more log, not just replaying it?

By the way, I could find some logs that can be related to the bug (regarding obstacle_stop_planner, path_smoother and obstacle_avoidance_planner. Can they be the cause?

1700802176.8520107 [component_container_mt-62] [WARN] [1700802176.851752597] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802176.8573928 [component_container_mt-62] [WARN] [1700802176.857080597] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802176.9685121 [component_container_mt-62] [WARN] [1700802176.968224703] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802176.9718113 [component_container_mt-62] [WARN] [1700802176.970929631] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802176.9842675 [component_container_mt-62] [WARN] [1700802176.980416359] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.0556555 [component_container_mt-62] [WARN] [1700802177.040514216] [path_smoother.trajectory_utils]: Fixed point will not be inserted due to the error during calculation.
1700802177.0558257 [component_container_mt-62] [WARN] [1700802177.053943136] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.0979228 [component_container_mt-62] [WARN] [1700802177.097674864] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.1584635 [component_container_mt-62] [WARN] [1700802177.158132562] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.1762669 [component_container_mt-62] [WARN] [1700802177.174972242] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.1784666 [component_container_mt-62] [WARN] [1700802177.178307523] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.1826227 [component_container_mt-62] [WARN] [1700802177.181389454] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.2319012 [component_container_mt-62] [WARN] [1700802177.231623728] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.3735209 [component_container_mt-62] [WARN] [1700802177.372711749] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.3771455 [component_container_mt-62] [WARN] [1700802177.376220058] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.3931603 [component_container_mt-62] [WARN] [1700802177.392943635] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802177.4860768 [component_container_mt-62] [WARN] [1700802177.485826454] [planning.scenario_planning.lane_driving.motion_planning.obstacle_stop_planner]: size of vel que is 0. Something has wrong.
1700802178.8114269 [component_container_mt-62] [WARN] [1700802178.806527287] [obstacle_avoidance_planner.trajectory_utils]: Fixed point will not be inserted due to the error during calculation.
Kim-mins commented 7 months ago

Oh sorry, I just found that I modified another python file. Here's a new [launch.log] file, and I could find logs regarding localization, not behavior_planning_container:

1700803896.3757224 [ndt_scan_matcher-31] [ERROR] [1700803896.367688053] [localization.pose_estimator.ndt_scan_matcher]: Cannot find the reference position for map update. Please check if the EKF odometry is provided to NDT.
1700803896.3763189 [service_log_checker-3] [ERROR] [1700803896.367737108] [system.service_log_checker]: /localization/initialize: status code 1 'The vehicle is not stopped.' (/localization/util/pose_initializer_node)
1700803896.3763847 [service_log_checker-3] [ERROR] [1700803896.367868030] [system.service_log_checker]: /localization/initialize: status code 1 'The vehicle is not stopped.' (/default_ad_api/node/localization)
1700803896.3764348 [service_log_checker-3] [ERROR] [1700803896.368173635] [system.service_log_checker]: /api/localization/initialize: status code 1 'The vehicle is not stopped.' (/default_ad_api/node/localization)
1700803896.3764811 [service_log_checker-3] [ERROR] [1700803896.368353735] [system.service_log_checker]: /api/localization/initialize: status code 1 'The vehicle is not stopped.' (/localization/util/default_ad_api/helpers/automatic_pose_initializer)

And it seems the error message is from [here] and [here]. I cannot sure these errors are relevant to the original error, but I have no more idea for debugging..

VRichardJP commented 7 months ago

With the launch prefix, the behavior planning container should start in a new terminal, like here: https://github.com/autowarefoundation/autoware.universe/issues/5649#issuecomment-1822192857

Be careful that due to default gdb pagination, sometimes the program does not start until you press Enter (you can avoid this by creating a ~/.gdbinit file with set pagination off inside).

Regarding your second issue, either the vehicle is not stopped, or Autoware has not received any velocity feedback from the vehicle (the wording is not clear I know). The simulator should sends this data to /vehicle/velocity_status

Kim-mins commented 7 months ago

Thank you for the kind instruction @VRichardJP!!

Here are the [full log] and the [video] while logging. In the log file, I could observe the message below:

...
Thread 26 "component_conta" received signal SIGSEGV, Segmentation fault.
...

I don't know why but after the segmentation fault occurs, the planner seems not work.

VRichardJP commented 7 months ago

Once the segmentation fault has occured, you should be able to inspect the state of the program with gdb. The first thing to do would be to generate a backtrace with the bt command. Something like this:

Thread 29 "component_conta" received signal SIGABRT, Aborted.
[Switching to Thread 0x7fffcc7f0640 (LWP 31126)]
__pthread_kill_implementation (no_tid=0, signo=6, threadid=140736624264768) at ./nptl/pthread_kill.c:44
44  ./nptl/pthread_kill.c: No such file or directory.
(gdb) bt
#0  __pthread_kill_implementation (no_tid=0, signo=6, threadid=140736624264768) at ./nptl/pthread_kill.c:44
#1  __pthread_kill_internal (signo=6, threadid=140736624264768) at ./nptl/pthread_kill.c:78
#2  __GI___pthread_kill (threadid=140736624264768, signo=signo@entry=6) at ./nptl/pthread_kill.c:89
#3  0x00007ffff7442476 in __GI_raise (sig=sig@entry=6) at ../sysdeps/posix/raise.c:26
#4  0x00007ffff74287f3 in __GI_abort () at ./stdlib/abort.c:79
#5  0x00007ffff78a2b9e in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#6  0x00007ffff78ae20c in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#7  0x00007ffff78ae277 in std::terminate() () from /lib/x86_64-linux-gnu/libstdc++.so.6
#8  0x00007ffff78ae4d8 in __cxa_throw () from /lib/x86_64-linux-gnu/libstdc++.so.6
#9  0x00007fffe4096e65 in ?? () from /opt/ros/humble/lib/x86_64-linux-gnu/liblanelet2_core.so.1
#10 0x00007ffff42d2ee9 in route_handler::RouteHandler::getLaneletsFromId (this=<optimized out>, id=<optimized out>) at /home/computer/autoware/src/universe/autoware.universe/planning/route_handler/src/route_handler.cpp:512
#11 0x00007fffc63463eb in behavior_path_planner::utils::getCurrentLanesFromPath (path=..., planner_data=std::shared_ptr<const behavior_path_planner::PlannerData> (use count 14, weak count 0) = {...}) at /home/computer/autoware/src/universe/autoware.universe/planning/behavior_path_planner/src/utils/utils.cpp:3065
#12 0x00007fffc630a944 in behavior_path_planner::NormalLaneChange::getCurrentLanes (this=0x7fff600217d0) at /home/computer/autoware/src/universe/autoware.universe/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp:406
#13 behavior_path_planner::NormalLaneChange::isLaneChangeRequired (this=0x7fff600217d0) at /home/computer/autoware/src/universe/autoware.universe/planning/behavior_path_planner/src/scene_module/lane_change/normal.cpp:117
#14 0x00007fffc615638a in behavior_path_planner::PlannerManager::getRequestModules (this=0x5555557c4ec0, previous_module_output=...) at /usr/include/c++/11/bits/shared_ptr_base.h:1295
#15 0x00007fffc615e25b in operator() (__closure=0x7fffcc7ee8e0) at /home/computer/autoware/src/universe/autoware.universe/planning/behavior_path_planner/src/planner_manager.cpp:95
#16 0x00007fffc615efc8 in behavior_path_planner::PlannerManager::run (this=this@entry=0x5555557c4ec0, data=std::shared_ptr<behavior_path_planner::PlannerData> (use count 14, weak count 0) = {...}) at /home/computer/autoware/src/universe/autoware.universe/planning/behavior_path_planner/src/planner_manager.cpp:55
#17 0x00007fffc619530e in behavior_path_planner::BehaviorPathPlannerNode::run (this=0x5555556a7490) at /usr/include/c++/11/bits/shared_ptr_base.h:1295
#18 0x00007fffc6199fa5 in std::__invoke_impl<void, void (behavior_path_planner::BehaviorPathPlannerNode::*&)(), behavior_path_planner::BehaviorPathPlannerNode*&> (__t=@0x5555558943c0: 0x5555556a7490, __f=@0x5555558943b0: (void (behavior_path_planner::BehaviorPathPlannerNode::*)(behavior_path_planner::BehaviorPathPlannerNode * const)) 0x7fffc6194ee0 <behavior_path_planner::BehaviorPathPlannerNode::run()>) at /usr/include/c++/11/bits/invoke.h:71
#19 std::__invoke<void (behavior_path_planner::BehaviorPathPlannerNode::*&)(), behavior_path_planner::BehaviorPathPlannerNode*&> (__fn=@0x5555558943b0: (void (behavior_path_planner::BehaviorPathPlannerNode::*)(behavior_path_planner::BehaviorPathPlannerNode * const)) 0x7fffc6194ee0 <behavior_path_planner::BehaviorPathPlannerNode::run()>) at /usr/include/c++/11/bits/invoke.h:96
#20 std::_Bind<void (behavior_path_planner::BehaviorPathPlannerNode::*(behavior_path_planner::BehaviorPathPlannerNode*))()>::__call<void, , 0ul>(std::tuple<>&&, std::_Index_tuple<0ul>) (__args=..., this=0x5555558943b0) at /usr/include/c++/11/functional:420
#21 std::_Bind<void (behavior_path_planner::BehaviorPathPlannerNode::*(behavior_path_planner::BehaviorPathPlannerNode*))()>::operator()<, void>() (this=0x5555558943b0) at /usr/include/c++/11/functional:503
#22 rclcpp::GenericTimer<std::_Bind<void (behavior_path_planner::BehaviorPathPlannerNode::*(behavior_path_planner::BehaviorPathPlannerNode*))()>, (void*)0>::execute_callback_delegate<std::_Bind<void (behavior_path_planner::BehaviorPathPlannerNode::*(behavior_path_planner::BehaviorPathPlannerNode*))()>, (void*)0>() (this=0x555555894380) at /opt/ros/humble/include/rclcpp/rclcpp/timer.hpp:244
#23 rclcpp::GenericTimer<std::_Bind<void (behavior_path_planner::BehaviorPathPlannerNode::*(behavior_path_planner::BehaviorPathPlannerNode*))()>, (void*)0>::execute_callback() (this=0x555555894380) at /opt/ros/humble/include/rclcpp/rclcpp/timer.hpp:230
#24 0x00007ffff7d63472 in rclcpp::Executor::execute_any_executable (this=this@entry=0x5555555d1410, any_exec=...) at /home/computer/autoware/src/rclcpp/rclcpp/src/rclcpp/executor.cpp:518
#25 0x00007ffff7d695ea in rclcpp::executors::MultiThreadedExecutor::run (this=0x5555555d1410, this_thread_number=<optimized out>) at /home/computer/autoware/src/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:93
#26 0x00007ffff78dc253 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#27 0x00007ffff7494ac3 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#28 0x00007ffff7526a40 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81
(gdb) 

This would give a better idea of where your program has crashed (usually the exact line). In your case, the crash is most likely caused by a nullptr dereference, so you may be able to identify it immediately (you can navigate through the backtrace with up and down commands.)

If there are several candidates or if the trace is obfuscated due to optimizations, you could try to recompile the target module without optimization. For example:

colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Debug --packages-select behavior_velocity_planner  # and other crashing modules...

If you can catch the same crash in gdb with debug build, it should be pretty easy to find the cause:

Kim-mins commented 7 months ago

Thank you for the kind response @VRichardJP!!

I checked the gdb terminal again, typed bt and could get the log below:

Thread 22 "component_conta" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffc77fe640 (LWP 7356)]
0x00007fffc05a13f3 in behavior_velocity_planner::IntersectionModule::checkCollision(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&, std::vector<lanelet::ConstLanelet, std::allocator<lanelet::ConstLanelet> > const&, std::vector<lanelet::ConstLanelet, std::allocator<lanelet::ConstLanelet> > const&, std::optional<boost::geometry::model::polygon<tier4_autoware_utils::Point2d, true, true, std::vector, std::vector, std::allocator, std::allocator> > const&, std::vector<lanelet::ConstLanelet, std::allocator<lanelet::ConstLanelet> > const&, int, double) () from /autoware/install/behavior_velocity_intersection_module/lib/libbehavior_velocity_intersection_module.so
(gdb) bt
#0  0x00007fffc05a13f3 in behavior_velocity_planner::IntersectionModule::checkCollision(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&, std::vector<lanelet::ConstLanelet, std::allocator<lanelet::ConstLanelet> > const&, std::vector<lanelet::ConstLanelet, std::allocator<lanelet::ConstLanelet> > const&, std::optional<boost::geometry::model::polygon<tier4_autoware_utils::Point2d, true, true, std::vector, std::vector, std::allocator, std::allocator> > const&, std::vector<lanelet::ConstLanelet, std::allocator<lanelet::ConstLanelet> > const&, int, double) () from /autoware/install/behavior_velocity_intersection_module/lib/libbehavior_velocity_intersection_module.so
#1  0x00007fffc05a7cf0 in behavior_velocity_planner::IntersectionModule::modifyPathVelocityDetail(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*, tier4_planning_msgs::msg::StopReason_<std::allocator<void> >*) () from /autoware/install/behavior_velocity_intersection_module/lib/libbehavior_velocity_intersection_module.so
#2  0x00007fffc05a94a3 in behavior_velocity_planner::IntersectionModule::modifyPathVelocity(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*, tier4_planning_msgs::msg::StopReason_<std::allocator<void> >*) () from /autoware/install/behavior_velocity_intersection_module/lib/libbehavior_velocity_intersection_module.so
#3  0x00007fffc058e6d2 in behavior_velocity_planner::SceneModuleManagerInterface::modifyPathVelocity(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*) () from /autoware/install/behavior_velocity_intersection_module/lib/libbehavior_velocity_intersection_module.so
#4  0x00007fffc056e736 in behavior_velocity_planner::PluginWrapper<behavior_velocity_planner::IntersectionModuleManager>::plan(autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >*) () from /autoware/install/behavior_velocity_intersection_module/lib/libbehavior_velocity_intersection_module.so
#5  0x00007fffc258a73e 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&) () from /autoware/install/behavior_velocity_planner/lib/libbehavior_velocity_planner.so
#6  0x00007fffc24ab4a7 in behavior_velocity_planner::BehaviorVelocityPlannerNode::generatePath(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>, behavior_velocity_planner::PlannerData const&) () from /autoware/install/behavior_velocity_planner/lib/libbehavior_velocity_planner.so
#7  0x00007fffc24ababb in behavior_velocity_planner::BehaviorVelocityPlannerNode::onTrigger(std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const>) () from /autoware/install/behavior_velocity_planner/lib/libbehavior_velocity_planner.so
#8  0x00007fffc24f3f47 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>&&) () from /autoware/install/behavior_velocity_planner/lib/libbehavior_velocity_planner.so
#9  0x00007fffc24f0cc2 in std::__detail::__variant::__gen_vtable_impl<std::__detail::__variant::_Multi_array<std::__detail::__variant::__deduce_visit_result<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::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<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::function<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> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, 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>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&)>, std::integer_sequence<unsigned long, 8ul> >::__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::function<void (autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<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::function<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> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, 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>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&) () from /autoware/install/behavior_velocity_planner/lib/libbehavior_velocity_planner.so
#10 0x00007fffc25739f5 in rclcpp::Subscription<autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, std::allocator<void>, autoware_auto_planning_msgs::msg::PathWithLaneId_<std::allocator<void> >, autoware_auto_planning_msgs::msg::PathWithLaneId_<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&) () from /autoware/install/behavior_velocity_planner/lib/libbehavior_velocity_planner.so
#11 0x00007ffff7e70eac in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () from /opt/ros/humble/lib/librclcpp.so
#12 0x00007ffff7e716af in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () from /opt/ros/humble/lib/librclcpp.so
#13 0x00007ffff7e7890a in rclcpp::executors::MultiThreadedExecutor::run(unsigned long) () from /opt/ros/humble/lib/librclcpp.so
#14 0x00007ffff7bf9253 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#15 0x00007ffff7967ac3 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#16 0x00007ffff79f9a40 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

I'm, currently running prebuilt version of Autoware in docker, and I could not get the error line in gdb directly. Could you please provide me some idea for this?

VRichardJP commented 7 months ago

I don't use the prebuilt docker, but I think the source code should be inside (something like /autoware/src)

If so, you could recompile autoware from a container like this:

$ cd /autoware
$ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Debug --packages-select behavior_velocity_planner behavior_velocity_intersection_module  # maybe add more if necessary or just `--packages-up-to behavior_velocity_planner` instead
$ source install/setup.bash

Then run autoware as you usually do.

The behavior_velocity_planner::IntersectionModule::checkCollision is here:

https://github.com/autowarefoundation/autoware.universe/blob/b50be764537574a35d878fe833e7a5cd7dbdc767/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1482

The function is pretty big so having the exact line would help.

Kim-mins commented 7 months ago

Thank you for the kind instruction @VRichardJP!!

I could finally localize the fault line with gdb by recompiling the Autoware with the option you provided!! Here's the [full log] of gdb, and I think the log below is the most important:

...
Thread 20 "component_conta" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffd2ffd640 (LWP 6019)]
0x00007fff674a0dd4 in Eigen::PlainObjectBase<Eigen::Matrix<double, 2, 1, 0, 2, 1> >::PlainObjectBase (this=0x7fffa40303c0, other=...) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:512
512       : Base(), m_storage(other.m_storage) { }
(gdb) backtrace
#0  0x00007fff674a0dd4 in Eigen::PlainObjectBase<Eigen::Matrix<double, 2, 1, 0, 2, 1> >::PlainObjectBase (this=0x7fffa40303c0, other=...) at /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h:512
#1  0x00007fff67498877 in Eigen::Matrix<double, 2, 1, 0, 2, 1>::Matrix (this=0x7fffa40303c0, other=...) at /usr/include/eigen3/Eigen/src/Core/Matrix.h:414
#2  0x00007fff674a927b in tier4_autoware_utils::Point2d::Point2d (this=0x7fffa40303c0) at /home/mins/autoware/install/tier4_autoware_utils/include/tier4_autoware_utils/geometry/boost_geometry.hpp:53
#3  0x00007fff674ac249 in __gnu_cxx::new_allocator<tier4_autoware_utils::Point2d>::construct<tier4_autoware_utils::Point2d, tier4_autoware_utils::Point2d&> (this=0x7fffd2ff8a80, __p=0x7fffa40303c0) at /usr/include/c++/11/ext/new_allocator.h:162
#4  0x00007fff674a45bb in std::allocator_traits<std::allocator<tier4_autoware_utils::Point2d> >::construct<tier4_autoware_utils::Point2d, tier4_autoware_utils::Point2d&> (__a=..., __p=0x7fffa40303c0) at /usr/include/c++/11/bits/alloc_traits.h:516
#5  0x00007fff674a468f in std::vector<tier4_autoware_utils::Point2d, std::allocator<tier4_autoware_utils::Point2d> >::_M_realloc_insert<tier4_autoware_utils::Point2d&> (this=0x7fffd2ff8a80, __position=non-dereferenceable iterator for std::vector) at /usr/include/c++/11/bits/vector.tcc:449
#6  0x00007fff6749bf0e in std::vector<tier4_autoware_utils::Point2d, std::allocator<tier4_autoware_utils::Point2d> >::emplace_back<tier4_autoware_utils::Point2d&> (this=0x7fffd2ff8a80) at /usr/include/c++/11/bits/vector.tcc:121
#7  0x00007fff6748a4db in behavior_velocity_planner::IntersectionModule::checkCollision (this=0x7fff840788a0, path=..., attention_area_lanelets=std::vector of length 24, capacity 32 = {...}, adjacent_lanelets=std::vector of length 1, capacity 1 = {...}, 
    intersection_area=std::optional<boost::geometry::model::polygon<tier4_autoware_utils::Point2d, true, true, std::vector, std::vector, std::allocator, std::allocator>> [no contained value], ego_lane_with_next_lane=std::vector of length 2, capacity 2 = {...}, closest_idx=4, time_delay=0)
    at /home/mins/autoware/src/universe/autoware.universe/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp:1015
...

Since I'm currently running somewhat old version of Autoware, the code line of 7th stack is here: https://github.com/autowarefoundation/autoware.universe/blob/4c47a5f994f599c0070030ff1e010503ef9fc4a3/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp#L1015 and the header file PlaneObjectBase.h seems an external library.

So, I guess the library makes a segmentation fault due to some illegal values provided to the library function.

If you need information other than the ones above, please let me know.

VRichardJP commented 7 months ago

You just found the problem:

        Polygon2d polygon{};
        for (const auto & p : trimmed_ego_polygon) {
          polygon.outer().emplace_back(p.x(), p.y());
        }

        polygon.outer().emplace_back(polygon.outer().front());

We have a trimmed_ego_polygon which we use to build another polygon. After that we try to close that polygon by adding a copy of the first point at the end (so that polygon.first() == polygon.last())... and this is where the program crash.

If by any change, the trimmed_ego_polygon happens to be empty, then our polygon is empty. So accessing its first element with polygon.outer().front() is undefined behavior.

@soblin @takayuki5168 @tkimura4 @shmpwk Could you check this?

stale[bot] commented 5 months ago

This pull request has been automatically marked as stale because it has not had recent activity.

mehmetdogru commented 4 months ago

@soblin

It seems the issue is related to intersection module. Could you take a look when you are available?

mehmetdogru commented 4 months ago

@Kim-mins Could you please provide the videos again since they don't work for me. As well could you please check if the issue is reproducable with planning simulator?

@maxime-clem to assign to a proper person that can reproduce the issue using Carla Sim.

Kim-mins commented 4 months ago

Hi @mehmetdogru!

Sorry for the inconvenience.. I should have noticed that the links are not working currently. I just restored every important link like video, log, ros2bag file.

Please let me know if you need more information during the debugging.

Thank you!

soblin commented 4 months ago

This issue is already fixed at latest version.

soblin commented 4 months ago

https://github.com/autowarefoundation/autoware.universe/blob/3f216833e62f3f4b21b9a287cdce3df82da66eab/planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp#L278

soblin commented 4 months ago

https://github.com/autowarefoundation/autoware.universe/pull/4655

Kim-mins commented 4 months ago

Thank for checking @soblin and sorry for bothering with the issue resolved already.