-
Notifications
You must be signed in to change notification settings - Fork 1.8k
Description
Bug report
Required Info:
- Operating System:
- Ubuntu 20.04
- ROS2 Version:
- Foxy
- Version or commit hash:
- DDS implementation:
- Fast-RTPS(default)
Steps to reproduce issue
launch the following command together in processes:
ros2 launch fuzz mygazebo.py
ros2 run nav2_controller controller_server --ros-args --params-fole configall.yaml -r __node:=controller_server
ros2 run nav2_planner planner_server --ros-args --params-fole configall.yaml -r __node:=planner_server
ros2 run nav2_recoveries recoveries_server --ros-args --params-fole configall.yaml -r __node:=recoveries_server
ros2 run nav2_bt_navigator bt_navigator --ros-args --params-fole configall.yaml -r __node:=bt_navigator
ros2 run nav2_waypoint_follower waypoint_follower --ros-args --params-fole configall.yaml -r __node:=waypoint_follower
ros2 run nav2_lifecycle_manager lifecycle_manager --ros-args --params-fole configall.yaml -r __node:=lifecycle_manager_navigation
ros2 run nav2_map_server map_server --ros-args --params-fole configall.yaml -r __node:=map_server
ros2 run nav2_amcl amcl --ros-args --params-fole configall.yaml -r __node:=amcl
ros2 run nav2_lifecycle_manager lifecycle_manager --ros-args --params-fole configall.yaml -r __node:=lifecycle_manager_localization
and add another node to publish /goal_pose per 4s:
self.goal_pub = self.node.create_publisher(geometry_msgs.msg.PoseStamped, '/goal_pose', 10)
…
def _publish_goal(self, px=2.0, py=0.5, oz=1.0):
msg = geometry_msgs.msg.PoseStamped()
msg.header.frame_id = 'map'
msg.pose.position.x = float(px)
msg.pose.position.y = float(py)
msg.pose.orientation.z = float(oz)
print('[!] change_goal:'+str(px)+" "+str(py)+" "+str(oz)+" ")
self.goal_pub.publish(msg)
4s: px = -2.0 py = 0.5 oz = 1.0
8s: px = 0.0 py = 0.5 oz = 1.0
12s: px = 2.0 py = 0.5 oz = 1.0
12s-30s: no new goals
30s: stop program.
where, the 'fuzz' is a package of mine, it can be changed into whatever.
there are also some files specially written, I've list their contents below.
here is the mygazebo.py:
#!/usr/bin/env python3
import launch
import launch_ros
import ament_index_python.packages
import os
#import launch.actions
def generate_launch_description():
env = {
'GAZEBO_MODEL_PATH': '/opt/ros/foxy/share/turtlebot3_gazebo/models',
#'GAZEBO_PLUGIN_PATH': plugin,
#'GAZEBO_RESOURCE_PATH': media
}
#os.path.join(ament_index_python.packages.get_package_share_directory('fuzz'), 'launch')
cmd = [
'gzserver',
'/home/shx/ros2_nav_fuzz/src/fuzz/scripts/config/world_only.model',
'-s', 'libgazebo_ros_init.so',
'-s', 'libgazebo_ros_factory.so',
'-s', 'libgazebo_ros_force_system.so']
return launch.LaunchDescription([
launch.actions.ExecuteProcess(
cmd=cmd,
output='screen',
additional_env=env
),
launch_ros.actions.Node(
package='gazebo_ros',
executable='spawn_entity.py',
arguments=[
'-entity',
'burger',
'-file',
'/home/shx/ros2_nav_fuzz/src/fuzz/scripts/config/myburger.sdf',
'-x',
'-2.0',
'-y',
'-0.5'
]),
launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': True}],
arguments=['/opt/ros/foxy/share/turtlebot3_description/urdf/turtlebot3_burger.urdf']),
])
where the world_only.model is the original world model from the example in ros2_bringup.
here is myburger.sdf:
<sdf version="1.5">
<model name="turtlebot3_burger">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<link name="base_footprint" />
<link name="base_link">
<inertial>
<pose>-0.032 0 0.070 0 0 0</pose>
<inertia>
<ixx>7.2397393e-01</ixx>
<ixy>4.686399e-10</ixy>
<ixz>-1.09525703e-08</ixz>
<iyy>7.2397393e-01</iyy>
<iyz>2.8582649e-09</iyz>
<izz>6.53050163e-01</izz>
</inertia>
<mass>8.2573504e-01</mass>
</inertial>
<collision name="base_collision">
<pose>-0.032 0 0.070 0 0 0</pose>
<geometry>
<box>
<size>0.140 0.140 0.140</size>
</box>
</geometry>
</collision>
<visual name="base_visual">
<pose>-0.032 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/burger_base.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="imu_link">
<sensor name="tb3_imu" type="imu">
<always_on>true</always_on>
<update_rate>200</update_rate>
<imu>
<angular_velocity>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>2e-4</stddev>
</noise>
</z>
</angular_velocity>
<linear_acceleration>
<x>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</x>
<y>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</y>
<z>
<noise type="gaussian">
<mean>0.0</mean>
<stddev>1.7e-2</stddev>
</noise>
</z>
</linear_acceleration>
</imu>
<plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
<ros>
<remapping>~/out:=imu</remapping>
</ros>
</plugin>
</sensor>
</link>
<link name="base_scan">
<inertial>
<pose>-0.020 0 0.161 0 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.114</mass>
</inertial>
<collision name="lidar_sensor_collision">
<pose>-0.020 0 0.161 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.0508</radius>
<length>0.055</length>
</cylinder>
</geometry>
</collision>
<visual name="lidar_sensor_visual">
<pose>-0.032 0 0.171 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/lds.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
<sensor name="hls_lfcd_lds" type="ray">
<always_on>true</always_on>
<visualize>true</visualize>
<pose>-0.032 0 0.171 0 0 0</pose>
<update_rate>5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<range>
<min>0.120000</min>
<max>3.5</max>
<resolution>0.015000</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<remapping>~/out:=scan_proxyme</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>base_scan</frame_name>
</plugin>
</sensor>
</link>
<link name="wheel_left_link">
<inertial>
<pose>0 0.08 0.023 -1.57 0 0</pose>
<inertia>
<ixx>1.8158194e-03</ixx>
<ixy>-9.3392e-12</ixy>
<ixz>1.04909e-11</ixz>
<iyy>3.2922126e-03</iyy>
<iyz>5.75694e-11</iyz>
<izz>1.8158194e-03</izz>
</inertia>
<mass>2.8498940e-02</mass>
</inertial>
<collision name="wheel_left_collision">
<pose>0 0.08 0.023 -1.57 0 0</pose>
<geometry>
<cylinder>
<radius>0.033</radius>
<length>0.018</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+5</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="wheel_left_visual">
<pose>0 0.08 0.023 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/tire.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="wheel_right_link">
<inertial>
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<inertia>
<ixx>1.8158194e-03</ixx>
<ixy>-9.3392e-12</ixy>
<ixz>1.04909e-11</ixz>
<iyy>3.2922126e-03</iyy>
<iyz>5.75694e-11</iyz>
<izz>1.8158194e-03</izz>
</inertia>
<mass>2.8498940e-02</mass>
</inertial>
<collision name="wheel_right_collision">
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<geometry>
<cylinder>
<radius>0.033</radius>
<length>0.018</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+5</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="wheel_right_visual">
<pose>0.0 -0.08 0.023 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/tire.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="caster_back_link">
<pose>-0.081 0 -0.004 -1.57 0 0</pose>
<inertial>
<mass>0.005</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<sphere>
<radius>0.005000</radius>
</sphere>
</geometry>
<surface>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+5</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
</link>
<joint name="base_joint" type="fixed">
<parent>base_footprint</parent>
<child>base_link</child>
<pose>0.0 0.0 0.010 0 0 0</pose>
</joint>
<joint name="wheel_left_joint" type="revolute">
<parent>base_link</parent>
<child>wheel_left_link</child>
<pose>0.0 0.08 0.023 -1.57 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="wheel_right_joint" type="revolute">
<parent>base_link</parent>
<child>wheel_right_link</child>
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="caster_back_joint" type="ball">
<parent>base_link</parent>
<child>caster_back_link</child>
</joint>
<joint name="imu_joint" type="fixed">
<parent>base_link</parent>
<child>imu_link</child>
<pose>-0.032 0 0.068 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<joint name="lidar_joint" type="fixed">
<parent>base_link</parent>
<child>base_scan</child>
<pose>-0.032 0 0.171 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
</axis>
</joint>
<plugin name="turtlebot3_diff_drive" filename="libgazebo_ros_diff_drive.so">
<ros>
<remapping>odom:=odom</remapping>
</ros>
<update_rate>30</update_rate>
<left_joint>wheel_left_joint</left_joint>
<right_joint>wheel_right_joint</right_joint>
<wheel_separation>0.160</wheel_separation>
<wheel_diameter>0.066</wheel_diameter>
<max_wheel_torque>20</max_wheel_torque>
<max_wheel_acceleration>1.0</max_wheel_acceleration>
<command_topic>cmd_vel</command_topic>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>false</publish_wheel_tf>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_footprint</robot_base_frame>
</plugin>
<plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
<ros>
<remapping>~/out:=joint_states</remapping>
</ros>
<update_rate>30</update_rate>
<joint_name>wheel_left_joint</joint_name>
<joint_name>wheel_right_joint</joint_name>
</plugin>
</model>
</sdf>
configall.yaml, is a result of our fuzzing of configs, with some parameters not sensible. However, since it's user-defined, the bugs may still happen because of wrong user behavior. The following is the configall.yaml leading to a crash:
/loc2d_ros:
ros__parameters:
base_frame_id: base_footprint
d_thresh: 0.02
global_frame_id: map
initial_pos_a: 0.0
initial_pos_x: -2.0
initial_pos_y: -0.5
odom_frame_id: odom
scan_topic: /scan
transform_tolerance: 0.2
use_sim_time: true
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: 2.6
beam_skip_threshold: 0.3
do_beamskip: false
global_frame_id: map
initial_pose:
x: -2.0
y: -0.5
yaw: 0.0
z: 0.0
lambda_short: 1.7000000000000002
laser_likelihood_max_dist: 6.1000000000000005
laser_max_range: 98.7
laser_min_range: -0.29999999999999993
laser_model_type: likelihood_field
max_beams: 60
max_particles: 2100
min_particles: 500
odom_frame_id: odom
pf_err: 0.05
pf_z: 0.99
recovery_alpha_fast: -2.6
recovery_alpha_slow: 2.0
resample_interval: 128
robot_model_type: differential
save_pose_rate: -0.6000000000000001
set_initial_pose: true
sigma_hit: -1.8
tf_broadcast: true
transform_tolerance: 6.5
update_min_a: -10.000000000000002
update_min_d: 1.85
use_sim_time: true
z_hit: 9.8
z_max: 0.05
z_rand: 0.5
z_short: -0.05
amcl_map_client:
ros__parameters:
use_sim_time: true
amcl_rclcpp_node:
ros__parameters:
use_sim_time: true
bt_navigator:
ros__parameters:
default_bt_xml_filename: /home/shx/ros2_nav_fuzz/src/fuzz/scripts/config/navigate_w_replanning_and_recovery.xml
global_frame: map
odom_topic: /odom
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
- nav2_back_up_action_bt_node
- nav2_spin_action_bt_node
- nav2_wait_action_bt_node
- nav2_clear_costmap_service_bt_node
- nav2_is_stuck_condition_bt_node
- nav2_goal_reached_condition_bt_node
- nav2_goal_updated_condition_bt_node
- nav2_initial_pose_received_condition_bt_node
- nav2_reinitialize_global_localization_service_bt_node
- nav2_rate_controller_bt_node
- nav2_distance_controller_bt_node
- nav2_speed_controller_bt_node
- nav2_recovery_node_bt_node
- nav2_pipeline_sequence_bt_node
- nav2_round_robin_node_bt_node
- nav2_transform_available_condition_bt_node
- nav2_time_expired_condition_bt_node
- nav2_distance_traveled_condition_bt_node
robot_base_frame: base_link
use_sim_time: true
bt_navigator_rclcpp_node:
ros__parameters:
use_sim_time: true
cartographer_node:
ros__parameters:
use_sim_time: true
controller_server:
ros__parameters:
FollowPath:
BaseObstacle.scale: -1.08
GoalAlign.forward_point_distance: 0.6
GoalAlign.scale: 24.0
GoalDist.scale: 24.1
PathAlign.forward_point_distance: 0.1
PathAlign.scale: 35.2
PathDist.scale: 31.9
RotateToGoal.lookahead_time: -1.0
RotateToGoal.scale: 29.6
RotateToGoal.slowing_factor: -0.8000000000000007
acc_lim_theta: -1.0999999999999996
acc_lim_x: 15.200000000000001
acc_lim_y: -0.1
angular_granularity: 2.4250000000000003
critics:
- RotateToGoal
- Oscillation
- BaseObstacle
- GoalAlign
- PathAlign
- PathDist
- GoalDist
debug_trajectory_details: true
decel_lim_theta: -3.4000000000000004
decel_lim_x: -2.6
decel_lim_y: -0.5
linear_granularity: -12.75
max_speed_xy: 0.22
max_vel_theta: -11.8
max_vel_x: 0.22
max_vel_y: 0.0
min_speed_theta: 0.0
min_speed_xy: 1.6
min_vel_x: 10.0
min_vel_y: -1.6
plugin: dwb_core::DWBLocalPlanner
short_circuit_trajectory_evaluation: true
sim_time: 1.7
stateful: true
trans_stopped_velocity: 0.25
transform_tolerance: 0.2
vtheta_samples: 1
vx_samples: 10
vy_samples: 5
xy_goal_tolerance: -1.9500000000000002
controller_frequency: 32.6
controller_plugins:
- FollowPath
min_theta_velocity_threshold: -0.399
min_x_velocity_threshold: 3.201
min_y_velocity_threshold: 0.4
use_sim_time: true
controller_server_rclcpp_node:
ros__parameters:
use_sim_time: true
ekf_localization:
ros__parameters:
gnss_pose_topic: gnss_pose
imu_topic: imu
odom_topic: odom
pub_period: -118
reference_frame_id: map
robot_frame_id: base_link
use_gnss: false
use_odom: true
var_gnss: 0.6
var_imu_acc: 0.11
var_imu_w: -10.99
var_odom: -6.1000000000000005
global_costmap:
global_costmap:
ros__parameters:
always_send_full_costmap: true
global_frame: map
inflation_layer:
cost_scaling_factor: 7.300000000000001
inflation_radius: -2.1500000000000004
plugin: nav2_costmap_2d::InflationLayer
obstacle_layer:
enabled: true
observation_sources: scan
plugin: nav2_costmap_2d::ObstacleLayer
scan:
clearing: true
data_type: LaserScan
marking: true
max_obstacle_height: 2.0
topic: /scan
plugins:
- static_layer
- obstacle_layer
- voxel_layer
- inflation_layer
publish_frequency: 10.5
resolution: -0.05
robot_base_frame: base_link
robot_radius: 0.0
static_layer:
map_subscribe_transient_local: true
plugin: nav2_costmap_2d::StaticLayer
update_frequency: 0.9
use_sim_time: true
voxel_layer:
enabled: true
mark_threshold: -10
max_obstacle_height: 2.0
observation_sources: pointcloud
origin_z: 0.0
plugin: nav2_costmap_2d::VoxelLayer
pointcloud:
clearing: true
data_type: PointCloud2
marking: true
max_obstacle_height: 2.0
topic: /intel_realsense_r200_depth/points
publish_voxel_map: true
z_resolution: 0.6500000000000001
z_voxels: 16
global_costmap_client:
ros__parameters:
use_sim_time: true
global_costmap_rclcpp_node:
ros__parameters:
use_sim_time: true
lifecycle_manager_localization:
ros__parameters:
autostart: true
node_names:
- map_server
- amcl
use_sim_time: true
lifecycle_manager_mapserver:
ros__parameters:
autostart: true
node_names:
- map_server
use_sim_time: true
lifecycle_manager_navigation:
ros__parameters:
autostart: true
node_names:
- controller_server
- planner_server
- recoveries_server
- bt_navigator
- waypoint_follower
use_sim_time: true
local_costmap:
local_costmap:
ros__parameters:
always_send_full_costmap: true
global_frame: odom
height: -23
inflation_layer:
cost_scaling_factor: 10.600000000000001
plugin: nav2_costmap_2d::InflationLayer
obstacle_layer:
enabled: true
observation_sources: scan
plugin: nav2_costmap_2d::ObstacleLayer
scan:
clearing: true
data_type: LaserScan
marking: true
max_obstacle_height: 14.700000000000001
topic: /scan
plugins:
- obstacle_layer
- voxel_layer
- inflation_layer
publish_frequency: 2.0
resolution: 7.95
robot_base_frame: base_link
robot_radius: -12.500000000000002
rolling_window: true
static_layer:
map_subscribe_transient_local: false
update_frequency: 11.4
use_sim_time: true
voxel_layer:
enabled: true
mark_threshold: 0
max_obstacle_height: 2.0
observation_sources: pointcloud
origin_z: 3.8000000000000003
plugin: nav2_costmap_2d::VoxelLayer
pointcloud:
clearing: true
data_type: PointCloud2
marking: true
max_obstacle_height: 2.0
topic: /intel_realsense_r200_depth/points
publish_voxel_map: true
z_resolution: 0.05
z_voxels: 16
width: -125
local_costmap_client:
ros__parameters:
use_sim_time: true
local_costmap_rclcpp_node:
ros__parameters:
use_sim_time: true
map_saver:
ros__parameters:
free_thresh_default: -4.65
occupied_thresh_default: -1.15
save_map_timeout: 4998
use_sim_time: true
map_server:
ros__parameters:
use_sim_time: true
yaml_filename: /home/shx/ros2_nav_fuzz/src/fuzz/scripts/config/turtlebot3_world.yaml
occupancy_grid_node:
ros__parameters:
use_sim_time: true
planner_server:
ros__parameters:
GridBased:
allow_unknown: true
plugin: nav2_navfn_planner/NavfnPlanner
tolerance: 0.4
use_astar: false
expected_planner_frequency: 20.6
planner_plugins:
- GridBased
use_sim_time: true
planner_server_rclcpp_node:
ros__parameters:
use_sim_time: true
recoveries_server:
ros__parameters:
backup:
plugin: nav2_recoveries/BackUp
costmap_topic: local_costmap/costmap_raw
cycle_frequency: 5.7
footprint_topic: local_costmap/published_footprint
global_frame: odom
max_rotational_vel: 7.2
min_rotational_vel: 0.4
recovery_plugins:
- spin
- backup
- wait
robot_base_frame: base_link
rotational_acc_lim: 6.6000000000000005
simulate_ahead_time: 1.9
spin:
plugin: nav2_recoveries/Spin
transform_timeout: 0.1
use_sim_time: true
wait:
plugin: nav2_recoveries/Wait
robot_state_publisher:
ros__parameters:
use_sim_time: true
rtabmap:
ros__parameters:
RGBD/NeighborLinkRefining: 'True'
Reg/Strategy: '1'
approx_sync: true
frame_id: base_footprint
subscribe_depth: false
subscribe_rgb: false
subscribe_scan: true
use_sim_time: true
rtabmap_camera:
ros__parameters:
frame_id: base_footprint
subscribe_depth: true
use_sim_time: true
slam_toolbox:
ros__parameters:
angle_variance_penalty: 0.9
base_frame: base_footprint
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_loss_function: None
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
coarse_angle_resolution: -0.0651
coarse_search_angle_offset: -0.9510000000000001
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: -0.09000000000000001
correlation_search_space_smear_deviation: -1.2
debug_logging: false
distance_variance_penalty: 0.6
do_loop_closing: true
enable_interactive_mode: true
fine_search_angle_offset: 0.00349
link_match_minimum_response_fine: 5.8
link_scan_maximum_distance: -0.40000000000000013
loop_match_maximum_variance_coarse: 6.2
loop_match_minimum_chain_size: 10
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 3.45
loop_search_maximum_distance: 3.0
loop_search_space_dimension: 9.4
loop_search_space_resolution: 12.750000000000002
loop_search_space_smear_deviation: 0.03
map_frame: map
map_update_interval: 3.2
max_laser_range: 20.0
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
minimum_time_interval: 0.5
minimum_travel_distance: 0.5
minimum_travel_heading: 1.2000000000000002
mode: mapping
odom_frame: odom
resolution: 0.35000000000000003
scan_buffer_maximum_scan_distance: 10.0
scan_buffer_size: 10
scan_topic: /scan
solver_plugin: solver_plugins::CeresSolver
stack_size_to_use: 40000000
tf_buffer_duration: 30.0
throttle_scans: -35
transform_publish_period: 2.62
transform_timeout: 12.9
use_response_expansion: true
use_scan_barycenter: true
use_scan_matching: true
use_sim_time: true
Expected behavior
Process should not crash.
Actual behavior
the program crashed with the Asan information below:
==454685==ERROR: AddressSanitizer: heap-buffer-overflow on address 0x6030000ae214 at pc 0x7fda71a9448d bp 0x7fda64b1bb50 sp 0x7fda64b1bb48
WRITE of size 1 at 0x6030000ae214 thread T13
#0 0x7fda71a9448c in nav2_costmap_2d::Costmap2D::MarkCell::operator()(unsigned int) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp:476:24
#1 0x7fda71a940ef in void nav2_costmap_2d::Costmap2D::bresenham2D<nav2_costmap_2d::Costmap2D::MarkCell>(nav2_costmap_2d::Costmap2D::MarkCell, unsigned int, unsigned int, int, int, int, unsigned int, unsigned int) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp:439:7
#2 0x7fda7198afd4 in void nav2_costmap_2d::Costmap2D::raytraceLine<nav2_costmap_2d::Costmap2D::MarkCell>(nav2_costmap_2d::Costmap2D::MarkCell, unsigned int, unsigned int, unsigned int, unsigned int, unsigned int) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp:413:7
#3 0x7fda71982b03 in nav2_costmap_2d::ObstacleLayer::raytraceFreespace(nav2_costmap_2d::Observation const&, double*, double*, double*, double*) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/plugins/obstacle_layer.cpp:608:5
#4 0x7fda7197dac3 in nav2_costmap_2d::ObstacleLayer::updateBounds(double, double, double, double*, double*, double*, double*) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/plugins/obstacle_layer.cpp:377:5
#5 0x7fda710716ee in nav2_costmap_2d::LayeredCostmap::updateMap(double, double, double) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/layered_costmap.cpp:150:16
#6 0x7fda7109921e in nav2_costmap_2d::Costmap2DROS::updateMap() /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_2d_ros.cpp:443:25
#7 0x7fda71093568 in nav2_costmap_2d::Costmap2DROS::mapUpdateLoop(double) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_2d_ros.cpp:397:5
#8 0x7fda7126c3c1 in void std::__invoke_impl<void, void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&>(std::__invoke_memfun_deref, void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&) /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/bits/invoke.h:73:14
#9 0x7fda7126c11a in std::__invoke_result<void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&>::type std::__invoke<void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&>(void (nav2_costmap_2d::Costmap2DROS::*&)(double), nav2_costmap_2d::Costmap2DROS*&, double&) /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/bits/invoke.h:95:14
#10 0x7fda7126c037 in void std::_Bind<void (nav2_costmap_2d::Costmap2DROS::* (nav2_costmap_2d::Costmap2DROS*, double))(double)>::__call<void, 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/functional:400:11
#11 0x7fda7126be73 in void std::_Bind<void (nav2_costmap_2d::Costmap2DROS::* (nav2_costmap_2d::Costmap2DROS*, double))(double)>::operator()<void>() /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/functional:482:17
#12 0x7fda7126bd60 in void 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)>&&) /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/bits/invoke.h:60:14
#13 0x7fda7126bcb0 in std::__invoke_result<std::_Bind<void (nav2_costmap_2d::Costmap2DROS::* (nav2_costmap_2d::Costmap2DROS*, double))(double)> >::type 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)>&&) /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/bits/invoke.h:95:14
#14 0x7fda7126bc78 in void 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>) /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/thread:244:13
#15 0x7fda7126bc38 in std::thread::_Invoker<std::tuple<std::_Bind<void (nav2_costmap_2d::Costmap2DROS::* (nav2_costmap_2d::Costmap2DROS*, double))(double)> > >::operator()() /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/thread:251:11
#16 0x7fda7126b602 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() /usr/bin/../lib/gcc/x86_64-linux-gnu/9/../../../../include/c++/9/thread:195:13
#17 0x7fda6fc6cde3 (/lib/x86_64-linux-gnu/libstdc++.so.6+0xd6de3)
#18 0x7fda701d7608 in start_thread (/lib/x86_64-linux-gnu/libpthread.so.0+0x9608)
#19 0x7fda6f951292 in clone (/lib/x86_64-linux-gnu/libc.so.6+0x122292)
0x6030000ae214 is located 6 bytes to the right of 30-byte region [0x6030000ae1f0,0x6030000ae20e)
allocated by thread T0 here:
#0 0x5dab4d in operator new[](unsigned long) (/home/r1/ros2_nav_fuzz/build/nav2_controller/controller_server+0x5dab4d)
#1 0x7fda7105959c in nav2_costmap_2d::Costmap2D::initMaps(unsigned int, unsigned int) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_2d.cpp:72:14
#2 0x7fda71059998 in nav2_costmap_2d::Costmap2D::resizeMap(unsigned int, unsigned int, double, double, double) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_2d.cpp:85:3
#3 0x7fda712f8314 in nav2_costmap_2d::CostmapLayer::matchSize() /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_layer.cpp:59:3
#4 0x7fda719709e8 in nav2_costmap_2d::ObstacleLayer::onInitialize() /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/plugins/obstacle_layer.cpp:104:18
#5 0x7fda71065ced in nav2_costmap_2d::Layer::initialize(nav2_costmap_2d::LayeredCostmap*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, tf2_ros::Buffer*, std::shared_ptr<rclcpp_lifecycle::LifecycleNode>, std::shared_ptr<rclcpp::Node>, std::shared_ptr<rclcpp::Node>) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/layer.cpp:61:3
#6 0x7fda7108aa75 in nav2_costmap_2d::Costmap2DROS::on_configure(rclcpp_lifecycle::State const&) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_2d_ros.cpp:153:13
#7 0x5e977c in nav2_controller::ControllerServer::on_configure(rclcpp_lifecycle::State const&) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_controller/src/nav2_controller.cpp:105:17
#8 0x7fda701bec27 in rclcpp_lifecycle::LifecycleNode::LifecycleNodeInterfaceImpl::execute_callback(unsigned int, rclcpp_lifecycle::State const&) (/opt/ros/foxy/lib/librclcpp_lifecycle.so+0x2bc27)
Thread T13 created by T0 here:
#0 0x59607a in pthread_create (/home/r1/ros2_nav_fuzz/build/nav2_controller/controller_server+0x59607a)
#1 0x7fda6fc6d0a8 in std::thread::_M_start_thread(std::unique_ptr<std::thread::_State, std::default_delete<std::thread::_State> >, void (*)()) (/lib/x86_64-linux-gnu/libstdc++.so.6+0xd70a8)
#2 0x7fda71092203 in nav2_costmap_2d::Costmap2DROS::on_activate(rclcpp_lifecycle::State const&) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/src/costmap_2d_ros.cpp:224:28
#3 0x5f30b7 in nav2_controller::ControllerServer::on_activate(rclcpp_lifecycle::State const&) /home/r1/ros2_nav_fuzz/src/navigation2/nav2_controller/src/nav2_controller.cpp:178:17
#4 0x7fda701bec27 in rclcpp_lifecycle::LifecycleNode::LifecycleNodeInterfaceImpl::execute_callback(unsigned int, rclcpp_lifecycle::State const&) (/opt/ros/foxy/lib/librclcpp_lifecycle.so+0x2bc27)
SUMMARY: AddressSanitizer: heap-buffer-overflow /home/r1/ros2_nav_fuzz/src/navigation2/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp:476:24 in nav2_costmap_2d::Costmap2D::MarkCell::operator()(unsigned int)
Shadow bytes around the buggy address:
0x0c068000dbf0: 00 00 04 fa fa fa fd fd fd fd fa fa fd fd fd fd
0x0c068000dc00: fa fa fd fd fd fa fa fa fd fd fd fa fa fa fd fd
0x0c068000dc10: fd fa fa fa fd fd fd fa fa fa fd fd fd fa fa fa
0x0c068000dc20: fd fd fd fa fa fa fd fd fd fa fa fa fd fd fd fa
0x0c068000dc30: fa fa fd fd fd fd fa fa fd fd fd fd fa fa 00 00
=>0x0c068000dc40: 00 06[fa]fa fd fd fd fd fa fa fd fd fd fd fa fa
0x0c068000dc50: fd fd fd fd fa fa fd fd fd fd fa fa fd fd fd fd
0x0c068000dc60: fa fa fd fd fd fd fa fa 00 00 00 02 fa fa 00 00
0x0c068000dc70: 00 07 fa fa fd fd fd fd fa fa fd fd fd fd fa fa
0x0c068000dc80: fd fd fd fd fa fa 00 00 02 fa fa fa fd fd fd fd
0x0c068000dc90: fa fa fd fd fd fd fa fa 00 00 00 05 fa fa fd fd
Shadow byte legend (one shadow byte represents 8 application bytes):
Addressable: 00
Partially addressable: 01 02 03 04 05 06 07
Heap left redzone: fa
Freed heap region: fd
Stack left redzone: f1
Stack mid redzone: f2
Stack right redzone: f3
Stack after return: f5
Stack use after scope: f8
Global redzone: f9
Global init order: f6
Poisoned by user: f7
Container overflow: fc
Array cookie: ac
Intra object redzone: bb
ASan internal: fe
Left alloca redzone: ca
Right alloca redzone: cb
Shadow gap: cc
I'll also explore the root cause of this, just report the event first.