-
Notifications
You must be signed in to change notification settings - Fork 1.7k
Open
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 24.04.3 (in a docker container)
- Host machine is Fedora Workstation 43
- Computer:
- Dell Precision 7780, 13th Gen Intel® Core™ i7-13850HX × 28, 32 GiB RAM
- ROS2 Version:
- Jazzy
- Version or commit hash:
- From source:
6794f00fb316efc2e9ede468d913021a481f57a1 - From package:
ros-jazzy-nav2-costmap-2d 1.3.10-1noble.20251108.010311
- From source:
- DDS implementation:
- rmw_cyclonedds_cpp
Steps to reproduce issue
Using the following nav2_params.yaml file (modifications to the global_costmap):
amcl:
ros__parameters:
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
max_particles: 2000
min_particles: 500
odom_frame_id: "odom"
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "nav2_amcl::DifferentialMotionModel"
save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
transform_tolerance: 1.0
update_min_a: 0.2
update_min_d: 0.25
z_hit: 0.5
z_max: 0.05
z_rand: 0.5
z_short: 0.05
scan_topic: scan
bt_navigator:
ros__parameters:
global_frame: map
robot_base_frame: base_link
odom_topic: /odom
bt_loop_duration: 10
default_server_timeout: 20
wait_for_service_timeout: 1000
action_server_result_timeout: 900.0
navigators: ["navigate_to_pose", "navigate_through_poses"]
navigate_to_pose:
plugin: "nav2_bt_navigator::NavigateToPoseNavigator"
navigate_through_poses:
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
# They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
# plugin_lib_names is used to add custom BT plugins to the executor (vector of strings).
# Built-in plugins are added automatically
# plugin_lib_names: []
error_code_names:
- compute_path_error_code
- follow_path_error_code
controller_server:
ros__parameters:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
progress_checker_plugins: ["progress_checker"]
goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker"
controller_plugins: ["FollowPath"]
use_realtime_priority: false
# Progress checker parameters
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
movement_time_allowance: 10.0
# Goal checker parameters
#precise_goal_checker:
# plugin: "nav2_controller::SimpleGoalChecker"
# xy_goal_tolerance: 0.25
# yaw_goal_tolerance: 0.25
# stateful: True
general_goal_checker:
stateful: True
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.25
yaw_goal_tolerance: 0.25
FollowPath:
plugin: "nav2_mppi_controller::MPPIController"
time_steps: 56
model_dt: 0.05
batch_size: 2000
ax_max: 3.0
ax_min: -3.0
ay_max: 3.0
ay_min: -3.0
az_max: 3.5
vx_std: 0.2
vy_std: 0.2
wz_std: 0.4
vx_max: 0.5
vx_min: -0.35
vy_max: 0.5
wz_max: 1.9
iteration_count: 1
prune_distance: 1.7
transform_tolerance: 0.1
temperature: 0.3
gamma: 0.015
motion_model: "DiffDrive"
visualize: true
regenerate_noises: true
TrajectoryVisualizer:
trajectory_step: 5
time_step: 3
AckermannConstraints:
min_turning_r: 0.2
critics: [
"ConstraintCritic", "CostCritic", "GoalCritic",
"GoalAngleCritic", "PathAlignCritic", "PathFollowCritic",
"PathAngleCritic", "PreferForwardCritic"]
ConstraintCritic:
enabled: true
cost_power: 1
cost_weight: 4.0
GoalCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
threshold_to_consider: 1.4
GoalAngleCritic:
enabled: true
cost_power: 1
cost_weight: 3.0
threshold_to_consider: 0.5
PreferForwardCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
threshold_to_consider: 0.5
CostCritic:
enabled: true
cost_power: 1
cost_weight: 3.81
near_collision_cost: 253
critical_cost: 300.0
consider_footprint: false
collision_cost: 1000000.0
near_goal_distance: 1.0
trajectory_point_step: 2
PathAlignCritic:
enabled: true
cost_power: 1
cost_weight: 14.0
max_path_occupancy_ratio: 0.05
trajectory_point_step: 4
threshold_to_consider: 0.5
offset_from_furthest: 20
use_path_orientations: false
PathFollowCritic:
enabled: true
cost_power: 1
cost_weight: 5.0
offset_from_furthest: 5
threshold_to_consider: 1.4
PathAngleCritic:
enabled: true
cost_power: 1
cost_weight: 2.0
offset_from_furthest: 4
threshold_to_consider: 0.5
max_angle_to_furthest: 1.0
mode: 0
# TwirlingCritic:
# enabled: true
# twirling_cost_power: 1
# twirling_cost_weight: 10.0
local_costmap:
local_costmap:
ros__parameters:
update_frequency: 5.0
publish_frequency: 2.0
global_frame: odom
robot_base_frame: base_link
rolling_window: true
width: 3
height: 3
resolution: 0.05
robot_radius: 0.22
plugins: ["voxel_layer", "inflation_layer"]
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.70
voxel_layer:
plugin: "nav2_costmap_2d::VoxelLayer"
enabled: True
publish_voxel_map: True
origin_z: 0.0
z_resolution: 0.05
z_voxels: 16
max_obstacle_height: 2.0
mark_threshold: 0
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
always_send_full_costmap: True
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_link
robot_radius: 0.22
track_unknown_space: true
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
scan:
topic: /scan
max_obstacle_height: 2.0
clearing: True
marking: True
data_type: "LaserScan"
raytrace_max_range: 3.0
raytrace_min_range: 0.0
obstacle_max_range: 2.5
obstacle_min_range: 0.0
static_layer:
plugin: "nav2_costmap_2d::StaticLayer"
map_subscribe_transient_local: True
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.7
################################################################################
### START OF CHANGES
always_send_full_costmap: False
rolling_window: True
resolution: 1.0
width: 1000
height: 1000
### END OF CHANGES
################################################################################
# The yaml_filename does not need to be specified since it going to be set by defaults in launch.
# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py
# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used.
# map_server:
# ros__parameters:
# yaml_filename: ""
map_saver:
ros__parameters:
save_map_timeout: 5.0
free_thresh_default: 0.25
occupied_thresh_default: 0.65
map_subscribe_transient_local: True
planner_server:
ros__parameters:
expected_planner_frequency: 20.0
planner_plugins: ["GridBased"]
costmap_update_timeout: 1.0
GridBased:
plugin: "nav2_navfn_planner::NavfnPlanner"
tolerance: 0.5
use_astar: false
allow_unknown: true
smoother_server:
ros__parameters:
smoother_plugins: ["simple_smoother"]
simple_smoother:
plugin: "nav2_smoother::SimpleSmoother"
tolerance: 1.0e-10
max_its: 1000
do_refinement: True
behavior_server:
ros__parameters:
local_costmap_topic: local_costmap/costmap_raw
global_costmap_topic: global_costmap/costmap_raw
local_footprint_topic: local_costmap/published_footprint
global_footprint_topic: global_costmap/published_footprint
cycle_frequency: 10.0
behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"]
spin:
plugin: "nav2_behaviors::Spin"
backup:
plugin: "nav2_behaviors::BackUp"
drive_on_heading:
plugin: "nav2_behaviors::DriveOnHeading"
wait:
plugin: "nav2_behaviors::Wait"
assisted_teleop:
plugin: "nav2_behaviors::AssistedTeleop"
local_frame: odom
global_frame: map
robot_base_frame: base_link
transform_tolerance: 0.1
simulate_ahead_time: 2.0
max_rotational_vel: 1.0
min_rotational_vel: 0.4
rotational_acc_lim: 3.2
waypoint_follower:
ros__parameters:
loop_rate: 20
stop_on_failure: false
action_server_result_timeout: 900.0
waypoint_task_executor_plugin: "wait_at_waypoint"
wait_at_waypoint:
plugin: "nav2_waypoint_follower::WaitAtWaypoint"
enabled: True
waypoint_pause_duration: 200
route_server:
ros__parameters:
# The graph_filepath does not need to be specified since it going to be set by defaults in launch.
# If you'd rather set it in the yaml, remove the default "graph" value in the launch file(s).
# file & provide full path to map below. If graph config or launch default is provided, it is used
# graph_filepath: $(find-pkg-share nav2_route)/graphs/aws_graph.geojson
boundary_radius_to_achieve_node: 1.0
radius_to_achieve_node: 2.0
smooth_corners: true
operations: ["AdjustSpeedLimit", "ReroutingService", "CollisionMonitor"]
ReroutingService:
plugin: "nav2_route::ReroutingService"
AdjustSpeedLimit:
plugin: "nav2_route::AdjustSpeedLimit"
CollisionMonitor:
plugin: "nav2_route::CollisionMonitor"
max_collision_dist: 3.0
edge_cost_functions: ["DistanceScorer", "CostmapScorer"]
DistanceScorer:
plugin: "nav2_route::DistanceScorer"
CostmapScorer:
plugin: "nav2_route::CostmapScorer"
velocity_smoother:
ros__parameters:
smoothing_frequency: 20.0
scale_velocities: False
feedback: "OPEN_LOOP"
max_velocity: [0.5, 0.0, 2.0]
min_velocity: [-0.5, 0.0, -2.0]
max_accel: [2.5, 0.0, 3.2]
max_decel: [-2.5, 0.0, -3.2]
odom_topic: "odom"
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
velocity_timeout: 1.0
collision_monitor:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.2
source_timeout: 1.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types,
# and robot footprint for "approach" action type.
polygons: ["FootprintApproach"]
FootprintApproach:
type: "polygon"
action_type: "approach"
footprint_topic: "/local_costmap/published_footprint"
time_before_collision: 1.2
simulation_time_step: 0.1
min_points: 6
visualize: False
enabled: True
observation_sources: ["scan"]
scan:
type: "scan"
topic: "scan"
min_height: 0.15
max_height: 2.0
enabled: True
docking_server:
ros__parameters:
controller_frequency: 50.0
initial_perception_timeout: 5.0
wait_charge_timeout: 5.0
dock_approach_timeout: 30.0
undock_linear_tolerance: 0.05
undock_angular_tolerance: 0.1
max_retries: 3
base_frame: "base_link"
fixed_frame: "odom"
dock_backwards: false
dock_prestaging_tolerance: 0.5
# Types of docks
dock_plugins: ['simple_charging_dock']
simple_charging_dock:
plugin: 'opennav_docking::SimpleChargingDock'
docking_threshold: 0.05
staging_x_offset: -0.7
use_external_detection_pose: true
use_battery_status: false # true
use_stall_detection: false # true
external_detection_timeout: 1.0
external_detection_translation_x: -0.18
external_detection_translation_y: 0.0
external_detection_rotation_roll: -1.57
external_detection_rotation_pitch: -1.57
external_detection_rotation_yaw: 0.0
filter_coef: 0.1
# Dock instances
# The following example illustrates configuring dock instances.
# docks: ['home_dock'] # Input your docks here
# home_dock:
# type: 'simple_charging_dock'
# frame: map
# pose: [0.0, 0.0, 0.0]
controller:
k_phi: 3.0
k_delta: 2.0
v_linear_min: 0.15
v_linear_max: 0.15
use_collision_detection: true
costmap_topic: "local_costmap/costmap_raw"
footprint_topic: "local_costmap/published_footprint"
transform_tolerance: 0.1
projection_time: 5.0
simulation_step: 0.1
dock_collision_threshold: 0.3
loopback_simulator:
ros__parameters:
base_frame_id: "base_footprint"
odom_frame_id: "odom"
map_frame_id: "map"
scan_frame_id: "base_scan" # tb4_loopback_simulator.launch.py remaps to 'rplidar_link'
update_duration: 0.02
scan_range_min: 0.05
scan_range_max: 30.0
scan_angle_min: -3.1415
scan_angle_max: 3.1415
scan_angle_increment: 0.02617
scan_use_inf: true
Run the tb3_simulation.py launch from nav2_bringup:
ros2 launch nav2_bringup tb3_simulation_launch.py
In another terminal, subscribe to the static_layer_raw_updates topic (either updates topic will trigger the crash):
ros2 topic echo /global_costmap/static_layer_raw_updates
This will cause the nav2_container to crash in the nav2_bringup.
Thread 12 "component_conta" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 3678773.3685316]
0x00007fffeaf6cb94 in nav2_costmap_2d::Costmap2D::getCost (this=0x7fff88211500, mx=384, my=384) at /workspace/STcore/external/src/navigation2/nav2_costmap_2d/src/costmap_2d.cpp:266
266 return costmap_[getIndex(mx, my)];
This is the backtrace:
(gdb) bt
#0 0x00007fffd35f7b94 in nav2_costmap_2d::Costmap2D::getCost (this=0x7fff88212d50, mx=384, my=384) at /workspace/STcore/external/src/navigation2/nav2_costmap_2d/src/costmap_2d.cpp:266
#1 0x00007fffd370005e in nav2_costmap_2d::Costmap2DPublisher::createCostmapUpdateMsg (this=0x7fff88343fc0) at /workspace/STcore/external/src/navigation2/nav2_costmap_2d/src/costmap_2d_publisher.cpp:227
#2 0x00007fffd3700476 in nav2_costmap_2d::Costmap2DPublisher::publishCostmap (this=0x7fff88343fc0) at /workspace/STcore/external/src/navigation2/nav2_costmap_2d/src/costmap_2d_publisher.cpp:258
#3 0x00007fffd360f63a in nav2_costmap_2d::Costmap2DROS::mapUpdateLoop (this=0x555555a18e30, frequency=1) at /workspace/STcore/external/src/navigation2/nav2_costmap_2d/src/costmap_2d_ros.cpp:554
#4 0x00007fffd36fca7d in std::__invoke_impl<void, void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&> (
__f=@0x7fff880015c8: (void (nav2_costmap_2d::Costmap2DROS::*)(nav2_costmap_2d::Costmap2DROS * const, double)) 0x7fffd360eac4 <nav2_costmap_2d::Costmap2DROS::mapUpdateLoop(double)>,
__t=@0x7fff880015e0: 0x555555a18e30) at /usr/include/c++/13/bits/invoke.h:74
#5 0x00007fffd36fbe5f in std::__invoke<void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&> (
__fn=@0x7fff880015c8: (void (nav2_costmap_2d::Costmap2DROS::*)(nav2_costmap_2d::Costmap2DROS * const, double)) 0x7fffd360eac4 <nav2_costmap_2d::Costmap2DROS::mapUpdateLoop(double)>)
at /usr/include/c++/13/bits/invoke.h:96
#6 0x00007fffd36fafd4 in std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (
this=0x7fff880015c8, __args=...) at /usr/include/c++/13/functional:506
#7 0x00007fffd36f951b in std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)>::operator()<, void>() (this=0x7fff880015c8) at /usr/include/c++/13/functional:591
#8 0x00007fffd36f647b in std::__invoke_impl<void, std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)>>(std::__invoke_other, std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)>&&) (__f=...) at /usr/include/c++/13/bits/invoke.h:61
#9 0x00007fffd36f1be3 in std::__invoke<std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)>>(std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)>&&) (__fn=...) at /usr/include/c++/13/bits/invoke.h:96
#10 0x00007fffd36e7fac in std::thread::_Invoker<std::tuple<std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (
this=0x7fff880015c8) at /usr/include/c++/13/bits/std_thread.h:292
#11 0x00007fffd36e2ddc in std::thread::_Invoker<std::tuple<std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)> > >::operator()() (this=0x7fff880015c8)
at /usr/include/c++/13/bits/std_thread.h:299
#12 0x00007fffd36dbe02 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (nav2_costmap_2d::Costmap2DROS::*(nav2_costmap_2d::Costmap2DROS*, double))(double)> > > >::_M_run() (
this=0x7fff880015c0) at /usr/include/c++/13/bits/std_thread.h:244
#13 0x00007ffff7b53db4 in std::execute_native_thread_routine (__p=0x7fff880015c0) at ../../../../../src/libstdc++-v3/src/c++11/thread.cc:104
#14 0x00007ffff78c3aa4 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:447
#15 0x00007ffff7950c6c in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:78
The local state of costmap at frame 0:
(gdb) p *this
$1 = {
_vptr.Costmap2D = 0x7fff327c3cc8 <vtable for nav2_costmap_2d::StaticLayer+128>,
access_ = 0x7fff88216450,
size_x_ = 384,
size_y_ = 384,
resolution_ = 0.05000000074505806,
origin_x_ = -10,
origin_y_ = -10,
costmap_ = 0x7ffefc029f30 '\377' <repeats 200 times>...,
default_value_ = 0 '\000'
}
The local state of costmap_2d at frame 1:
(gdb) p *this
$9 = {
clock_ = {
<std::__shared_ptr<rclcpp::Clock, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp::Clock, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<rclcpp::Clock, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x555555a267b0,
_M_refcount = {
_M_pi = 0x555555a267a0
}
}, <No data fields>},
logger_ = {
name_ = {
<std::__shared_ptr<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x555555a12c50,
_M_refcount = {
_M_pi = 0x555555a270d0
}
}, <No data fields>},
logger_sublogger_pairname_ = {
<std::__shared_ptr<std::pair<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<std::pair<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<std::pair<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x0,
_M_refcount = {
_M_pi = 0x0
}
}, <No data fields>}
},
costmap_ = 0x7fff88211500,
global_frame_ = {
_M_dataplus = {
<std::allocator<char>> = {
<std::__new_allocator<char>> = {<No data fields>}, <No data fields>},
members of std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::_Alloc_hider:
_M_p = 0x7fff883246f8 "map"
},
_M_string_length = 3,
{
_M_local_buf = "map\000\000\000\253\004\001\020\231\251\f5M\353",
_M_allocated_capacity = 336362597176598893
}
},
topic_name_ = {
_M_dataplus = {
<std::allocator<char>> = {
<std::__new_allocator<char>> = {<No data fields>}, <No data fields>},
members of std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::_Alloc_hider:
_M_p = 0x7fff88324718 "static_layer"
},
_M_string_length = 12,
{
_M_local_buf = "static_layer\0005M\353",
_M_allocated_capacity = 7809069583458989171
}
},
x0_ = 384,
xn_ = 510,
y0_ = 384,
yn_ = 509,
saved_origin_x_ = -10,
saved_origin_y_ = -10,
active_ = false,
always_send_full_costmap_ = false,
map_vis_z_ = 0,
costmap_pub_ = {
<std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff883551e0,
_M_refcount = {
_M_pi = 0x7fff883551d0
}
}, <No data fields>},
costmap_update_pub_ = {
<std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff8835a9f0,
_M_refcount = {
_M_pi = 0x7fff8835a9e0
}
}, <No data fields>},
costmap_update_pub_ = {
<std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fie
lds>},
members of std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<map_msgs::msg::OccupancyGridUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff8835a9f0,
_M_refcount = {
_M_pi = 0x7fff8835a9e0
}
}, <No data fields>},
costmap_raw_pub_ = {
<std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff8835ca00,
_M_refcount = {
_M_pi = 0x7fff8835c9f0
}
}, <No data fields>},
costmap_raw_pub_ = {
<std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff8835ca00,
_M_refcount = {
_M_pi = 0x7fff8835c9f0
}
}, <No data fields>},
costmap_raw_update_pub_ = {
<std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CostmapUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CostmapUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>}
,
members of std::__shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CostmapUpdate_<std::allocator<void> >, std::allocator<void> >, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff88359250,
_M_refcount = {
_M_pi = 0x7fff88359240
}
}, <No data fields>},
costmap_service_ = {
<std::__shared_ptr<rclcpp::Service<nav2_msgs::srv::GetCostmap>, (__gnu_cxx::_Lock_policy)2>> = {
<std::__shared_ptr_access<rclcpp::Service<nav2_msgs::srv::GetCostmap>, (__gnu_cxx::_Lock_policy)2, false, false>> = {<No data fields>},
members of std::__shared_ptr<rclcpp::Service<nav2_msgs::srv::GetCostmap>, (__gnu_cxx::_Lock_policy)2>:
_M_ptr = 0x7fff88209a40,
_M_refcount = {
_M_pi = 0x7fff88209a30
}
}, <No data fields>},
grid_resolution_ = 0.0500000007,
grid_width_ = 384,
grid_height_ = 384,
grid_ = {
_M_t = {
<std::__uniq_ptr_impl<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >> = {
_M_t = {
<std::_Tuple_impl<0, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >*, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >> = {
<std::_Tuple_impl<1, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >> = {
<std::_Head_base<1, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, true>> = {
_M_head_impl = {<No data fields>}
}, <No data fields>},
<std::_Head_base<0, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >*, false>> = {
_M_head_impl = 0x0
}, <No data fields>}, <No data fields>}
}, <No data fields>}
},
costmap_raw_ = {
_M_t = {
<std::__uniq_ptr_impl<nav2_msgs::msg::Costmap_<std::allocator<void> >, std::default_delete<nav2_msgs::msg::Costmap_<std::allocator<void> > > >> = {
_M_t = {
<std::_Tuple_impl<0, nav2_msgs::msg::Costmap_<std::allocator<void> >*, std::default_delete<nav2_msgs::msg::Costmap_<std::allocator<void> > > >> = {
<std::_Tuple_impl<1, std::default_delete<nav2_msgs::msg::Costmap_<std::allocator<void> > > >> = {
<std::_Head_base<1, std::default_delete<nav2_msgs::msg::Costmap_<std::allocator<void> > >, true>> = {
_M_head_impl = {<No data fields>}
}, <No data fields>},
<std::_Head_base<0, nav2_msgs::msg::Costmap_<std::allocator<void> >*, false>> = {
_M_head_impl = 0x0
}, <No data fields>}, <No data fields>}
}, <No data fields>}
}
}
Expected behavior
nav2_containter does not crash
Actual behavior
nav2_container crashes
Reproduction instructions
See above
Additional information
N/A
Metadata
Metadata
Assignees
Labels
No labels