Hello, I am using the Rosbot 3 and following the slam tutorials on your page. When I try to run the SLAM launch file it stops at “Node using stack size 40000000”:
ros2 launch tests_pkg slam.launch.py
[INFO] [launch]: All log files can be found below /home/husarion/.ros/log/2024-11-27-11-32-47-352019-rosbot-98531
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [async_slam_toolbox_node-1]: process started with pid [98534]
[async_slam_toolbox_node-1] [INFO] [1732703567.601100936] [slam]: Node using stack size 40000000
It seems that the solver is not being started. Also it does not subscribe to the /scan topic, not publish the /map topic and does not create a map frame.
This is the slam.yaml file:
slam:
ros__parameters:
# Plugin params
solver_plugin: solver_plugins::CeresSolver
ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
ceres_preconditioner: SCHUR_JACOBI
ceres_trust_strategy: LEVENBERG_MARQUARDT
ceres_dogleg_type: TRADITIONAL_DOGLEG
ceres_loss_function: None
# ROS Parameters
odom_frame: odom
map_frame: map
base_frame: base_link
scan_topic: /scans
# mode: mapping # It will be set in launch file
debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 # If 0 never publishes odometry
map_update_interval: 2.0
resolution: 0.04
max_laser_range: 12.0
minimum_time_interval: 0.1
transform_timeout: 0.2
tf_buffer_duration: 20.0
stack_size_to_use: 40000000
enable_interactive_mode: false
# General Parameters
use_scan_matching: true
use_scan_barycenter: true
minimum_travel_distance: 0.3
minimum_travel_heading: 0.5
scan_buffer_size: 10
scan_buffer_maximum_scan_distance: 7.0
link_match_minimum_response_fine: 0.1
link_scan_maximum_distance: 1.0
loop_search_maximum_distance: 3.0
do_loop_closing: true
loop_match_minimum_chain_size: 10
loop_match_maximum_variance_coarse: 3.0
loop_match_minimum_response_coarse: 0.35
loop_match_minimum_response_fine: 0.45
# Correlation Parameters - Correlation Parameters
correlation_search_space_dimension: 0.5
correlation_search_space_resolution: 0.01
correlation_search_space_smear_deviation: 0.1
# Correlation Parameters - Loop Closure Parameters
loop_search_space_dimension: 8.0
loop_search_space_resolution: 0.05
loop_search_space_smear_deviation: 0.03
# Scan Matcher Parameters
distance_variance_penalty: 0.5
angle_variance_penalty: 1.0
fine_search_angle_offset: 0.00349
coarse_search_angle_offset: 0.349
coarse_angle_resolution: 0.0349
minimum_angle_penalty: 0.9
minimum_distance_penalty: 0.5
use_response_expansion: true
And this is the slam.launch.py file:
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
slam_params_file = LaunchConfiguration('slam_params_file')
use_sim_time = LaunchConfiguration('use_sim_time')
slam_params_file_arg = DeclareLaunchArgument(
'slam_params_file',
default_value=PathJoinSubstitution(
[FindPackageShare("tests_pkg"), 'config', 'slam.yaml']
),
description='Full path to the ROS2 parameters file to use for the slam_toolbox node',
)
use_sim_time_arg = DeclareLaunchArgument(
'use_sim_time', default_value='false', description='Use simulation/Gazebo clock'
)
slam_node = Node(
package='slam_toolbox',
executable='async_slam_toolbox_node',
name='slam',
parameters=[slam_params_file, {'use_sim_time': use_sim_time}],
)
return LaunchDescription([use_sim_time_arg, slam_params_file_arg, slam_node])
What could be the reason?
Hello @DavRodFer ,
You specified the wrong topic name in the yaml file. This is probably the main reason why the no slam robot doesn’t work
DavRodFer:
scan_topic: /scans
Regards
Hello @RafalGorecki ,
Even after changing the topic name it still happens exactly the same.
Thanks.
Hello @RafalGorecki ,
I have been looking at what may change from one version of ROS to the other and there does not seem to be any difference in the way you configure it. Even with the example configuration in /opt/ros/jazzy/share/slam_toolbox/config/mapper_params_online_async.yaml
the same results come out.
About the mode
param being commented, even after uncommenting it the same result happens and no /map
topic appears.
Lastly, the name should not affect as that same name is specified when creating the node:
DavRodFer:
slam_node = Node(
package='slam_toolbox',
executable='async_slam_toolbox_node',
name='slam',
parameters=[slam_params_file, {'use_sim_time': use_sim_time}],
)
However, even after changing it as indicated, there are no changes in the outcome.
Also, when I run the slam node it does not seem to subscribe to the /scan
topic.
husarion@rosbot:~/ros2_ws$ ros2 node info /slam_toolbox
/slam_toolbox
Subscribers:
/parameter_events: rcl_interfaces/msg/ParameterEvent
Publishers:
/parameter_events: rcl_interfaces/msg/ParameterEvent
/rosout: rcl_interfaces/msg/Log
/slam_toolbox/transition_event: lifecycle_msgs/msg/TransitionEvent
Service Servers:
/slam_toolbox/change_state: lifecycle_msgs/srv/ChangeState
/slam_toolbox/describe_parameters: rcl_interfaces/srv/DescribeParameters
/slam_toolbox/get_available_states: lifecycle_msgs/srv/GetAvailableStates
/slam_toolbox/get_available_transitions: lifecycle_msgs/srv/GetAvailableTransitions
/slam_toolbox/get_parameter_types: rcl_interfaces/srv/GetParameterTypes
/slam_toolbox/get_parameters: rcl_interfaces/srv/GetParameters
/slam_toolbox/get_state: lifecycle_msgs/srv/GetState
/slam_toolbox/get_transition_graph: lifecycle_msgs/srv/GetAvailableTransitions
/slam_toolbox/get_type_description: type_description_interfaces/srv/GetTypeDescription
/slam_toolbox/list_parameters: rcl_interfaces/srv/ListParameters
/slam_toolbox/set_parameters: rcl_interfaces/srv/SetParameters
/slam_toolbox/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically
Service Clients:
Action Servers:
Action Clients:
Hello @DavRodFer ,
It still looks like the parameters are not being passed correctly. Check with the ros2 param get /slam_toolbox <parmaerter_name> command if the parameters are set with the config.
In the above message it still says name=slam
(packages should stay as it is), but you check node /slam_toolbox
, so I don’t know how to interpret that.
Also check if slam_params_file is the correct file path.
Regards
Hello @RafalGorecki ,
The first piece of code is referencing the first post, the name is changed as you indicated, that is why they have different names.
Regarding the parameters of the slam_toolbox
none appear when I try to autocomplete, when on ROS 2 Humble many options appeared.
husarion@rosbot:~/ros2_ws$ ros2 param get /slam_toolbox
build/ install/ log/ src/
Could it possible there is some kind of problem with the slam_toolbox
in the Jazzy version?
It should work. Command ros2 param list
should show you all parameters. Then you can verify some of them using ros2 param get <node_name> <param_name>
.
When running ros2 param list
this is what I get:
/controller_manager:
diagnostic_updater.period
diagnostic_updater.use_fqn
imu_broadcaster.fallback_controllers
imu_broadcaster.params_file
imu_broadcaster.type
joint_state_broadcaster.fallback_controllers
joint_state_broadcaster.params_file
joint_state_broadcaster.type
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
robot_description
rosbot_base_controller.fallback_controllers
rosbot_base_controller.params_file
rosbot_base_controller.type
start_type_description_service
update_rate
use_sim_time
/ekf_filter_node:
base_link_frame
base_link_frame_output
control_timeout
debug
diagnostic_updater.period
diagnostic_updater.use_fqn
disabled_at_startup
dynamic_process_noise_covariance
frequency
gravitational_acceleration
history_length
imu0
imu0_config
imu0_differential
imu0_linear_acceleration_rejection_threshold
imu0_pose_rejection_threshold
imu0_queue_size
imu0_relative
imu0_remove_gravitational_acceleration
imu0_twist_rejection_threshold
imu1
initial_estimate_covariance
initial_state
map_frame
odom0
odom0_config
odom0_differential
odom0_pose_rejection_threshold
odom0_pose_use_child_frame
odom0_queue_size
odom0_relative
odom0_twist_rejection_threshold
odom1
odom_frame
permit_corrected_publication
pose0
predict_to_current_time
print_diagnostics
process_noise_covariance
publish_acceleration
publish_tf
qos_overrides./odometry/filtered.publisher.depth
qos_overrides./odometry/filtered.publisher.history
qos_overrides./odometry/filtered.publisher.reliability
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
qos_overrides./tf.publisher.depth
qos_overrides./tf.publisher.durability
qos_overrides./tf.publisher.history
qos_overrides./tf.publisher.reliability
reset_on_time_jump
sensor_timeout
smooth_lagged_data
start_type_description_service
tf_prefix
transform_time_offset
transform_timeout
twist0
two_d_mode
use_control
use_sim_time
world_frame
/foxglove_bridge:
address
asset_uri_allowlist
capabilities
certfile
client_topic_whitelist
disable_load_message
include_hidden
keyfile
max_qos_depth
min_qos_depth
param_whitelist
port
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
send_buffer_limit
service_whitelist
start_type_description_service
tls
topic_whitelist
use_compression
use_sim_time
/imu_broadcaster:
frame_id
is_async
sensor_name
start_type_description_service
static_covariance_angular_velocity
static_covariance_linear_acceleration
static_covariance_orientation
update_rate
use_sim_time
/imu_sensor_node:
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
start_type_description_service
use_sim_time
/joint_state_broadcaster:
extra_joints
interfaces
is_async
joints
map_interface_to_joint_state.effort
map_interface_to_joint_state.position
map_interface_to_joint_state.velocity
start_type_description_service
update_rate
use_local_topics
use_sim_time
use_urdf_to_filter
/joy_node:
autorepeat_rate
coalesce_interval_ms
deadzone
device_id
device_name
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
start_type_description_service
sticky_buttons
use_sim_time
/launch_ros_2607:
start_type_description_service
use_sim_time
/oak:
camera.i_calibration_dump
camera.i_enable_diagnostics
camera.i_enable_imu
camera.i_enable_ir
camera.i_enable_sync
camera.i_external_calibration_path
camera.i_floodlight_brightness
camera.i_ip
camera.i_laser_dot_brightness
camera.i_mx_id
camera.i_nn_type
camera.i_pipeline_dump
camera.i_pipeline_type
camera.i_publish_tf_from_calibration
camera.i_restart_on_diagnostics_error
camera.i_rs_compat
camera.i_tf_base_frame
camera.i_tf_cam_pitch
camera.i_tf_cam_pos_x
camera.i_tf_cam_pos_y
camera.i_tf_cam_pos_z
camera.i_tf_cam_roll
camera.i_tf_cam_yaw
camera.i_tf_camera_model
camera.i_tf_camera_name
camera.i_tf_custom_urdf_location
camera.i_tf_custom_xacro_args
camera.i_tf_imu_from_descr
camera.i_tf_parent_frame
camera.i_usb_port_id
camera.i_usb_speed
diagnostic_updater.period
diagnostic_updater.use_fqn
ffmpeg_image_transport.bit_rate
ffmpeg_image_transport.delay
ffmpeg_image_transport.encoding
ffmpeg_image_transport.gop_size
ffmpeg_image_transport.measure_performance
ffmpeg_image_transport.performance_interval
ffmpeg_image_transport.pixel_format
ffmpeg_image_transport.preset
ffmpeg_image_transport.profile
ffmpeg_image_transport.qmax
ffmpeg_image_transport.tune
oak.rgb.image_raw.compressed.format
oak.rgb.image_raw.compressed.jpeg_quality
oak.rgb.image_raw.compressed.png_level
oak.rgb.image_raw.compressed.tiff.res_unit
oak.rgb.image_raw.compressed.tiff.xdpi
oak.rgb.image_raw.compressed.tiff.ydpi
oak.rgb.image_raw.compressedDepth.depth_max
oak.rgb.image_raw.compressedDepth.depth_quantization
oak.rgb.image_raw.compressedDepth.format
oak.rgb.image_raw.compressedDepth.png_level
oak.rgb.image_raw.depth_max
oak.rgb.image_raw.depth_quantization
oak.rgb.image_raw.enable_pub_plugins
oak.rgb.image_raw.format
oak.rgb.image_raw.jpeg_quality
oak.rgb.image_raw.keyframe_frequency
oak.rgb.image_raw.optimize_for
oak.rgb.image_raw.png_level
oak.rgb.image_raw.quality
oak.rgb.image_raw.target_bitrate
oak.rgb.image_raw.theora.keyframe_frequency
oak.rgb.image_raw.theora.optimize_for
oak.rgb.image_raw.theora.quality
oak.rgb.image_raw.theora.target_bitrate
oak.rgb.image_raw.tiff.res_unit
oak.rgb.image_raw.tiff.xdpi
oak.rgb.image_raw.tiff.ydpi
oak.rgb.image_raw.zstd.zstd_level
pipeline_gen.i_enable_diagnostics
pipeline_gen.i_enable_imu
pipeline_gen.i_enable_sync
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
rgb.i_add_exposure_offset
rgb.i_board_socket_id
rgb.i_calibration_file
rgb.i_disable_node
rgb.i_enable_feature_tracker
rgb.i_enable_lazy_publisher
rgb.i_enable_nn
rgb.i_enable_preview
rgb.i_exposure_offset
rgb.i_fps
rgb.i_fsync_continuous
rgb.i_fsync_trigger
rgb.i_get_base_device_timestamp
rgb.i_height
rgb.i_interleaved
rgb.i_isp_den
rgb.i_isp_num
rgb.i_keep_preview_aspect_ratio
rgb.i_low_bandwidth
rgb.i_low_bandwidth_bitrate
rgb.i_low_bandwidth_ffmpeg_encoder
rgb.i_low_bandwidth_frame_freq
rgb.i_low_bandwidth_profile
rgb.i_low_bandwidth_quality
rgb.i_max_q_size
rgb.i_output_isp
rgb.i_preview_height
rgb.i_preview_size
rgb.i_preview_width
rgb.i_publish_compressed
rgb.i_publish_topic
rgb.i_resolution
rgb.i_reverse_stereo_socket_order
rgb.i_sensor_img_orientation
rgb.i_set_isp3a_fps
rgb.i_set_isp_scale
rgb.i_simulate_from_topic
rgb.i_simulated_topic_name
rgb.i_synced
rgb.i_update_ros_base_time_on_ros_msg
rgb.i_width
rgb.r_exposure
rgb.r_focus
rgb.r_iso
rgb.r_set_man_exposure
rgb.r_set_man_focus
rgb.r_set_man_whitebalance
rgb.r_whitebalance
start_type_description_service
use_sim_time
Wait for service timed out waiting for parameter services for node NodeName(name='oak_container', namespace='/', full_name='/oak_container')
/oak_state_publisher:
frame_prefix
ignore_timestamp
publish_frequency
qos_overrides./joint_states.subscription.depth
qos_overrides./joint_states.subscription.history
qos_overrides./joint_states.subscription.reliability
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
qos_overrides./tf.publisher.depth
qos_overrides./tf.publisher.durability
qos_overrides./tf.publisher.history
qos_overrides./tf.publisher.reliability
qos_overrides./tf_static.publisher.depth
qos_overrides./tf_static.publisher.history
qos_overrides./tf_static.publisher.reliability
robot_description
start_type_description_service
use_sim_time
/robot_state_publisher:
frame_prefix
ignore_timestamp
publish_frequency
qos_overrides./joint_states.subscription.depth
qos_overrides./joint_states.subscription.history
qos_overrides./joint_states.subscription.reliability
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
qos_overrides./tf.publisher.depth
qos_overrides./tf.publisher.durability
qos_overrides./tf.publisher.history
qos_overrides./tf.publisher.reliability
qos_overrides./tf_static.publisher.depth
qos_overrides./tf_static.publisher.history
qos_overrides./tf_static.publisher.reliability
robot_description
start_type_description_service
use_sim_time
/rosbot_base_controller:
angular.z.has_acceleration_limits
angular.z.has_jerk_limits
angular.z.has_velocity_limits
angular.z.max_acceleration
angular.z.max_jerk
angular.z.max_velocity
angular.z.min_acceleration
angular.z.min_jerk
angular.z.min_velocity
base_frame_id
cmd_vel_timeout
enable_odom_tf
is_async
left_wheel_names
left_wheel_radius_multiplier
linear.x.has_acceleration_limits
linear.x.has_jerk_limits
linear.x.has_velocity_limits
linear.x.max_acceleration
linear.x.max_jerk
linear.x.max_velocity
linear.x.min_acceleration
linear.x.min_jerk
linear.x.min_velocity
odom_frame_id
open_loop
pose_covariance_diagonal
position_feedback
publish_limited_velocity
publish_rate
right_wheel_names
right_wheel_radius_multiplier
start_type_description_service
tf_frame_prefix
tf_frame_prefix_enable
twist_covariance_diagonal
update_rate
use_sim_time
velocity_rolling_window_size
wheel_radius
wheel_separation
wheel_separation_multiplier
Wait for service timed out waiting for parameter services for node NodeName(name='rosbot_ros2_firmware', namespace='/', full_name='/rosbot_ros2_firmware')
/rosbot_system_node:
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
start_type_description_service
use_sim_time
/rplidar_node:
angle_compensate
auto_standby
channel_type
flip_x_axis
frame_id
inverted
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
scan_frequency
scan_mode
serial_baudrate
serial_port
start_type_description_service
tcp_ip
tcp_port
topic_name
udp_ip
udp_port
use_sim_time
/slam_toolbox:
/bond_disable_heartbeat_timeout
stack_size_to_use
start_type_description_service
use_sim_time
/teleop_twist_joy_node:
axis_angular.pitch
axis_angular.roll
axis_angular.yaw
axis_linear.x
axis_linear.y
axis_linear.z
enable_button
enable_turbo_button
frame
inverted_reverse
publish_stamped_twist
qos_overrides./parameter_events.publisher.depth
qos_overrides./parameter_events.publisher.durability
qos_overrides./parameter_events.publisher.history
qos_overrides./parameter_events.publisher.reliability
require_enable_button
scale_angular.pitch
scale_angular.roll
scale_angular.yaw
scale_angular_turbo.pitch
scale_angular_turbo.roll
scale_angular_turbo.yaw
scale_linear.x
scale_linear.y
scale_linear.z
scale_linear_turbo.x
scale_linear_turbo.y
scale_linear_turbo.z
start_type_description_service
use_sim_time
Wait for service timed out waiting for parameter services for node NodeName(name='transform_listener_impl_aaaac69c3410', namespace='/', full_name='/transform_listener_impl_aaaac69c3410')
Where only these parameters are for the slam_toolbox
node:
/slam_toolbox:
/bond_disable_heartbeat_timeout
stack_size_to_use
start_type_description_service
use_sim_time
How should I interpret this? Is there a problem with the package?
I looked into the slam_toolbox package and the way it is launched in Ros 2 Jazzy has changed significantly. Please base your launch file on the default launcher and change the path to the configuration file:
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import (DeclareLaunchArgument, EmitEvent, LogInfo,
RegisterEventHandler)
from launch.conditions import IfCondition
from launch.events import matches_action
from launch.substitutions import (AndSubstitution, LaunchConfiguration,
NotSubstitution)
from launch_ros.actions import LifecycleNode
from launch_ros.event_handlers import OnStateTransition
from launch_ros.events.lifecycle import ChangeState
from lifecycle_msgs.msg import Transition
def generate_launch_description():
autostart = LaunchConfiguration('autostart')
use_lifecycle_manager = LaunchConfiguration("use_lifecycle_manager")
use_sim_time = LaunchConfiguration('use_sim_time')
This file has been truncated. show original
After applying this change, everything should work.
Hello @RafalGorecki ,
That solved it. Thank you very much.
1 Like