Until now, I haven't paid a lot of attention to the way maps were configured,
as it wasn't of any importance. Now things changed, so let's stress out the following:
We have two robots in our project, and each of them is an independent
one. It means that, if Internet is down, robots should still function and
at least be able to return home.
That means they have to keep their own maps. Now, that is already implemented: instead of creating a centralized map server, I have separate map servers, one per robot. However, it also means that RViz receives two maps. You have probably noticed it, when in a SLAM session, one map is less bright: this is because maps are semi-transparent, and whichever map is displayed on top, is brighter:
Same applies to keepout maps: there are two of them.
For the RViz to display these maps in proper places, relative to each other, we need to make sure the "fixed frame" in RViz is set to "world", not to map or odom.
RViz config files are available in the archive.
The maze_with_charger.sdf world changed, too. It now has spherical_coordinates set to a random place in USA. What is important, same coordinates are used in code to initialize GPS: now ROS2 knows how to link map's X,Y to GPS coordinates.
<spherical_coordinates> <!-- Minnesota: never been there --> <surface_model>EARTH_WGS84</surface_model> <latitude_deg>44.98</latitude_deg> <longitude_deg>-93.27</longitude_deg> <elevation>256</elevation> <heading_deg>0</heading_deg> </spherical_coordinates>
As I am adding new files to the scripts folder (multi_bot_nav_01/multi_bot_nav_01) folder, I need to make them available in a package. To do it, I have to modify the setup.py:
'coordinator = multi_bot_nav_01.Coordinator:main', 'path_follower = multi_bot_nav_01.PathFollower:main', 'global_planner_straight_line = multi_bot_nav_01.GlobalPlannerStraightLine:main',
In a config folder, we have two config files: nav2_params.yaml and nav2_params_multi.yaml, one is for a single robot project, another is for multi robot project.
The difference is in the way I treat frames and topics: for multi robots case they have prefix (robot's name) so each robot can get its own messages. I believe it is possible to make it a single file, but it looks like keeping them separate is easier. For details, see earlier sections, where I created a multi robot project.
These config files are very important for localization, as they hold parameters for AMCL and Kalman Filter. Important thing here is that usually, in tutorials, you will see people creating two robot localization nodes, one with GPS and one without it.
I do not use this approach: GPS is not accurate enough, so it can only be used for rough position estimation; I use raw GPS for that purposes, plus filtered position produced by ROS2 robot localization node from /odom, /imu and /scal (lidar).
In the project, a PathFollower class is provided; as it moves the robot along the path, it gathers location data, so we can create a chart. You can see that amcl provides coordinates that strongly corellate with "odom" and GPS is... well, we can use it for initial pose estimation.
ROS2 uses amcl to run particle filters (see links section), robot localization node uses Kalman Filter, and together they provide a rather accurate pose estimation. However, keep in mind that in ROS2/Nav2 it all is true only for "flat" 2D map where 2D lidar shines.
Note that there are many non-obvious things that you will discover when working with settings files. Here is one example: suddenly, robot localization node doesn't publish filtered odometry with a strange message:
[amcl-13] [ERROR] [1695812295.338249158] [amcl]: (40) consecutive laser scan transforms failed: (Lookup would require extrapolation into the future. Requested time 7.050000 but the latest data is at time 6.949000, when looking up transform from frame [base_footprint] to frame [odom]) [planner_server-19] [INFO] [1695817013.238520386] [global_costmap.global_costmap_rclcpp_node]: Message Filter dropping message: frame 'lidar_link' at time 5.762 for reason 'the timestamp on the message is earlier than all the data in the transform cache'
There is a lot of discussions on forums, main "cure" being to synchronize time between computers (I only have one), or to rebuild ROS2 from sources...
What I found was, I used "base_footprint", while I was supposed to use "base_link", a very non-obvious reason... However, I was still not able to figure out how to make robot_localization_node to work with namespaces. What that means: In the code (PathFollower.py), I have a class member self.current_pose. Now, in a single robot project, it is possible to set this variable in the callback for filtered odometry. Filtered odometry is published by robot_localization_node (ekf) and it contains the most accurate combination of odom, imu and lidar data.
And it doesn't work with namespaces, so in multi-robot project I have to set the self.current_pose in AMCL callback. Not a big deal, but...
The only launch file that changed is "main" multi_simulation_launch.py, the rest of files are the same, and they work the same way, allowing access to localization and Nav2 functionality. Below, in a "Compiling and Running" section, I provided the corresponding commands.
As for multi_simulation_launch, let's take a look at important aspects of the code:
# (c) robotics.snowcron.com # Use: MIT license # Import necessary modules from launch import LaunchDescription import launch ... # Import global variables import sys sys.path.append("src/multi_bot_nav_01/launch") from globals import * # Here, we can either uncomment the section with single # robot, so its namespace is "", or uncomment section with # two robots. def generate_launch_description(): robots = [ # {'name': '', 'x_pos': -2.0, 'y_pos': 0.0, 'z_pos': 0.01, # "color_name" : "Green", "color_rgb" : "0 1 0 1"}, {'name': 'robot1', 'x_pos': 2.0, 'y_pos': 2.0, 'z_pos': 0.01, "color_name" : 'Yellow', "color_rgb" : "1 1 0 1"}, {'name': 'robot2', 'x_pos': 0.0, 'y_pos': 0.0, 'z_pos': 0.01, "color_name" : 'Blue', "color_rgb" : "0 0 1 1"}, ] # This array contains nodes. I find it more convenient # to initialize nodes later, in a cycle arrNodes = [] ... # For localization, time is very important. We need to # make sure all nodes use time from the same source, in our case, # it is /clock that Gazebo publishes use_sim_time = LaunchConfiguration('use_sim_time') ... # This change is necessary: I wasn't able to figure out how to # make Gazebo to come up with proper "use_sim_time", # as the result, the following code doesn't publish /clock # gazebo_node = ExecuteProcess( # cmd=['gazebo', '--verbose', world, '-s', # 'libgazebo_ros_factory.so'], # output='screen') # arrNodes.append(gazebo_node) # ... while this code does publish /clock # Note the use of exit handlers, if we close Gazebo, # all other nodes (like RViz) will be closed, too. gazebo_server_process = ExecuteProcess( cmd=['gzserver', '-s', 'libgazebo_ros_init.so', "-s", "libgazebo_ros_factory.so", world], on_exit=EmitEvent(event=Shutdown(reason='gazebo server exited')), #cwd=[def_worlds_dir], output='screen') arrNodes.append(gazebo_server_process) gazebo_client_process = ExecuteProcess( cmd=['gzclient'], #cwd=[def_worlds_dir], on_exit=EmitEvent(event=Shutdown(reason='gazebo client exited')), output='screen') arrNodes.append(gazebo_client_process) ... for robot in robots: ... # This node publishes filtered odometry robot_localization_node = Node( package='robot_localization', executable='ekf_node', name='ekf_filter_node', namespace=namespace, output='screen', parameters=[ namespaced_params, {'use_sim_time': use_sim_time } ], ) arrNodes.append(robot_localization_node) # We need to make sure all signifficant transformations are available # Robot state publisher will take care of robot's transformations, # as for static ones, for example, between maps and world, we have # ho do it ourself. node_tf_world_to_odom = launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', arguments=[str(robot['x_pos']), str(robot['y_pos']), str(robot['z_pos']), '0', '0', '0', '/world', robot['name'] + '/odom'], parameters=[{'use_sim_time': use_sim_time}], output='screen') arrNodes.append(node_tf_world_to_odom) node_tf_map_to_odom = launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', arguments=[str(robot['x_pos']), str(robot['y_pos']), str(robot['z_pos']), '0', '0', '0', robot['name'] + '/map', robot['name'] + '/odom'], parameters=[{'use_sim_time': use_sim_time}], output='screen') arrNodes.append(node_tf_map_to_odom) node_tf_world_to_map = launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', arguments=[#str(robot['x_pos']), str(robot['y_pos']), str(robot['z_pos']), '0', '0', '0', '0', '0', '0', '0', '0', '0', '/world', robot['name'] + '/map'], parameters=[{'use_sim_time': use_sim_time}], output='screen') arrNodes.append(node_tf_world_to_map) node_tf_world_to_keepout = launch_ros.actions.Node( package='tf2_ros', executable='static_transform_publisher', arguments=[#str(robot['x_pos']), str(robot['y_pos']), str(robot['z_pos']), '0', '0', '0', '0', '0', '0', '0', '0', '0', '/world', robot['name'] + '/keepout_mask'], parameters=[{'use_sim_time': use_sim_time}], output='screen') arrNodes.append(node_tf_world_to_keepout) # Now, in cycle, add nodes to launch description # Create the launch description and populate ld = LaunchDescription() for node in arrNodes: ld.add_action(node) return ld
As you can see, the only important difference is that we used the robot localization node.