[Solved] Rosbot 2.0 PRO - ROS 2 Foxy - How to load a pre-built map into ROS2 for navigation?

Hello everyone,

I have been playing with my ROSbot 2.0 PRO for a couple of weeks and I’m stuck in a lack of clear documentation.

I have installed the husarion packages and tried both navigation_demo_sim.launch and navigation_demo_pro.launch. These launch files starts the navigation and SLAM packages so than I can build a map after moving around the robot with the keyboard teleop and calling the map_saver_cli of ROS2. While doing so, the topic /pose is published but there is no position published in it. My understanding is that it will be sent only if the robot knows the map and can determine it’s position based on AMCL mapping.

So, now that I have my generated map (map.pgm and map.yaml), I want to use it into navigation_demo_sim.launch and navigation_demo_pro.launch. What needs to be modified in those launch files to take into account my newly generated map instead of building a new one every time and not benefiting from the /pose topic ?

All the documentation that I can find is on ROS1. I found a topic here describing what I want to do in ROS 2:
answer_ros.com

I tried to implement it in your existing launch (rosbot_navigation_sim.launch) with no success, see code below.

So my question is, do you know how to achieve what I want to do and can you provide a launch file to make my ROSbot 2.0 PRO work with AMCL on an already built map ?

Thank you a lot for your help !

Ps: Subsidiary question : How can I easily change the Gazebo world in your simulation demo ? The current world is huge, therefore the generated map is quite heavy too.

import os

from launch import LaunchDescription
import launch.actions
import launch_ros.actions
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
from ament_index_python.packages import get_package_prefix
from ament_index_python.packages import get_package_share_directory
from nav2_common.launch import RewrittenYaml


def generate_launch_description():
    rosbot_description = get_package_share_directory('rosbot_description')
    use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time',
                                                            default='true')
    autostart = launch.substitutions.LaunchConfiguration('autostart')
    params_file = launch.substitutions.LaunchConfiguration('params')
    default_bt_xml_filename = launch.substitutions.LaunchConfiguration(
        'default_bt_xml_filename')

    remappings = []
    
    # Map server ---------------ADDED--------------
    map_server_config_path = os.path.join(
    get_package_share_directory('rosbot_description'),
    'maps',
    'map_sim.yaml'
    )
    #---------------------------------------------------
    # Create our own temporary YAML files that include substitutions
    param_substitutions = {
        'use_sim_time': use_sim_time,
        'default_bt_xml_filename': default_bt_xml_filename,
        'autostart': autostart,
    }

    lifecycle_nodes = ['controller_server',
                       'planner_server',
                       'recoveries_server',
                       'bt_navigator',
                       'map_server', #---------------ADDED--------------
                       'waypoint_follower']

    configured_params = RewrittenYaml(
        source_file=params_file,
        param_rewrites=param_substitutions,
        convert_types=True)

    return LaunchDescription([
        # Set env var to print messages to stdout immediately
        SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),

        launch.actions.DeclareLaunchArgument(
            'use_sim_time', default_value='false',
            description='Use simulation (Gazebo) clock if true'),

        launch.actions.DeclareLaunchArgument(
            'autostart', default_value='true',
            description='Automatically startup the nav2 stack'),

        launch.actions.DeclareLaunchArgument(
            'params',
            default_value=[rosbot_description,
                           '/config/nav2_params.yaml'],
            description='Full path to the ROS2 parameters file to use'),

        DeclareLaunchArgument(
            'default_bt_xml_filename',
            default_value=os.path.join(
                get_package_share_directory('nav2_bt_navigator'),
                'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
            description='Full path to the behavior tree xml file to use'),

        launch_ros.actions.Node(
            package='nav2_controller',
            executable='controller_server',
            output='screen',
            parameters=[configured_params],
            remappings=remappings),

        launch_ros.actions.Node(
            package='nav2_planner',
            executable='planner_server',
            name='planner_server',
            output='screen',
            parameters=[configured_params],
            remappings=remappings),


        launch_ros.actions.Node(
            package='nav2_recoveries',
            executable='recoveries_server',
            name='recoveries_server',
            output='screen',
            parameters=[{'use_sim_time': use_sim_time}],
            remappings=remappings),

        launch_ros.actions.Node(
            package='nav2_bt_navigator',
            executable='bt_navigator',
            name='bt_navigator',
            output='screen',
            parameters=[configured_params],
            remappings=remappings),

        launch_ros.actions.Node(
            package='nav2_waypoint_follower',
            executable='waypoint_follower',
            name='waypoint_follower',
            output='screen',
            parameters=[configured_params],
            remappings=remappings),
        #---------------ADDED--------------    
        launch_ros.actions.Node(
            package='nav2_map_server',
            executable='map_server',
            output='screen',
            parameters=[{'yaml_filename': map_server_config_path}],
            remappings=remappings),
        #----------------------------------------
        launch_ros.actions.Node(
            package='nav2_lifecycle_manager',
            executable='lifecycle_manager',
            name='lifecycle_manager_navigation',
            output='screen',
            parameters=[{'use_sim_time': use_sim_time},
                        {'autostart': autostart},
                        {'node_names': lifecycle_nodes}]),

    ])

