Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AMCL Crashes Randomly When Using Recovery Parameters #3311

Closed
borongyuan opened this issue Dec 5, 2022 · 3 comments · Fixed by #3315
Closed

AMCL Crashes Randomly When Using Recovery Parameters #3311

borongyuan opened this issue Dec 5, 2022 · 3 comments · Fixed by #3315

Comments

@borongyuan
Copy link
Contributor

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • ROS2 Version:
    • Foxy
  • Version or commit hash:
    • 0.4.7
  • DDS implementation:
    • Fast-RTPS

Steps to reproduce issue

It's easy to reproduce this issue. Just use the getting started example here. Only modify the following 3 parameters in nav2_params.yaml.

laser_model_type: "likelihood_field_prob"
recovery_alpha_fast: 0.1
recovery_alpha_slow: 0.001

Start the simulation and keep setting target points to keep TurtleBot moving (in order for AMCL to keep updating).

ros2 launch nav2_bringup tb3_simulation_launch.py headless:=False

Expected behavior

AMCL should never crash.

Actual behavior

AMCL will randomly crash after a few minutes of continuous running (usually within 10 minutes).

[ERROR] [amcl-6]: process has died [pid 29525, exit code -11, cmd '/opt/ros/foxy/lib/nav2_amcl/amcl --ros-args -r __node:=amcl --params-file /tmp/tmpmfwsb4zo -r /tf:=tf -r /tf_static:=tf_static'].

Additional information

The same problem exists if laser_model_type is set to the default likelihood_field. But setting it to likelihood_field_prob seems to have a higher probability of crashing. I'm still looking for the exact reason, but I open this issue first, maybe some of you already know it. It really bothers me when this problem occurs at the same time as the communication problem of DDS in WiFi scenarios. Fortunately, we can easily reproduce this in the basic simulation environment now. I don't know if the same problem exists in ROS1, I haven't tested this before. It stands to reason that this part of the code should have been heavily used and tested in ROS1. Since I'm using precompiled version 0.4.7, it's not clear to me if it has been fixed in subsequent updates. It might be related to #3242, because these few parameters should be covered by the search space of #3231. I will test the updated version later.

@SteveMacenski
Copy link
Member

SteveMacenski commented Dec 5, 2022

Please recompile with debug flags and run GDB so we can see specifically where its crashing. See the tutorial https://navigation.ros.org/tutorials/docs/get_backtrace.html

We don't really support Foxy anymore, but AMCL hasn't changed in a long time so I suspect whatever you're running into (assuming its not networking related) is relevant to AMCL in the main branches so I'm willing to make the exception here.

@borongyuan
Copy link
Contributor Author

Thanks for your advice. I got the traceback information as below.

Thread 13 "amcl" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffd3fff700 (LWP 137302)]
0x00007ffff7d14d66 in nav2_amcl::AmclNode::uniformPoseGenerator (arg=0x0)
    at /usr/include/c++/9/bits/stl_vector.h:1040
1040          operator[](size_type __n) _GLIBCXX_NOEXCEPT
(gdb) backtrace
#0  0x00007ffff7d14d66 in nav2_amcl::AmclNode::uniformPoseGenerator (arg=0x0)
    at /usr/include/c++/9/bits/stl_vector.h:1040
#1  0x00007ffff73fc63f in pf_update_resample (pf=0x555555bcc950)
    at /home/borong/ros2_ws/src/nav2_amcl/src/pf/pf.c:347
#2  0x00007ffff7d21c19 in nav2_amcl::AmclNode::laserReceived (
    this=<optimized out>, 
    laser_scan=std::shared_ptr<const sensor_msgs::msg::LaserScan_<std::allocator<void> >> (use count 5, weak count 0) = {...})
    at /home/borong/ros2_ws/src/nav2_amcl/src/amcl_node.cpp:699
#3  0x00007ffff7d3e029 in std::__invoke_impl<void, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), nav2_amcl::AmclNode*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&> (__t=<optimized out>, __f=<optimized out>)
    at /usr/include/c++/9/ext/atomicity.h:96
#4  std::__invoke<void (nav2_amcl::AmclNode::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), nav2_amcl::AmclNode*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&> (
    __fn=<optimized out>) at /usr/include/c++/9/bits/invoke.h:95
#5  std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)>::__call<void, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, 0ul, 1ul>(std::tuple<std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&>&&, std::_Index_tuple<0ul, 1ul>)

uniformPoseGenerator() is rarely called by pf_update_resample(). But once it is called, AMCL crashes. However when it is called by pf_init_model() there is no problem (call /reinitialize_global_localization service). After inspection, I found that the problem data is map_ pointer. A fixed map_ pointer is assigned to pf_ in initParticleFilter(). It was too early to even get the first map. At this point first_map_received_ is false and map_ is nullptr. Considering that the map may change, I'm trying to figure out how to fix it.

@SteveMacenski
Copy link
Member

I'll take a look at the PR!

@SteveMacenski SteveMacenski linked a pull request Dec 6, 2022 that will close this issue
7 tasks
SteveMacenski pushed a commit that referenced this issue Dec 6, 2022
Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
jwallace42 pushed a commit to jwallace42/navigation2 that referenced this issue Dec 14, 2022
Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
andrewlycas pushed a commit to StratomInc/navigation2 that referenced this issue Feb 23, 2023
Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
mergify bot pushed a commit that referenced this issue Nov 3, 2023
Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
(cherry picked from commit 85735ea)
SteveMacenski pushed a commit that referenced this issue Nov 3, 2023
Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
(cherry picked from commit 85735ea)

Co-authored-by: Borong Yuan <yuanborong@hotmail.com>
RBT22 pushed a commit to EnjoyRobotics/navigation2 that referenced this issue Nov 16, 2023
…s-navigation#3938)

Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
(cherry picked from commit 85735ea)

Co-authored-by: Borong Yuan <yuanborong@hotmail.com>
RBT22 pushed a commit to EnjoyRobotics/navigation2 that referenced this issue Nov 16, 2023
…s-navigation#3938)

Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
(cherry picked from commit 85735ea)

Co-authored-by: Borong Yuan <yuanborong@hotmail.com>
redvinaa pushed a commit to EnjoyRobotics/navigation2 that referenced this issue Nov 20, 2023
…s-navigation#3938)

Not assigning fixed map pointer to particle filter, using latest when resample.

(cherry picked from commit cc6f205)

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>

Signed-off-by: Borong Yuan <yuanborong@hotmail.com>
(cherry picked from commit 85735ea)

Co-authored-by: Borong Yuan <yuanborong@hotmail.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging a pull request may close this issue.

2 participants