Multiple Maps: create, save, clear during mapping; load different maps at run-time

Hello NVIDIA Isaac Team,

Our use-case briefly:

  • We require multiple, separate yet contiguous maps for a particular robot deployment. During mapping (with 2D Cartographer), we would like the ability to save the current occupancy map (as a png), clear the current occupancy map, then continue creating a new/second map.
  • Then during run-time localization our robot will determine when to transition from, for example, a default map 0 to map 1, and then do so by loading map 1.

Our questions:

  • Within the Isaac-wrapped implementation of Cartographer, is there an exposed API to Save the current map (png), Clear it, and Restart mapping? E.g. a programmatic mechanism equivalent to Ctrl-C to save, clear and restart?
  • Is there a programmatic way to load a new/different map at run-time? We acknowledge the existence of the map_json parameter of the Application object. However, later at run-time we require the ability to load a second (or third, etc) map based on path-planning logic.
  • Related, is there a programmatic way to get and set the origin of a Cartographer-created map, possibly through the isaac::map::Map object or other? This would allow us to appropriately set the origin of a second or third map such that it corresponds and is meaningful to the odometry of the robot as it travels and transitions into the new map.

Thank you!

@hemals
@skk_supreeth

  • Within the Isaac-wrapped implementation of Cartographer, is there an exposed API to Save the current map (png), Clear it, and Restart mapping? E.g. a programmatic mechanism equivalent to Ctrl-C to save, clear and restart?

You can try stopping the node that the Cartographer codelet is in which would be the same as saving+clear, then restarting the node again. From inside a codelet in the different node, you could try finding the node like so: node()->app()->backend()->node_backend()->findNodeByName() and then shutting is down or starting it up with startNode(Node*) and stopNode(Node*). There have been attempts to make this work for your case but many have instead reconfigured their whole app to be restarted rather than figure it out.

  • Is there a programmatic way to load a new/different map at run-time? We acknowledge the existence of the map_json parameter of the Application object. However, later at run-time we require the ability to load a second (or third, etc) map based on path-planning logic.

Unfortunately, no. You will have to shut down the subgraph and restart it to pick up a new map.

  • Related, is there a programmatic way to get and set the origin of a Cartographer-created map, possibly through the isaac::map::Map object or other? This would allow us to appropriately set the origin of a second or third map such that it corresponds and is meaningful to the odometry of the robot as it travels and transitions into the new map.

I didn’t quite follow here, but there is a world_T_map pose that lets you set where in the world frame the origin of the map and you could set different map frame names to work with different maps if this is for submapping.