I’ve also tried to modify the given “nav_amcl_demo_sim.launch.py” to work with a real robot and not a gazebo simulation. I gave it an already built map but it’s still not working. You will find below the modified code and the command log. The program fails to load map yaml file, even though it has been created on the same robot. After this error, the program freezes and I have to stop it manually with Ctrl + C

Do you have an idea why it’s happening ?

Code :

import os
import launch
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, GroupAction
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, Command
from ament_index_python.packages import get_package_share_directory

def generate_launch_description():
    rosbot_description = get_package_share_directory('rosbot_description')
    nav2_bringup = get_package_share_directory('nav2_bringup')
    
    default_map = os.path.join(rosbot_description, 'maps', 'map.yaml')
    nav_params = os.path.join(rosbot_description, 'config', 'nav2_params_nav_amcl_sim_demo.yaml')
    
    map_cfg = LaunchConfiguration('map')
    params_cfg = LaunchConfiguration('params')
    
    declare_map_arg = DeclareLaunchArgument('map', default_value=default_map, description='map file')
    declare_params_arg = DeclareLaunchArgument('params', default_value=nav_params, description='params file')
    
    include_files = GroupAction([
        IncludeLaunchDescription(
            PythonLaunchDescriptionSource([rosbot_description, '/launch/rosbot_pro.launch.py']),
        ),
        IncludeLaunchDescription(
            PythonLaunchDescriptionSource([rosbot_description, '/launch/rosbot_navigation_pro.launch.py']),
            launch_arguments = {'params': params_cfg}.items()
        ),
        IncludeLaunchDescription(
            PythonLaunchDescriptionSource([nav2_bringup, '/launch/localization_launch.py']),
            launch_arguments={'map': map_cfg,
                              'params_file': params_cfg}.items()
        ),
    ])
    
    ld = LaunchDescription()
    ld.add_action(declare_map_arg)
    ld.add_action(declare_params_arg)
    ld.add_action(include_files)
    
    return ld

Logs :

