cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.64k stars 1.2k forks source link

Get occupancy grid from multi trajectory setup #1695

Open tristan-schwoerer opened 2 years ago

tristan-schwoerer commented 2 years ago

Hi,

I am currently working on a project that uses cartographer for mapping with multiple robots at the same time. For this i set up an environment similar to the proposed one here https://github.com/cschuet/cartographer_ros/tree/cloud_demo.

When looking at the submaps on the server i can see both trajectories and all of their submaps, yet when i run the occupancy grid node on the master i only get the map of the trajectory i started first.

Is there any way to get live updates of all trajectories?

I would highly appreciate any help on this. Thanks in advance, Tristan

sandilyasg commented 1 year ago

@Tristan9497 How do you set up and use the environment that uses cartographer for mapping with multiple robots at the same time from https://github.com/cschuet/cartographer_ros/tree/cloud_demo ? I am wondering how to set this up and which files to launch. Thanks

tristan-schwoerer commented 1 year ago

@sandilyasg You can take a look at our config folders from back then. https://github.com/JonathanESchmidt/ROB7LanguageSLAM/tree/main/languageslam%2Fconfig

I haven't worked on it a year or more. We were able to run multi robot slam but had problems with streaming the assembled map back to the robot

sandilyasg commented 1 year ago

@Tristan9497 Thanks so much for your prompt reply!! What does the general process look like? For example, which process would I follow from the following issues: #1300 #1165 Is is similar to what oprezz mentioned in #1165:

"I understand your task, I also did something very similar. To use the cartographer with multiple robots, you have to use it with the grpc extension.

Then you start the two robot which generates the sensors data, in different terimanals, with different ROS masters, e.g.: Terminal 1:

export GAZEBO_MASTER_URI=http://localhost:11312
ROS_MASTER_URI="http://localhost:11311" roslaunch robot_sim_pkg gazebo_robot1.launch

Terminal 2:

export GAZEBO_MASTER_URI=http://localhost:11112
ROS_MASTER_URI="http://localhost:11111" roslaunch robot_sim_pkg gazebo_robot2.launch

Terminal 3: ROS_MASTER_URI="http://localhost:11311" roslaunch cartographer_ros robot1_master.launch Terminal 4: ROS_MASTER_URI="http://localhost:11111" roslaunch cartographer_ros robot2_client.launch After this you can start the two cartographer nodes. One of them will be the cartographer master, the other one publishes its data to this master node.

The master node's launch file is something like this:

<launch>
<group>
  <env name="ROS_MASTER_URI" value="http://localhost:11311" />
  <param name="/use_sim_time" value="true" />

  <node name="cartographer_grpc_server" pkg="cartographer_ros"
      type="cartographer_grpc_server.sh" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename robot1.lua">
  </node>

  <node name="cartographer_node_robot1" pkg="cartographer_ros"
      type="cartographer_grpc_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename robot1_cloud.lua
          -server_address localhost:55555
          -client_id 1"
   output="screen">

         <remap from="scan_1" to="front_scan" />
         <remap from="scan_2" to="rear_scan" />
     <remap from="scan" to="car1/top_scanner" /> 
     <remap from="odom" to="car1/odom" />
  </node>

</group>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/config.rviz" />
</launch>

The other client cartographer launch file is something like this:


<launch>
<group>
  <env name="ROS_MASTER_URI" value="http://localhost:11311" />
  <param name="/use_sim_time" value="true" />

  <node name="cartographer_grpc_server" pkg="cartographer_ros"
      type="cartographer_grpc_server.sh" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename robot2_cloud.lua">
  </node>

  <node name="cartographer_node_robot2" pkg="cartographer_ros"
      type="cartographer_grpc_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename robot2.lua
          -server_address localhost:55555
          -client_id 2"
   output="screen">

         <remap from="scan_1" to="front_scan" />
         <remap from="scan_2" to="rear_scan" />
     <remap from="scan" to="car2/top_scanner" /> 
     <remap from="odom" to="car2/odom" />
  </node>

</group>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
</launch>

The robot1_cloud.lua contains information about the server entrypoint:

include "map_builder_server.lua"

MAP_BUILDER_SERVER.map_builder.use_trajectory_builder_2d = true
MAP_BUILDER_SERVER.server_address = "0.0.0.0:55555"

return MAP_BUILDER_SERVER

The robot2_cloud.lua defines the connection for the client:

include "map_builder_server.lua"

MAP_BUILDER_SERVER.map_builder.use_trajectory_builder_2d = true
MAP_BUILDER_SERVER.uplink_server_address = "localhost:55555"

return MAP_BUILDER_SERVER

"