Skip to content
James Heselden edited this page Jun 26, 2024 · 6 revisions

This page details the topological map, what it is used for, and some relevant details of the map format and links to supporting info.

overview

properties

format

Creation by Hand

To complete this, please familiarise yourself with the TMAP COMPONENTS documents.

A topological map is made up of a series of sections in a single YAML file.

Your map will be made of a collection of nodes, and edges connecting them together into a network.

  1. Opening: The map file begins with the opening, this contains meta information such as where the map is, when it was updated, and what name it should be referenced by.

Begin your file by including the OPENING section. Fill in the gen_time, and location f-strings with relevent details.

meta:
  last_updated: {gen_time}
metric_map: {location}
name: {location}
pointset: {location}
transformation:
  child: topo_map
  parent: map
  rotation:
    w: 1.0
    x: 0.0
    y: 0.0
    z: 0.0
  translation:
    x: 0.0
    y: 0.0
    z: 0.0
  1. Nodes:

To begin this section, you must start with the node list opening. The final line of the opening in the associated link includes the beginning of the nodes section.

nodes:

For each node in your map, you must then must then create a NODE block and insert this into your file. You must in this, populate the location for the map, and give the node a name. You must also include an position and orientation. The restrictions can be left as "True", and the vert can be left as "vert0".

- meta:
    map: {location}
    node: {name}
    pointset: {location}
  node:
    localise_by_topic: ''
    parent_frame: map
    name: {name}
    pose:
      orientation:
        w: 1.0
        x: 0.0
        y: 0.0
        z: 0.0
      position:
        x: {x}
        y: {y}
        z: 0.0
    properties:
      xy_goal_tolerance: 0.3
      yaw_goal_tolerance: 0.1
    restrictions_planning: {restrictions}
    restrictions_runtime: obstacleFree_1
    verts: *{vert}
  1. Edges:

At the end of the node section, needs to be an edges tag. Each node may have a collection of edges which a robot can use to leave the node and travel to other nodes. If the node has no edges, you can include the [EMPTY EDGEES] section (https://github.com/LCAS/environment_common/blob/30f18b2b334a093f65fd98a18e4e631d56505a17/environment_common/convertors/templating/tmap.py#L56).

    edges: []

If not empty, you must start with the EDGES START section.

    edges:

For each edge to be included, you must include an EDGE block.

In this block, the name fstring must refer to the node hosting this edge, and the node2 fstring must be the name of the node at the destination end of the edge. The action must be the navigation approach to be used, with the action_type being the message format. The restrictions here can also be left as "True".

    - edge_id: {name}_{name2}
      action: {action}
      action_type: {action_type}
      config: []
      fail_policy: fail
      fluid_navigation: true
      goal:
        target_pose:
          header:
            frame_id: $node.parent_frame
          pose: $node.pose
      node: {name2}
      recovery_behaviours_config: ''
      restrictions_planning: {restrictions}
      restrictions_runtime: obstacleFree_1
  1. End:

Finally, once all the nodes have been included and all the edges are assigned attached to each node, the closing must be included. Begin with a verts opening.

verts:

Then include the standard vertices shown in VERTS.

  verts:
  - verts: &vert0
    - x: -0.13
      y:  0.213
    - x: -0.242
      y:  0.059
    - x: -0.213
      y: -0.13
    - x: -0.059
      y: -0.242
    - x:  0.13
      y: -0.213
    - x:  0.242
      y: -0.059
    - x:  0.213
      y:  0.13
    - x:  0.059
      y:  0.242
  - verts: &vert1
    - x:  0.128
      y: -0.214
    - x:  0.175
      y: -0.071
    - x:  0.148
      y:  0.118
    - x:  0.061
      y:  0.241
    - x: -0.128
      y:  0.214
    - x: -0.175
      y: 0.071
    - x: -0.148
      y: -0.118
    - x: -0.061
      y: -0.241

Include this at the bottom and you are good to go, or you can create your CUSTOM VERTS. For instance if you include the below it will create a ring of your defined size.

  custom_verts:
  - verts: &{id}
    - x: {-0.130*sz}
      y: {0.213*sz}
    - x: {-0.242*sz}
      y: {0.059*sz}
    - x: {-0.213*sz}
      y: {-0.130*sz}
    - x: {-0.059*sz}
      y: {-0.242*sz}
    - x: {0.130*sz}
      y: {-0.213*sz}
    - x: {0.242*sz}
      y: {-0.059*sz}
    - x: {0.213*sz}
      y: {0.130*sz}
    - x: {0.059*sz}
      y: {0.242*sz}

Automated Creation

The facilities within the environment common repository offer capabilities for automated generation of topoological maps from various sources with the required information encoded.

Clone this wiki locally