husarion@ubuntu:~/husarion_ws$ ros2 launch rosbot_description my_navigation_demo_pro.launch.py 
[INFO] [launch]: All log files can be found below /home/husarion/.ros/log/2022-05-23-10-07-13-778711-ubuntu-1540
[INFO] [launch]: Default logging verbosity is set to INFO
/home/husarion/husarion_ws/install/rplidar_ros/share/rplidar_ros/launch/rplidar_a3.launch.py:7: UserWarning: The parameter 'node_executable' is deprecated, use 'executable' instead
  Node(
/home/husarion/husarion_ws/install/rplidar_ros/share/rplidar_ros/launch/rplidar_a3.launch.py:7: UserWarning: The parameter 'node_name' is deprecated, use 'name' instead
  Node(
[INFO] [rplidar_composition-1]: process started with pid [1544]
[INFO] [static_transform_publisher-2]: process started with pid [1546]
[INFO] [rosserial_node.py-3]: process started with pid [1548]
[INFO] [rosbot_tf-4]: process started with pid [1550]
[INFO] [static_transform_publisher-5]: process started with pid [1552]
[INFO] [static_transform_publisher-6]: process started with pid [1554]
[INFO] [static_transform_publisher-7]: process started with pid [1556]
[INFO] [static_transform_publisher-8]: process started with pid [1558]
[INFO] [static_transform_publisher-9]: process started with pid [1560]
[INFO] [static_transform_publisher-10]: process started with pid [1562]
[INFO] [controller_server-11]: process started with pid [1564]
[INFO] [planner_server-12]: process started with pid [1566]
[INFO] [recoveries_server-13]: process started with pid [1576]
[INFO] [bt_navigator-14]: process started with pid [1634]
[INFO] [waypoint_follower-15]: process started with pid [1637]
[INFO] [lifecycle_manager-16]: process started with pid [1646]
[INFO] [map_server-17]: process started with pid [1648]
[INFO] [amcl-18]: process started with pid [1650]
[INFO] [lifecycle_manager-19]: process started with pid [1652]
[rplidar_composition-1] 1653293236.214965 [0] rplidar_co: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[rplidar_composition-1] [INFO] [1653293236.431678371] [rplidar_composition]: RPLIDAR running on ROS 2 package rplidar_ros. SDK Version: '1.12.0'
[static_transform_publisher-2] 1653293236.215839 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-2] [INFO] [1653293236.410070083] [static_transform_publisher_Iceyd2dUDVxnS4JJ]: Spinning until killed publishing transform from 'base_link' to 'laser'
[rosbot_tf-4] 1653293236.228976 [0]  rosbot_tf: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-5] 1653293236.213482 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-5] [INFO] [1653293236.435290634] [static_transform_publisher_otspP9djW5Gd7gsL]: Spinning until killed publishing transform from 'base_link' to 'front_left_wheel'
[static_transform_publisher-6] 1653293236.220313 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-6] [INFO] [1653293236.424289593] [static_transform_publisher_xy7xWhhbNu516BhK]: Spinning until killed publishing transform from 'base_link' to 'front_right_wheel'
[static_transform_publisher-7] 1653293236.213482 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-7] [INFO] [1653293236.381942718] [static_transform_publisher_M4e2cofP8wTLzH0a]: Spinning until killed publishing transform from 'base_link' to 'rear_left_wheel'
[static_transform_publisher-8] 1653293236.224326 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-8] [INFO] [1653293236.417234448] [static_transform_publisher_liASfEZ660Fst1dr]: Spinning until killed publishing transform from 'base_link' to 'rear_right_wheel'
[static_transform_publisher-9] 1653293236.232993 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-9] [INFO] [1653293236.487441867] [static_transform_publisher_lzT6BvIwFut7rnGq]: Spinning until killed publishing transform from 'base_link' to 'top'
[static_transform_publisher-10] 1653293236.298745 [0] static_tra: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[static_transform_publisher-10] [INFO] [1653293236.559672124] [static_transform_publisher_NZoeQ6y5QO1ktmsV]: Spinning until killed publishing transform from 'base_link' to 'camera_link'
[controller_server-11] 1653293236.533726 [0] controller: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[planner_server-12] 1653293236.530188 [0] planner_se: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[recoveries_server-13] 1653293236.543007 [0] recoveries: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[waypoint_follower-15] 1653293236.584515 [0] waypoint_f: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[lifecycle_manager-16] 1653293236.620338 [0] lifecycle_: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[lifecycle_manager-19] 1653293236.784936 [0] lifecycle_: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[planner_server-12] [INFO] [1653293236.800137120] [planner_server]: 
[planner_server-12] 	planner_server lifecycle node launched. 
[planner_server-12] 	Waiting on external lifecycle transitions to activate
[planner_server-12] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[lifecycle_manager-16] [INFO] [1653293236.816702073] [lifecycle_manager_navigation]: Creating
[amcl-18] 1653293236.856914 [0]       amcl: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[bt_navigator-14] 1653293236.859679 [0] bt_navigat: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[recoveries_server-13] [INFO] [1653293236.932626301] [recoveries_server]: 
[recoveries_server-13] 	recoveries_server lifecycle node launched. 
[recoveries_server-13] 	Waiting on external lifecycle transitions to activate
[recoveries_server-13] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[rplidar_composition-1] [INFO] [1653293236.958696123] [rplidar_composition]: RPLIDAR S/N: EEE092F0C9E299D8BEE499F46934391D
[rplidar_composition-1] [INFO] [1653293236.958840323] [rplidar_composition]: Firmware Ver: 1.27
[rplidar_composition-1] [INFO] [1653293236.958900984] [rplidar_composition]: Hardware Rev: 6
[rplidar_composition-1] [INFO] [1653293236.959892855] [rplidar_composition]: RPLidar health status : '0'
[planner_server-12] [INFO] [1653293236.999956260] [planner_server]: Creating
[lifecycle_manager-19] [INFO] [1653293237.178291909] [lifecycle_manager_localization]: Creating
[lifecycle_manager-16] [INFO] [1653293237.214235975] [lifecycle_manager_navigation]: Creating and initializing lifecycle service clients
[waypoint_follower-15] [INFO] [1653293237.224254291] [waypoint_follower]: 
[waypoint_follower-15] 	waypoint_follower lifecycle node launched. 
[waypoint_follower-15] 	Waiting on external lifecycle transitions to activate
[waypoint_follower-15] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[waypoint_follower-15] [INFO] [1653293237.224580316] [waypoint_follower]: Creating
[controller_server-11] [INFO] [1653293237.224834804] [controller_server]: 
[controller_server-11] 	controller_server lifecycle node launched. 
[controller_server-11] 	Waiting on external lifecycle transitions to activate
[controller_server-11] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_server-17] 1653293237.418049 [0] map_server: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[bt_navigator-14] [INFO] [1653293237.425149248] [bt_navigator]: 
[bt_navigator-14] 	bt_navigator lifecycle node launched. 
[bt_navigator-14] 	Waiting on external lifecycle transitions to activate
[bt_navigator-14] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[bt_navigator-14] [INFO] [1653293237.425970122] [bt_navigator]: Creating
[controller_server-11] [INFO] [1653293237.433214756] [controller_server]: Creating controller server
[lifecycle_manager-16] [INFO] [1653293237.457801028] [lifecycle_manager_navigation]: Starting managed nodes bringup...
[lifecycle_manager-16] [INFO] [1653293237.457935936] [lifecycle_manager_navigation]: Configuring controller_server
[rplidar_composition-1] [INFO] [1653293237.574541610] [rplidar_composition]: current scan mode: Sensitivity, max_distance: 25.0 m, Point number: 15.9K , angle_compensate: 4, flip_x_axis 0
[lifecycle_manager-19] [INFO] [1653293237.637464546] [lifecycle_manager_localization]: Creating and initializing lifecycle service clients
[lifecycle_manager-19] [INFO] [1653293237.709761001] [lifecycle_manager_localization]: Starting managed nodes bringup...
[lifecycle_manager-19] [INFO] [1653293237.709902772] [lifecycle_manager_localization]: Configuring map_server
[amcl-18] [INFO] [1653293237.724344458] [amcl]: 
[amcl-18] 	amcl lifecycle node launched. 
[amcl-18] 	Waiting on external lifecycle transitions to activate
[amcl-18] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[amcl-18] [INFO] [1653293237.737428176] [amcl]: Creating
[planner_server-12] [INFO] [1653293237.745137543] [global_costmap.global_costmap]: 
[planner_server-12] 	global_costmap lifecycle node launched. 
[planner_server-12] 	Waiting on external lifecycle transitions to activate
[planner_server-12] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[planner_server-12] [INFO] [1653293237.785778507] [global_costmap.global_costmap]: Creating Costmap
[map_server-17] [INFO] [1653293238.009082657] [map_server]: 
[map_server-17] 	map_server lifecycle node launched. 
[map_server-17] 	Waiting on external lifecycle transitions to activate
[map_server-17] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[map_server-17] [INFO] [1653293238.009675974] [map_server]: Creating
[controller_server-11] [INFO] [1653293238.288352655] [local_costmap.local_costmap]: 
[controller_server-11] 	local_costmap lifecycle node launched. 
[controller_server-11] 	Waiting on external lifecycle transitions to activate
[controller_server-11] 	See https://design.ros2.org/articles/node_lifecycle.html for more information.
[controller_server-11] [INFO] [1653293238.289667617] [local_costmap.local_costmap]: Creating Costmap
[map_server-17] [INFO] [1653293238.364673550] [map_server]: Configuring
[map_server-17] [INFO] [map_io]: Loading yaml file: /home/husarion/husarion_ws/install/rosbot_description/share/rosbot_description/maps/map_1653036568.yaml
[map_server-17] [ERROR] [map_io]: Failed processing YAML file /home/husarion/husarion_ws/install/rosbot_description/share/rosbot_description/maps/map_1653036568.yaml at position (-1:-1) for reason: bad file
[map_server-17] [ERROR] [1653293238.390615448] []: Caught exception in callback for transition 10
[map_server-17] [ERROR] [1653293238.390681532] []: Original error: Failed to load map yaml file: /home/husarion/husarion_ws/install/rosbot_description/share/rosbot_description/maps/map_1653036568.yaml
[map_server-17] [WARN] [1653293238.390782570] []: Error occurred while doing error handling.
[map_server-17] [FATAL] [1653293238.390827014] [map_server]: Lifecycle node map_server does not have error state implemented
[lifecycle_manager-19] [ERROR] [1653293238.403793156] [lifecycle_manager_localization]: Failed to change state for node: map_server
[lifecycle_manager-19] [ERROR] [1653293238.403932337] [lifecycle_manager_localization]: Failed to bring up all requested nodes. Aborting bringup.
[controller_server-11] [INFO] [1653293238.537857261] [controller_server]: Configuring controller interface
[controller_server-11] [INFO] [1653293238.545333163] [controller_server]: Controller frequency set to 20.0000Hz
[controller_server-11] [INFO] [1653293238.545501948] [local_costmap.local_costmap]: Configuring
[controller_server-11] [INFO] [1653293238.585667930] [local_costmap.local_costmap]: Using plugin "voxel_layer"
[controller_server-11] [INFO] [1653293238.655748199] [local_costmap.local_costmap]: Subscribed to Topics: scan
[controller_server-11] [INFO] [1653293238.719295315] [local_costmap.local_costmap]: Initialized plugin "voxel_layer"
[controller_server-11] [INFO] [1653293238.719520082] [local_costmap.local_costmap]: Using plugin "inflation_layer"
[controller_server-11] [INFO] [1653293238.731776080] [local_costmap.local_costmap]: Initialized plugin "inflation_layer"
[controller_server-11] [INFO] [1653293238.800134046] [controller_server]: Created progress_checker : progress_checker of type nav2_controller::SimpleProgressChecker
[controller_server-11] [INFO] [1653293238.811294136] [controller_server]: Created goal_checker : goal_checker of type nav2_controller::SimpleGoalChecker
[controller_server-11] [FATAL] [1653293238.821499338] [controller_server]: Failed to create controller. Exception: According to the loaded plugin descriptions the class nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController with base class type nav2_core::Controller does not exist. Declared types are  dwb_core::DWBLocalPlanner
[lifecycle_manager-16] [ERROR] [1653293238.824019346] [lifecycle_manager_navigation]: Failed to change state for node: controller_server
[lifecycle_manager-16] [ERROR] [1653293238.824207109] [lifecycle_manager_navigation]: Failed to bring up all requested nodes. Aborting bringup.
[rosserial_node.py-3] 1653293239.293985 [0]    python3: using network interface wlx70f11c430a8c (udp/192.168.0.113) selected arbitrarily from: wlx70f11c430a8c, docker0
[rosserial_node.py-3] [INFO] [1653293239.759641396] [serial_node]: open port /dev/ttyS4
[rosserial_node.py-3] [INFO] [1653293239.771628323] [serial_node]: Requesting topics...
[rosserial_node.py-3] [INFO] [1653293239.816289560] [serial_node]: Note: publish buffer size is 512 bytes
[rosserial_node.py-3] [INFO] [1653293239.819013901] [serial_node]: Init service server for rosbot_ekf/Configuration
[rosserial_node.py-3] [INFO] [1653293239.821836941] [serial_node]: Setup service server on config [rosbot_ekf/Configuration]
[rosserial_node.py-3] [INFO] [1653293240.873853179] [serial_node]: Setup publisher on battery [sensor_msgs/BatteryState]
[rosserial_node.py-3] [INFO] [1653293241.026248366] [serial_node]: Setup publisher on pose [geometry_msgs/PoseStamped]
[rosserial_node.py-3] [INFO] [1653293241.035859283] [serial_node]: Setup publisher on velocity [geometry_msgs/Twist]
[rosserial_node.py-3] [INFO] [1653293241.046008887] [serial_node]: Setup publisher on range/fr [sensor_msgs/Range]
[rosserial_node.py-3] [INFO] [1653293241.055111056] [serial_node]: Setup publisher on range/fl [sensor_msgs/Range]
[rosserial_node.py-3] [INFO] [1653293241.064661641] [serial_node]: Setup publisher on range/rr [sensor_msgs/Range]
[rosserial_node.py-3] [INFO] [1653293241.075837854] [serial_node]: Setup publisher on range/rl [sensor_msgs/Range]
[rosserial_node.py-3] [INFO] [1653293241.086815781] [serial_node]: Setup publisher on joint_states [sensor_msgs/JointState]
[rosserial_node.py-3] [INFO] [1653293241.093113508] [serial_node]: TODO: Skipped publisher for rosbot_ekf
[rosserial_node.py-3] [INFO] [1653293241.097332616] [serial_node]: topic_id: 134
[rosserial_node.py-3] topic_name: "mpu9250"
[rosserial_node.py-3] message_type: "rosbot_ekf/Imu"
[rosserial_node.py-3] md5sum: "3d83bdcabfe2927ed38c36f102a9f646"
[rosserial_node.py-3] buffer_size: 512
[rosserial_node.py-3] [INFO] [1653293241.100386800] [serial_node]: Setup publisher on mpu9250 [rosbot_ekf/Imu]
[rosserial_node.py-3] [INFO] [1653293241.110797735] [serial_node]: Setup publisher on buttons [std_msgs/UInt8]
[rosserial_node.py-3] [INFO] [1653293241.117333290] [serial_node]: Note: subscribe buffer size is 512 bytes
[rosserial_node.py-3] [INFO] [1653293241.129511246] [serial_node]: Setup subscriber on cmd_vel [geometry_msgs/Twist]
[rosserial_node.py-3] [INFO] [1653293241.140447768] [serial_node]: Setup subscriber on cmd_ser [std_msgs/UInt32]
[rosserial_node.py-3] [INFO] [1653293241.147097612] [serial_node]: 
[rosserial_node.py-3] 
[rosserial_node.py-3]  ______  _____  _____  _             _           __
[rosserial_node.py-3]  | ___ \|  _  |/  ___|| |           | |         / _|
[rosserial_node.py-3]  | |_/ /| | | |\ `--. | |__    ___  | |_       | |_ __      __
[rosserial_node.py-3]  |    / | | | | `--. \| '_ \  / _ \ | __|      |  _|\ \ /\ / /
[rosserial_node.py-3]  | |\ \ \ \_/ //\__/ /| |_) || (_) || |_       | |   \ V  V / 
[rosserial_node.py-3]  \_| \_| \___/ \____/ |_.__/  \___/  \__|      |_|    \_/\_/ 
[rosserial_node.py-3] 
[rosserial_node.py-3]  Firmware version: 0.14.3
[rosserial_node.py-3] 
[rosserial_node.py-3] 
[rosserial_node.py-3] [INFO] [1653293241.156080254] [serial_node]: Detected sensor: MPU9255
[rosserial_node.py-3] 

Hi ELD,

Your launch files seems fine. According to error log map_server fails to load map because file is bad at line 1, where usually path to map image is specified. Be sure to copy both files (map.pgm and map.yaml) to the same directory. If this is not the problem consider creating a new map.

The /pose topis is not accually published, only subscribed by Rviz that’s why you can see it with ros2 topic list. When using AMCL you can make it to publish estimated positin to that topic.

Path to Gazebo world is specified inside rosbot_sim.launch.py so you can change the world there.

Regards,
Dawid