diff --git a/.gitignore b/.gitignore
index 690a414..8bd14d9 100644
--- a/.gitignore
+++ b/.gitignore
@@ -47,6 +47,7 @@ qtcreator-*
# Emacs
.#*
+**/*.save
# Catkin custom files
CATKIN_IGNORE
diff --git a/environment_common/convertors/datum_to_kml.py b/environment_common/convertors/datum_to_kml.py
index 321525c..a5e3d7a 100644
--- a/environment_common/convertors/datum_to_kml.py
+++ b/environment_common/convertors/datum_to_kml.py
@@ -44,7 +44,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'riseholme_polytunnel'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
run({'src': src, 'location_name':location_name, 'line_col':'ff2f2fd3', 'line_width':'4', 'fill_col':'c02f2fd3'})
if __name__ == '__main__':
diff --git a/environment_common/convertors/datum_to_metric.py b/environment_common/convertors/datum_to_metric.py
index a71c107..374f2c3 100644
--- a/environment_common/convertors/datum_to_metric.py
+++ b/environment_common/convertors/datum_to_metric.py
@@ -59,7 +59,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'riseholme_polytunnel'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
run({'src': src, 'location_name':location_name})
if __name__ == '__main__':
diff --git a/environment_common/convertors/datum_to_satellite.py b/environment_common/convertors/datum_to_satellite.py
index 614524e..f85ea23 100644
--- a/environment_common/convertors/datum_to_satellite.py
+++ b/environment_common/convertors/datum_to_satellite.py
@@ -36,7 +36,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'riseholme_general_east_pathway'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name}
run(args)
diff --git a/environment_common/convertors/kml_copypaste_to_tmap.py b/environment_common/convertors/kml_copypaste_to_tmap.py
new file mode 100644
index 0000000..25deb23
--- /dev/null
+++ b/environment_common/convertors/kml_copypaste_to_tmap.py
@@ -0,0 +1,236 @@
+import sys, os
+import yaml
+from ament_index_python.packages import get_package_share_directory, get_package_prefix
+import xml.etree.ElementTree as ET
+from pprint import pprint
+
+from shapely.geometry import Point
+from shapely.geometry.polygon import Polygon
+
+from environment_common.convertors.templating.tmap import TMapTemplates
+from environment_common.convertors.tools.gps import calculate_displacement, calculate_distance_changes
+#from environment_common.convertors.tools.kml import KlmRead
+
+
+class KlmRead:
+
+ @classmethod
+ def polyline_to_dictlist(cls, polyline_str, name, tagtype, circuit=False):
+ pls = polyline_str.replace('\n','').replace('\t','').split(' ')[:-1]
+ coords = [g.split(',') for g in pls]
+ dictlist = [{'longitude':round(float(gnss[0]),6),
+ 'latitude': round(float(gnss[1]),6),
+ 'elevation':round(float(gnss[2]),6),
+ 'name': f"{name}"} for i,gnss in enumerate(coords)]
+ return dictlist
+
+ @classmethod
+ def get_coords(cls, root):
+ details = dict()
+ for i, base in enumerate(root[0]):
+ if 'Placemark' in base.tag:
+ name, coords = '', ''
+ tags = {field.tag.split('}')[-1]:field for field in base}
+ name = tags['name'].text
+ if 'LineString' in tags: continue
+ elif 'Point' in tags: continue
+ elif 'Polygon' in tags:
+ coords = tags['Polygon'][0][0][0].text
+ tagtype = 'Polygon'
+ details[name] = cls.polyline_to_dictlist(coords, name, tagtype)
+ return details
+
+
+def run(args=None):
+
+ # Load datum
+ datum_path = os.path.join(args['src'], 'config', 'location', 'datum.yaml')
+ if not os.path.isfile(datum_path):
+ datum_path = os.path.join(args['src'], 'config', 'location', 'datum_autogen.yaml')
+ with open(datum_path) as f:
+ data = f.read()
+ datum = yaml.safe_load(data)
+
+ # Load tmap
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network.tmap2.yaml')
+ if not os.path.isfile(tmap_path):
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
+ with open(tmap_path) as f:
+ data = f.read()
+ tmap = yaml.safe_load(data)
+
+ place_id = args['location_name']
+ lat = datum['datum_latitude']
+ lon = datum['datum_longitude']
+
+ print('If any properties such as actions, restrictions, exits of tollerance enforcements are to be defined, apply these first.')
+
+ # Select the kml file containing the regions
+ ENV = get_package_share_directory('environment_template')
+ kml_path = os.path.join(args['src'], 'config', 'topological', 'copypastes.kml')
+ while True:
+ print(f'Applying copypastes specified in `{kml_path}`. \nTo use a different KML, place the `.kml` file in: `environment_template/config/topological/` \n\n\nEnter the name of the file below, or press [ENTER] to continue:')
+ inp = input('>> environment_template/config/topological/')
+ print('\n')
+ print(inp)
+ if inp != '':
+ if not inp.endswith('.kml'):
+ print('Ensure you have included the correct file extension of: `.kml`\n\n')
+ else:
+ kml_path = os.path.join(args['src'], 'config', 'topological', inp)
+ break
+ else:
+ break
+ locations = dict()
+ tree = ET.parse(kml_path)
+ root = tree.getroot()
+
+ # Extract the polygon regions
+ placemarks = KlmRead.get_coords(root)
+ copy_polygons = []
+
+ # Convert polygons to datum
+ for name, place in placemarks.items():
+
+ # Convert gps points of polygon to netric relative to datum
+ for c in place:
+ c['y'], c['x'] = calculate_distance_changes(lat, lon, c['latitude'], c['longitude'])
+ polygon = [name, Polygon([(c['x'],c['y']) for c in place])]
+
+ # If placemark marks copy action
+ ## Copy polygons should be labelled such like 'copy/uuid'
+ if name.startswith('copy/'):
+ print(f'Polygon of type copy: {name}')
+ paste_polygons += [polygon]
+
+ # If placemark marks paste action
+ ## Copy polygons should be labelled such like 'paste/copy_uuid'
+ elif name.startswith('paste/'):
+ print(f'Polygon of type paste: {name}')
+ paste_polygons += [polygon]
+
+ # If placemark does not match known format
+ else:
+ print(f'Polygon does not match any pattern: {name}')
+
+
+ # Compile edge list and make nodes accessible by name
+ node_dict = dict()
+ edge_list = []
+ for n in tmap['nodes']:
+ node_dict[n['node']['name']] = n['node']
+ for e in n['node']['edges']:
+ edge_list += [[n['node']['name'], e]]
+
+
+
+ total_nodes = len(tmap['nodes'])
+ extra_nodes = []
+
+ # Actions are applied to an edge if both nodes of an edge are contained within a Polygon.
+ for polygon in paste_polygons:
+ paste, poly = polygon[0], polygon[1]
+
+ # Identify priority level
+ copy_uuid = paste.split('/')[1]
+ copy_poly = copy_polygons[copy_uuid]
+ copy_offset = copy_poly[1].pose[0] - paste_poly[1].pose[0]
+
+ # Apply copypaste to nodes
+ for n in tmap['nodes']:
+ P1 = Point(n['node']['pose']['position']['x'], n['node']['pose']['position']['y'])
+
+ if copy_poly.contains(P1):
+ p1 = copy.deepcopy(P1)
+
+ # Specify new Node ID and save reference
+ node_id = total_nodes + len(extra_nodes) + 1
+ new_nodes[n['node']['name']] = node_id
+ extra_nodes = node(p1.pose+copy_offset)
+
+ # Rename edges in extra_nodes
+ for n in extra_nodes:
+ old_name = n['node']['name']
+ new_name = new_nodes[n['node']['name']]
+
+ # Rename edges containing old_name, with new_name
+ for e in p1['node']['edges']:
+
+ # Update edge_id to use the new source
+ old_target = e['node']
+ e['edge_id'] = new_name + '_' + old_target
+
+ # Update edge_id to use the new target
+ if old_target in new_nodes:
+ new_target = new_nodes[old_target]
+ e['node'] = new_target
+ e['edge_id'] = new_name + '_' + new_target
+
+ # Handle if the target is outside the copy region
+ else:
+ print('Execute handling for if target is beyond the copy region')
+ print('perhaps we should do this by searching for if any other nodes')
+ print('are within the offset proximity of the taregt node')
+ print('if so, we can latch to a new target')
+ print('otherwise we have to delete the edge i guess')
+
+ # Search for nodes in region around target? but is the target ofset here?
+ x, y = n['node']['pose']['position']['x'], n['node']['pose']['position']['y']
+ polygon = Polygon( [(x+0,y+0), (x+n,y+0), (x+n,y+n), (x+0,y+n)] )
+
+ for n2 in tmap['nodes']:
+ P1 = Point(n2['node']['pose']['position']['x'], n2['node']['pose']['position']['y'])
+
+
+ # Add the node to the tmap
+ tmap['nodes'] += [n]
+
+
+
+
+
+ # Apply restrictions to nodes
+ for n in tmap['nodes']:
+ P1 = Point(n['node']['pose']['position']['x'], n['node']['pose']['position']['y'])
+
+ # Actions are applied to an edge if both nodes of an edge are contained within a Polygon.
+ for polygon in paste_polygons:
+ paste, poly = polygon[0], polygon[1]
+
+ if poly.contains(P1):
+
+ # Identify priority level
+ copy_uuid = paste.split('/')[1]
+
+ # Apply restriction to node if this restriction is a higher or equal priority
+ if ('restriction_priority' not in n) or (restriction_priority >= n['restriction_priority']):
+ print(f"node restricted with priority {restriction_priority} as {restriction}: {n['node']['name']}")
+ n['restrictions'] = restriction
+ n['restrictions_priority'] = restrictions_priority
+
+
+
+
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
+ with open(tmap_path, 'w') as f:
+ f.write(yaml.dump(tmap))
+
+
+
+def main(args=None):
+ print('This script is used to apply restrictions and actions to edges and nodes across a topological map.')
+ print('This is a roudementary system and should be used with a grain of salt.')
+ print('Navigation actions are applied to edges without problem.')
+ print('Restrictions are applied only to nodes, edges require manual intervention, while robots may be able to traverse across 2 nodes, it does not mean they can traverse between them.')
+ print('ohoh ohohoohoh we could apply a filter which uses a condition of if both nodes have same restrictions AND are in the same polygon region????')
+ e = 'environment_template'
+ src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
+ args = {'src': src, 'location_name':location_name}
+ run(args)
+
+if __name__ == '__main__':
+ main()
diff --git a/environment_common/convertors/kml_points_to_tmap.py b/environment_common/convertors/kml_points_to_tmap.py
new file mode 100644
index 0000000..effccc5
--- /dev/null
+++ b/environment_common/convertors/kml_points_to_tmap.py
@@ -0,0 +1,197 @@
+import sys, os
+import yaml
+from ament_index_python.packages import get_package_share_directory, get_package_prefix
+import xml.etree.ElementTree as ET
+from pprint import pprint
+
+from shapely.geometry import Point
+from shapely.geometry.polygon import Polygon
+
+from environment_common.convertors.templating.tmap import TMapTemplates
+from environment_common.convertors.tools.gps import calculate_displacement, calculate_distance_changes
+#from environment_common.convertors.tools.kml import KlmRead
+
+
+class KlmRead:
+
+ @classmethod
+ def polyline_to_dictlist(cls, polyline_str, name, tagtype, circuit=False):
+ pls = polyline_str.replace('\n','').replace('\t','').split(' ')[:-1]
+ coords = [g.split(',') for g in pls]
+ dictlist = [{'longitude':round(float(gnss[0]),6),
+ 'latitude': round(float(gnss[1]),6),
+ 'elevation':round(float(gnss[2]),6),
+ 'name': f"{name}"} for i,gnss in enumerate(coords)]
+ return dictlist
+
+ @classmethod
+ def get_coords(cls, root):
+ details = dict()
+ for i, base in enumerate(root[0]):
+ if 'Placemark' in base.tag:
+ name, coords = '', ''
+ tags = {field.tag.split('}')[-1]:field for field in base}
+ name = tags['name'].text
+ if 'LineString' in tags: continue
+ elif 'Polygon' in tags: continue
+ coords = tags['Polygon'][0][0][0].text
+ tagtype = 'Polygon'
+ elif 'Point' in tags:
+ coords = tags['Point'][0].text
+ tagtype = 'Point'
+ details[name] = cls.polyline_to_dictlist(coords, name, tagtype)
+ return details
+
+
+def run(args=None):
+
+ # Load datum
+ datum_path = os.path.join(args['src'], 'config', 'location', 'datum.yaml')
+ if not os.path.isfile(datum_path):
+ datum_path = os.path.join(args['src'], 'config', 'location', 'datum_autogen.yaml')
+ with open(datum_path) as f:
+ data = f.read()
+ datum = yaml.safe_load(data)
+
+ # Load tmap
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network.tmap2.yaml')
+ if not os.path.isfile(tmap_path):
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
+ with open(tmap_path) as f:
+ data = f.read()
+ tmap = yaml.safe_load(data)
+
+ place_id = args['location_name']
+ lat = datum['datum_latitude']
+ lon = datum['datum_longitude']
+
+ # Select the kml file containing the regions
+ ENV = get_package_share_directory('environment_template')
+ kml_path = os.path.join(args['src'], 'config', 'topological', 'actions.kml')
+ kml_path = os.path.join(args['src'], 'config', 'topological', 'r_nr_man_tmap_regions.kml')
+ while True:
+ print(f'Applying actions specified in `{kml_path}`. \nTo use a different KML, place the `.kml` file in: `environment_template/config/topological/` \n\n\nEnter the name of the file below, or press [ENTER] to continue:')
+ inp = input('>> environment_template/config/topological/')
+ print('\n')
+ print(inp)
+ if inp != '':
+ if not inp.endswith('.kml'):
+ print('Ensure you have included the correct file extension of: `.kml`\n\n')
+ else:
+ kml_path = os.path.join(args['src'], 'config', 'topological', inp)
+ break
+ else:
+ break
+ locations = dict()
+ tree = ET.parse(kml_path)
+ root = tree.getroot()
+
+ # Extract the waypoints
+ placemarks = KlmRead.get_coords(root)
+ name_rules = []
+ name_points = []
+ name_regions = []
+
+ # Convert polygons to datum
+ for name, place in placemarks.items():
+
+ # Convert gps points of polygon to netric relative to datum
+ for c in place:
+ c['y'], c['x'] = calculate_distance_changes(lat, lon, c['latitude'], c['longitude'])
+ if len(place) > 1:
+ placemark = [name, Polygon([(c['x'],c['y']) for c in place])]
+ else:
+ placemark = [name, place]
+
+ # If placemark is a region a naming convention should be applied
+ ## Naming rule polygons should be labelled such like 'renaming_rule/r[*]-c[*]'
+ if name.startswith('renaming_rule/'):
+ print(f'Polygon of type rule: {name}')
+ name_rules += [placemark]
+
+ # If placemark is a node point
+ ## Points should be labelled such like 'renaming_point/WayPoint121
+ elif name.startswith('renaming_point/'):
+ print(f'Point of type name: {name}')
+ name_points += [placemark]
+
+ # If placemark is a polygon to surround a node
+ ## Namey polygons should be labelled such like 'renaming_polygon/WayPoint120'
+ elif name.startswith('renaming_polygon/'):
+ print(f'Polygon of type name: {name}')
+ name_regions += [placemark]
+
+ # If placemark does not match known format
+ else:
+ print(f'Polygon does not match any pattern: {name}')
+
+
+ # Create dictionary to use for renaming process
+ rename_dict = dict()
+
+ # Find closest node to point
+ for nam in name_points:
+ name, point = nam[0], nam[1]
+ closest = None
+ closest_distance = -1
+ for n in tmap['nodes']:
+ dist = math.sqrt((point['x'] - n['node']['pose']['position']['x'])**2 + \
+ (point['y'] - n['node']['pose']['position']['y'])**2)
+ if closest_distance < 0 or dist < closest_dist:
+ closest = n['node']['name']
+ closest_distance = dist
+ print(f"Closest node to {name} is {closest}")
+ rename_dict[closest] = name
+
+ # Find node within polygon (assume only one)
+ for nam in name_regions:
+ name, poly = nam[0], nam[1]
+ for n in tmap['nodes']:
+ P1 = Point(n['node']['pose']['position']['x'], n['node']['pose']['position']['y'])
+ if poly.contains(P1):
+ print(f"Polygon {name} contains {n['node']['name']}")
+ rename_dict[n['node']['name']] = name
+ break
+
+ # Loop through each node replacing the names marked for replacement
+ for n in tmap['nodes']:
+
+ # Rename node details
+ if n['node']['name'] in rename_dict:
+ new = rename_dict[n['node']['name']]
+ n['meta']['node'] = new
+ n['node']['name'] = new
+
+ # Rename edge content
+ for e in n['edges']:
+
+ # Rename destination nodes
+ if e['node'] in rename_dict:
+ new = rename_dict[n['node']['name']]
+
+ # Rename edge_id components
+ eids = e['edge_id'].split('_')
+ if eids[0] in rename_dict:
+ eids[0] = rename_dict[eids[0]]
+ if eids[1] in rename_dict:
+ eids[1] = rename_dict[eids[1]]
+
+ # Save result
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
+ with open(tmap_path, 'w') as f:
+ f.write(yaml.dump(tmap))
+
+
+
+def main(args=None):
+ e = 'environment_template'
+ src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
+ args = {'src': src, 'location_name':location_name}
+ run(args)
+
+if __name__ == '__main__':
+ main()
diff --git a/environment_common/convertors/kml_regions_to_tmap.py b/environment_common/convertors/kml_regions_to_tmap.py
new file mode 100644
index 0000000..6673eb0
--- /dev/null
+++ b/environment_common/convertors/kml_regions_to_tmap.py
@@ -0,0 +1,224 @@
+import sys, os
+import yaml
+from ament_index_python.packages import get_package_share_directory, get_package_prefix
+import xml.etree.ElementTree as ET
+from pprint import pprint
+
+from shapely.geometry import Point
+from shapely.geometry.polygon import Polygon
+
+from environment_common.convertors.templating.tmap import TMapTemplates
+from environment_common.convertors.tools.gps import calculate_displacement, calculate_distance_changes
+#from environment_common.convertors.tools.kml import KlmRead
+
+
+class KlmRead:
+
+ @classmethod
+ def polyline_to_dictlist(cls, polyline_str, name, tagtype, circuit=False):
+ pls = polyline_str.replace('\n','').replace('\t','').split(' ')[:-1]
+ coords = [g.split(',') for g in pls]
+ dictlist = [{'longitude':round(float(gnss[0]),6),
+ 'latitude': round(float(gnss[1]),6),
+ 'elevation':round(float(gnss[2]),6),
+ 'name': f"{name}"} for i,gnss in enumerate(coords)]
+ return dictlist
+
+ @classmethod
+ def get_coords(cls, root):
+ details = dict()
+ for i, base in enumerate(root[0]):
+ if 'Placemark' in base.tag:
+ name, coords = '', ''
+ tags = {field.tag.split('}')[-1]:field for field in base}
+ name = tags['name'].text
+ if 'LineString' in tags: continue
+ elif 'Point' in tags: continue
+ elif 'Polygon' in tags:
+ coords = tags['Polygon'][0][0][0].text
+ tagtype = 'Polygon'
+ details[name] = cls.polyline_to_dictlist(coords, name, tagtype)
+ return details
+
+
+def run(args=None):
+
+ # Load datum
+ datum_path = os.path.join(args['src'], 'config', 'location', 'datum.yaml')
+ if not os.path.isfile(datum_path):
+ datum_path = os.path.join(args['src'], 'config', 'location', 'datum_autogen.yaml')
+ with open(datum_path) as f:
+ data = f.read()
+ datum = yaml.safe_load(data)
+
+ # Load tmap
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network.tmap2.yaml')
+ if not os.path.isfile(tmap_path):
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
+ with open(tmap_path) as f:
+ data = f.read()
+ tmap = yaml.safe_load(data)
+
+ place_id = args['location_name']
+ lat = datum['datum_latitude']
+ lon = datum['datum_longitude']
+
+ # Select the kml file containing the regions
+ ENV = get_package_share_directory('environment_template')
+ kml_path = os.path.join(args['src'], 'config', 'topological', 'actions.kml')
+ kml_path = os.path.join(args['src'], 'config', 'topological', 'r_nr_man_tmap_regions.kml')
+ while True:
+ print(f'Applying actions specified in `{kml_path}`. \nTo use a different KML, place the `.kml` file in: `environment_template/config/topological/` \n\n\nEnter the name of the file below, or press [ENTER] to continue:')
+ inp = input('>> environment_template/config/topological/')
+ print('\n')
+ print(inp)
+ if inp != '':
+ if not inp.endswith('.kml'):
+ print('Ensure you have included the correct file extension of: `.kml`\n\n')
+ else:
+ kml_path = os.path.join(args['src'], 'config', 'topological', inp)
+ break
+ else:
+ break
+ locations = dict()
+ tree = ET.parse(kml_path)
+ root = tree.getroot()
+
+ # Extract the polygon regions
+ placemarks = KlmRead.get_coords(root)
+ action_polygons = []
+ restriction_polygons = []
+ boundary_polygons = []
+
+ # Convert polygons to datum
+ for name, place in placemarks.items():
+
+ # Convert gps points of polygon to netric relative to datum
+ for c in place:
+ c['y'], c['x'] = calculate_distance_changes(lat, lon, c['latitude'], c['longitude'])
+ polygon = [name, Polygon([(c['x'],c['y']) for c in place])]
+
+ # If placemark marks actions
+ ## Action polygons should be labelled such like 'action/move_base/move_base_msgs/MoveBaseGoal'
+ if name.startswith('action/'):
+ print(f'Polygon of type action: {name}')
+ action_polygons += [polygon]
+
+ # If placemark marks restrictions
+ ## Restriction polygons should be labelled such like 'restriction/robot_short & robot_hunter'
+ elif name.startswith('restrictions/'):
+ print(f'Polygon of type restriction: {name}')
+ restriction_polygons += [polygon]
+
+ # If placemark mark map boundaries
+ ## Boundary polygons should be labelled such like 'exits/12'
+ elif name.startswith('exits/'):
+ print(f'Polygon of type boundary: {name}')
+ boundary_polygons += [polygon]
+
+ # If placemark does not match known format
+ else:
+ print(f'Polygon does not match any pattern: {name}')
+
+
+ # Compile edge list and make nodes accessible by name
+ node_dict = dict()
+ edge_list = []
+ for n in tmap['nodes']:
+ node_dict[n['node']['name']] = n['node']
+ for e in n['node']['edges']:
+ edge_list += [[n['node']['name'], e]]
+
+ # Apply actions to edges
+ for e in edge_list:
+ n_from, n_to = node_dict[e[0]], node_dict[e[1]['node']]
+ P1 = Point(n_from['pose']['position']['x'], n_to['pose']['position']['y'])
+ P2 = Point(n_to['pose']['position']['x'], n_to['pose']['position']['y'])
+
+ # Actions are applied to an edge if both nodes of an edge are contained within a Polygon.
+ for polygon in action_polygons:
+ act, poly = polygon[0], polygon[1]
+ if poly.contains(P1) and poly.contains(P2):
+
+ # Identify priority level
+ acts = act.split('/')
+ if len(acts) == 5:
+ action = acts[2]
+ action_type = acts[3] + "/" + acts[4]
+ action_priority = acts[1]
+ else:
+ action = acts[1]
+ action_type = acts[2] + "/" + acts[3]
+ action_priority = 0
+
+ # Apply action to edge if this action is a higher or equal priority
+ if ('action_priority' not in e[1]) or (action_priority >= e[1]['action_priority']):
+ print(f"edge actioned as {action} with priority of {action_priority} and type {action_type}")
+ e[1]['action'] = action
+ e[1]['action_type'] = action_type
+ e[1]['action_priority'] = action_priority
+
+ # Apply restrictions to nodes
+ for n in tmap['nodes']:
+ P1 = Point(n['node']['pose']['position']['x'], n['node']['pose']['position']['y'])
+
+ # Restrictions are applied to nodes first
+ for polygon in restriction_polygons:
+ rest, poly = polygon[0], polygon[1]
+ if poly.contains(P1):
+
+ # Identify priority level
+ rests = rest.split('/')
+ if len(rests) == 3:
+ restriction = rests[2]
+ restriction_priority = rests[1]
+ else:
+ restriction = rests[1]
+ restriction_priority = 0
+
+ # Apply restriction to node if this restriction is a higher or equal priority
+ if ('restriction_priority' not in n) or (restriction_priority >= n['restriction_priority']):
+ print(f"node restricted with priority {restriction_priority} as {restriction}: {n['node']['name']}")
+ n['restrictions'] = restriction
+ n['restrictions_priority'] = restrictions_priority
+
+ # Apply boundary marks to nodes
+ for n in tmap['nodes']:
+ P1 = Point(n['node']['pose']['position']['x'], n['node']['pose']['position']['y'])
+
+ # Restrictions are applied to nodes first
+ for polygon in boundary_polygons:
+ bound, poly = polygon[0], polygon[1]
+ if poly.contains(P1):
+ print(f"node marked as boundary by {bound}: {n['node']['name']}")
+ n['node']['properties']['boundarys'] = True
+
+ # Apply restrictions to edges
+ #for e in tmap['nodes']['']:
+ # #if both edges have the same restriction, we should add it to the edge too?
+ # #but what if the restrictions are different?
+
+
+ tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
+ with open(tmap_path, 'w') as f:
+ f.write(yaml.dump(tmap))
+
+
+
+def main(args=None):
+ print('This script is used to apply restrictions and actions to edges and nodes across a topological map.')
+ print('This is a roudementary system and should be used with a grain of salt.')
+ print('Navigation actions are applied to edges without problem.')
+ print('Restrictions are applied only to nodes, edges require manual intervention, while robots may be able to traverse across 2 nodes, it does not mean they can traverse between them.')
+ print('ohoh ohohoohoh we could apply a filter which uses a condition of if both nodes have same restrictions AND are in the same polygon region????')
+ e = 'environment_template'
+ src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
+ args = {'src': src, 'location_name':location_name}
+ run(args)
+
+if __name__ == '__main__':
+ main()
diff --git a/environment_common/convertors/kml_to_datum.py b/environment_common/convertors/kml_to_datum.py
index 233a22d..a643c9a 100644
--- a/environment_common/convertors/kml_to_datum.py
+++ b/environment_common/convertors/kml_to_datum.py
@@ -53,7 +53,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'riseholme_field_1'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
run({'src': src, 'location_name':location_name})
if __name__ == '__main__':
diff --git a/environment_common/convertors/kml_to_tmap.py b/environment_common/convertors/kml_to_tmap.py
index ff497d3..1dc9552 100644
--- a/environment_common/convertors/kml_to_tmap.py
+++ b/environment_common/convertors/kml_to_tmap.py
@@ -1,4 +1,4 @@
-import sys, os
+import sys, os, random
import yaml
from ament_index_python.packages import get_package_share_directory, get_package_prefix
import xml.etree.ElementTree as ET
@@ -54,61 +54,259 @@ def get_coords(cls, root):
return details
-def group_similar_coords(coord_dict_list):
+def group_similar_coords(coord_dict_list, aoe=1.5):
+ print(f'\n------------------------\n\nGrouping Nodes with aoe of {aoe}')
# Add initial labels for use in filtering later
- for i in range(len(coord_dict_list)):
- coord_dict_list[i]['name'] = str(i)
- coord_dict_list[i]['keep'] = False
- coord_dict_list[i]['clear'] = False
+ for node in coord_dict_list:
+ node['keep'] = False
+ node['clear'] = False
+ node['victims'] = [node['name']]
+
+ # Show connections
+ #print('\nConnections')
+ #pprint([[c['name'], [int(w.replace('WayPoint', '')) for w in c['connections']]] for c in coord_dict_list])
# Mark each node as to be cleared or kept
for node in coord_dict_list:
+
# Skip if node is already to be cleared
if node['clear']: continue
+
# Mark node to keep (first time seeing node)
node['keep'] = True
- node['cleared_by'] = node['raw_name']
- la, lo = node['latitude'], node['longitude']
+ node['cleared_by'] = node['name']
+ x1, y1 = node['x'], node['y']
for node2 in coord_dict_list:
+
# Skip if node has been viewed already
if node2['keep'] or node2['clear']: continue
+
# If node 1 and node 2 are within close proximity, clear node 2
- la2, lo2 = node2['latitude'], node2['longitude']
- if abs(la-la2) < 0.00001 and abs(lo-lo2) < 0.00001:
+ x2, y2 = node2['x'], node2['y']
+ if abs(x1-x2) < aoe and abs(y1-y2) < aoe:
+
# Mark node for clearance so it is not viewed anymore
node2['clear'] = True
- node2['cleared_by'] = node['raw_name']
- # Copy the cleared nodes connections into the kept node's details
- node['raw_connections'] += node2['raw_connections']
+ # Copy all victim nodes into the one being kept
+ # node is absobing all nodes already absorbed by the target
+ #print('@', node['name'], '=', node['victims'], '\n|', node2['name'], '=', node2['victims'], '\n')
+ node['victims'] += node2['victims']
+
+ ## Copy the absorbed nodes connections into the kept node's details
+ node['connections'].update(node2['connections'])
+
+
+ # Create reference dictionary
+ cdl = {node['name']:node for node in coord_dict_list}
+ rename = {node['name']:node['name'] for node in coord_dict_list}
+
+ # Loop through the cdl victims and apply the parent node to the rename block
+ for n in coord_dict_list:
+ for v in n['victims']:
+ if v != n['name']:
+ rename[v] = n['name']
+
+ # Show new owners
+ print('\n\nRenaming: dict[victim] = king')
+ pprint({int(k.replace('WayPoint', '')):v for k,v in rename.items() if k != v})
- #pprint(coord_dict_list)
+ # Show mergings
+ print('\n\nMergings: dict[king] = victims')
+ pprint({c['name']: [int(w.replace('WayPoint', '')) for w in c['victims'] if w != c['name']] for c in coord_dict_list if not c['clear'] and len(c['victims']) > 1})
- keeps = ['latitude', 'longitude', 'elevation', 'raw_name', 'raw_connections']
+ # Begin tidying the node details
+ keeps = ['name', 'connections', 'x', 'y']
kept = [{f:n[f] for f in keeps} for n in coord_dict_list if not n['clear']]
- for i in range(len(kept)):
- kept[i]['name'] = f"WayPoint{i+1}"
- final_convertor = {cdl['raw_name']: cdl['name'] for cdl in kept}
- convertor = {cdl['raw_name']: final_convertor[cdl['cleared_by']] for cdl in coord_dict_list}
- for k in kept:
- print('keeping? '+str(k))
- k['connections'] = set(convertor[c] if c in convertor else c for c in k['raw_connections'])
- del k['raw_connections'], k['raw_name']
- #[print(c) for c in kept]
+ # Rename connections using rename dictionary
+ for node in kept:
+ node['connections'] = {rename[c] for c in node['connections']}
+
+ # When a neighbour is copied in, it brings its edge to the new owner
+ # ... we just need to filter that out
+ for node in kept:
+ node['connections'] = {n for n in node['connections'] if n != node['name']}
+
+ print(f"\n\nReduced {len(coord_dict_list)} raw points down to {len(kept)} by {len(coord_dict_list)-len(kept)}")
+ check_diff(kept)
+
return kept
+def get_intersecting_point(line1node1, line1node2, line2node1, line2node2, buffer=1.5):
+ c1a = [line1node1['x'], line1node1['y']]
+ c1b = [line1node2['x'], line1node2['y']]
+ c2a = [line2node1['x'], line2node1['y']]
+ c2b = [line2node2['x'], line2node2['y']]
+
+
+ a1 = (c1b[1] - c1a[1]) / (c1b[0] - c1a[0])
+ a2 = (c2b[1] - c2a[1]) / (c2b[0] - c2a[0])
+
+ b1 = -1
+ b2 = -1
+
+ c1 = c1a[1] - (a1 * c1a[0])
+ c2 = c2a[1] - (a2 * c2a[0])
+
+ try:
+ # fix float division by 0 error? not sure what causes it though...
+ if (a1*b2) - (a2*b1) == 0 or (a1*b2) - (a2*b1) == 0:
+ return (None, None)
+
+ x = ( (b1*c2) - (b2*c1) ) / ( (a1*b2) - (a2*b1) )
+ y = ( (c1*a2) - (c2*a1) ) / ( (a1*b2) - (a2*b1) )
+
+ if ((x+buffer) < min([c1a[0],c1b[0]]) or (x-buffer) > max([c1a[0], c1b[0]])):
+ #print('x outside of line 1')
+ return (None, None)
+ elif ((y+buffer) < min([c1a[1],c1b[1]]) or (y-buffer) > max([c1a[1], c1b[1]])):
+ #print('y outside of line 1')
+ return (None, None)
+ elif ((x+buffer) < min([c2a[0],c2b[0]]) or (x-buffer) > max([c2a[0], c2b[0]])):
+ #print('x outside of line 2')
+ return (None, None)
+ elif ((y+buffer) < min([c2a[1],c2b[1]]) or (y-buffer) > max([c2a[1], c2b[1]])):
+ #print('y outside of line 2')
+ return (None, None)
+ else:
+ #print('intersection occured')
+ return (x, y)
+
+ except Exception as e:
+ print('\n--------------------\n\n')
+ print([line1node1['name'], line1node1['x'], line1node1['y']])
+ print([line1node2['name'], line1node2['x'], line1node2['y']])
+ print([line2node1['name'], line2node1['x'], line2node1['y']])
+ print([line2node2['name'], line2node2['x'], line2node2['y']])
+ print('\n\n\n')
+ print(e)
+ print( (b1*c2) - (b2*c1) )
+ print( (a1*b2) - (a2*b1) )
+ print( (c1*a2) - (c2*a1) )
+ print( (a1*b2) - (a2*b1) )
+ input('>')
+
+
+def split_intersecting_lines(coord_dict_list, overlap_aoe=1.5):
+ print(f'\n------------------------\n\nSplitting edges at intersections')
+
+ cdl = {c['name']:c for c in coord_dict_list}
+ highest_wp = max([int(node['name'].replace('WayPoint','')) for node in coord_dict_list])
+
+ # Loop through all edges
+ counter = 0
+ new_intersections = []
+ checked_intersections = []
+ for i, line1node1 in enumerate(coord_dict_list):
+ print(f'Completed {i}/{len(coord_dict_list)}')
+ for c1 in line1node1['connections']:
+ line1node2 = cdl[c1]
+
+ for j, line2node1 in enumerate(coord_dict_list):
+ for c2 in line2node1['connections']:
+ line2node2 = cdl[c2]
+
+ # Check the ends of the lines are different
+ lines = {'line1': [line1node1['name'], line1node2['name']], 'line2':[line2node1['name'], line2node2['name']]}
+ names = set([line1node1['name'], line1node2['name'], line2node1['name'], line2node2['name']])
+ if len(names) < 4:
+ continue
+ if names in checked_intersections:
+ continue
+
+ # Determine if intersection is within bounds
+ x, y = get_intersecting_point(line1node1, line1node2, line2node1, line2node2, buffer=overlap_aoe)
+ if x:
+
+ # Compile details for new node
+ counter += 1
+ wp = 'WayPoint'+str(highest_wp+counter)
+ new_intersections += [{'name': wp, 'x':x, 'y':y, 'connections': names, 'lines': lines}]
+
+
+ checked_intersections += [names]
+
+
+ print('Total Intersections:', counter, '\n\n---\n\n')
+ for i, new in enumerate(new_intersections):
+ #print(i, ':', new['name'])
+
+ for ln in ['line1', 'line2']:
+ n1, n2 = cdl[new['lines'][ln][0]], cdl[new['lines'][ln][1]]
+ #print('line:', ln, 'connecting', n1['name'], 'and', n2['name'])
+
+
+ # Swap the edges to reference the new intersection node instead
+ n1['connections'].add(new['name'])
+ if n2['name'] in n1['connections']: n1['connections'].remove(n2['name'])
+
+ n2['connections'].add(new['name'])
+ if n1['name'] in n2['connections']: n2['connections'].remove(n1['name'])
+
+ #print('---\n')
+
+ no_intersections_coord_dict_list = [v for v in cdl.values()] + new_intersections
+ return no_intersections_coord_dict_list
+
+
+
+
+def refresh_names(coord_dict_list):
+
+ # Assign proper names to each node
+ for i, node in enumerate(allpoints):
+ node['name'] = f"WayPoint{i+1}"
+
+
+def convert_raw_to_wp(coord_dict_list):
+
+ # Create dictionary to convert raw_connection ids to WayPoint names
+ convertor = {n['raw_name']:n['name'] for n in coord_dict_list}
+
+ # Apply convertor to nodes and edges
+ for n in coord_dict_list:
+ n['name'] = convertor[n['raw_name']]
+ n['connections'] = set([convertor[c] for c in n['raw_connections']])
+ del n['raw_connections'], n['raw_name']
+
+ return coord_dict_list
+
+
+
+def check_diff(coord_dict_list):
+ nodes_check = set([c['name'] for c in coord_dict_list])
+ edges_check = set(sum([list(c['connections']) for c in coord_dict_list],[]))
+ edge_length = [len(c['connections']) for c in coord_dict_list]
+ #print('unique node targets', len(nodes_check))
+ #print('unique edge targets', len(edges_check))
+
+ checks = edges_check.symmetric_difference(nodes_check)
+
+ if checks:
+ print('\n')
+ print('nodes without edges', sorted(nodes_check.difference(edges_check)))
+ print('edges without nodes', sorted(edges_check.difference(nodes_check)))
+ print('lens?', sorted(edge_length))
+ print('difference between?', sorted([int(i.replace('WayPoint', '')) for i in list(checks)]), '\n\n')
+
+ print('quitting...')
+ quit()
+
+
+
def run(args=None):
+ # Load the datum file to use for cvonverting gps to metric
datum_path = os.path.join(args['src'], 'config', 'location', 'datum.yaml')
if not os.path.isfile(datum_path):
datum_path = os.path.join(args['src'], 'config', 'location', 'datum_autogen.yaml')
@@ -121,9 +319,11 @@ def run(args=None):
lon = datum['datum_longitude']
+ # Acquire the kml file to convert to tmap
ENV = get_package_share_directory('environment_template')
kml_path = os.path.join(args['src'], 'config', 'topological', 'raw_connections.kml')
while True:
+# break
print(f'Constructing tmap from `{kml_path}`. \nTo use a different KML, place the `.kml` file in: `environment_template/config/topological/` \n\n\nEnter the name of the file below, or press [ENTER] to continue:')
inp = input('>> environment_template/config/topological/')
print('\n')
@@ -136,15 +336,20 @@ def run(args=None):
break
else:
break
+
+
+ # Parse the kml file into a dictionary for us to use
locations = dict()
tree = ET.parse(kml_path)
root = tree.getroot()
coords = KlmRead.get_coords(root)
- #pprint(coords)
- allpoints = sum(coords.values(),[])
- #[print(f"{l['longitude']} : {l['latitude']}) \t-- {l['raw_name']} {l['raw_connections']}") for l in allpoints]
+ # Get the coordinates and connections for each node
+ allpoints = sum(coords.values(),[])
+ print(f"Identified {len(allpoints)} points")
+ print(f"\n> allpoints")
+ print("\t", allpoints[0].keys())
lesspoints = group_similar_coords(allpoints)
print(lesspoints)
for l in lesspoints:
@@ -152,32 +357,113 @@ def run(args=None):
[print(f"{l['name']} ({l['longitude']}:{l['latitude']}) - {l['connections']}") for l in lesspoints]
print(f"Reduced {len(allpoints)} raw points down to {len(lesspoints)}")
- #[print(f"{l['name']} ({round(l['x'],1)}:{round(l['y'],1)}) - {l['connections']}") for l in lesspoints]
+ # Assign proper names to each node
+ for i, node in enumerate(allpoints):
+ node['name'] = f"WayPoint{i+1}"
+
+
+ # Convert raw_connections to connections
+ allnodes = convert_raw_to_wp(allpoints)
+ print(f"\n> allnodes")
+ print("\t", allnodes[0].keys())
+ check_diff(allnodes)
+
+
+ # Convert nodes to metric
+ for a in allnodes:
+ a['y'], a['x'] = calculate_distance_changes(lat, lon, a['latitude'], a['longitude'])
+ del a['longitude'], a['latitude'], a['elevation']
+ print(f"\n> allnodes")
+ print("\t", allnodes[0].keys())
+ check_diff(allnodes)
+
+ # Group the points within 1.5m into single nodes
+ lessnodes = group_similar_coords(allnodes, aoe=1.5)
+ print(f"Reduced {len(allnodes)} raw points down to {len(lessnodes)}")
+ print(f"\n> lessnodes")
+ print("\t", lessnodes[0].keys())
+ check_diff(lessnodes)
+ #lessnodes = allnodes
+
+
+ print('\n')
+ pprint({c['name']:[c['connections'], c['x'], c['y']] for c in lessnodes})
+
+
+ # Segment overlapping lines
+ nocrosses = split_intersecting_lines(lessnodes, overlap_aoe=1.5)
+ print(f"Added an additional {len(nocrosses)-len(lessnodes)} nodes at intersecting lines.")
+ print(f"\n> nocrosses")
+ print("\t", nocrosses[0].keys())
+ check_diff(nocrosses)
+ #nocrosses = lessnodes
+
+
+ print('\n')
+ pprint({c['name']:[c['connections'], c['x'], c['y']] for c in nocrosses})
+
+
+ # Group the points within 1.5m into single nodes
+ lessnocrosses = group_similar_coords(nocrosses, aoe=1.5)
+ print(f"Reduced {len(nocrosses)} intersecting points down to {len(lessnocrosses)}")
+ print(f"\n> lessnocrosses")
+ print("\t", lessnocrosses[0].keys())
+ check_diff(lessnocrosses)
+
+
+ print('\n')
+ [print(f"{c['name']}\t({round(c['x'],1)},{round(c['y'],1)})\t{c['connections']}\n") for c in lessnocrosses]
+
+ print('\n\n\n\n\n')
+ print('WARNING: EACH INTERSECTION NODE CONNECTS ONLY TO ITS BOUNDARIES, NOT TO ANY OTHER NODES')
+
+ # Begin construction of the tmap file
tmap = TMapTemplates.vert_sample
+
+
+ # Create a set of standard vertices
#tmap += TMapTemplates.vert_opening
#tmap += TMapTemplates.vert_ring.format(**{'id':'vert2', 'sz':1})
+
+ # Begin formatting of nodes for file
print('|\n|\n|\n|\n|', place_id)
tmap += TMapTemplates.opening.format(**{'gen_time':0, 'location':place_id})
+
+ # Define common properties to apply
node = {'location':place_id, 'vert': 'vert1', 'restrictions':'robot', 'connections':None}
- edge = {'action':'move_base', 'action_type':'move_base_msgs/MoveBaseGoal', 'restrictions':'robot'}
- for l in lesspoints:
- node.update({'name':l['name'], 'x':l['x'], 'y':l['y']})
+ edge = {'action':'move_base', 'action_type':'move_base_msgs/MoveBaseGoal', 'restrictions':'True'}
+
+
+ # Loop through each node and create the node object
+ for l in lessnocrosses:
+ node.update({'name':l['name'], 'x':l['x'], 'y':l['y'], 'connections':l['connections']})
tmap += TMapTemplates.node.format(**node)
- if not l['connections']:
+
+ # If the node has no edges, apply empty edge template
+ if not node['connections']:
tmap += TMapTemplates.edges_empty
+
+ # If the node has edges, create edge objects to insert
else:
tmap += TMapTemplates.edges_start
for c in l['connections']:
edge.update({'name':l['name'], 'name2':c})
+ i = random.randint(1,10)
+ edge.update({'action':f'a{i}', 'action_type':f'a{i}/a'})
tmap += TMapTemplates.edges.format(**edge)
+ #print(l['name'], l['connections'])
+
+ # Save file
tmap_path = os.path.join(args['src'], 'config', 'topological', 'network_autogen.tmap2.yaml')
print(tmap_path)
with open(tmap_path, 'w') as f:
f.write(tmap)
+
+ # Copy to GDRIVE link for quick verification
if os.getenv('GDRIVE_PATH', ""):
gdrive_path = os.path.join(os.getenv('GDRIVE_PATH'), 'Google Earth', 'kml', 'network_autogen.tmap2.yaml')
with open(gdrive_path, 'w') as f:
diff --git a/environment_common/convertors/metric_to_kml.py b/environment_common/convertors/metric_to_kml.py
index 2d05cb5..dcf6ca9 100644
--- a/environment_common/convertors/metric_to_kml.py
+++ b/environment_common/convertors/metric_to_kml.py
@@ -101,7 +101,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'r_gep'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name}
run(args)
diff --git a/environment_common/convertors/navgraph_to_tmap.py b/environment_common/convertors/navgraph_to_tmap.py
index c86fadc..be136b5 100644
--- a/environment_common/convertors/navgraph_to_tmap.py
+++ b/environment_common/convertors/navgraph_to_tmap.py
@@ -76,7 +76,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'r_gep'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name}
run(args)
diff --git a/environment_common/convertors/osm_to_datum.py b/environment_common/convertors/osm_to_datum.py
index 56274d0..7c5463b 100644
--- a/environment_common/convertors/osm_to_datum.py
+++ b/environment_common/convertors/osm_to_datum.py
@@ -17,6 +17,10 @@ def run(args=None):
osm_path = os.path.join(args['src'], 'config', 'topological', 'osm.xml')
if not os.path.isfile(osm_path):
osm_path = os.path.join(args['src'], 'config', 'topological', 'osm_autogen.xml')
+ if not os.path.isfile(osm_path):
+ osm_path = os.path.join(args['src'], 'config', 'topological', 'map.osm')
+ if not os.path.isfile(osm_path):
+ osm_path = os.path.join(args['src'], 'config', 'topological', 'map_autogen.osm')
root = getroot(osm_path)
tree = gettree(root)
@@ -46,7 +50,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'r_gep'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name}
run(args)
diff --git a/environment_common/convertors/osm_to_kml.py b/environment_common/convertors/osm_to_kml.py
index 98540dc..3c9f2e1 100644
--- a/environment_common/convertors/osm_to_kml.py
+++ b/environment_common/convertors/osm_to_kml.py
@@ -73,7 +73,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'r_gep'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name}
run(args)
diff --git a/environment_common/convertors/osm_to_tmap.py b/environment_common/convertors/osm_to_tmap.py
index fced7df..64a5365 100644
--- a/environment_common/convertors/osm_to_tmap.py
+++ b/environment_common/convertors/osm_to_tmap.py
@@ -28,6 +28,10 @@ def run(args=None):
osm_path = os.path.join(args['src'], 'config', 'topological', 'osm.xml')
if not os.path.isfile(osm_path):
osm_path = os.path.join(args['src'], 'config', 'topological', 'osm_autogen.xml')
+ if not os.path.isfile(osm_path):
+ osm_path = os.path.join(args['src'], 'config', 'topological', 'map.osm')
+ if not os.path.isfile(osm_path):
+ osm_path = os.path.join(args['src'], 'config', 'topological', 'map_autogen.osm')
root = getroot(osm_path)
tree = gettree(root)
@@ -77,6 +81,7 @@ def run(args=None):
'lat':float(c['lat']), 'lon':float(c['lon']),
'raw_connections':connections,
'raw_name':c['ref'],
+ 'action': wtd['highway'],
'keep':False,
'clear':False}
@@ -134,8 +139,8 @@ def run(args=None):
tmap += TMapTemplates.edges_start
for c in n['connections']:
if c == n['name']: continue
- connection_name = n['name'] #+"_"+c['ref']
edge.update({'name':n['name'], 'name2':c})
+ edge.update({'action':n['action']})
tmap += TMapTemplates.edges.format(**edge)
# Save tmap file
@@ -153,7 +158,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'r_gep'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name}
run(args)
diff --git a/environment_common/convertors/tmap_to_kml.py b/environment_common/convertors/tmap_to_kml.py
index a7734c4..8bc9f65 100644
--- a/environment_common/convertors/tmap_to_kml.py
+++ b/environment_common/convertors/tmap_to_kml.py
@@ -59,7 +59,10 @@ def run(args=None):
def main(args=None):
e = 'environment_template'
src = '/'.join(get_package_prefix(e).split('/')[:-2]) + f'/src/{e}'
- location_name = 'riseholme_polytunnel'
+ location_name = os.getenv('FIELD_NAME')
+ if not location_name:
+ print('missing ENVVAR FIELD_NAME, not continuing')
+ return
args = {'src': src, 'location_name':location_name, 'line_col':'ff2f2fd3', 'line_width':'4', 'fill_col':'c02f2fd3', 'shape_size':0.000005}
run(args)
diff --git a/launch/environment.launch.py b/launch/environment.launch.py
index b1c2e15..97756dc 100644
--- a/launch/environment.launch.py
+++ b/launch/environment.launch.py
@@ -124,8 +124,5 @@ def generate_launch_description():
arguments=['-d', rviz_input]
))
-
## Execute all Components
return LD
-
-
diff --git a/launch/topological_restrictions.launch.py b/launch/topological_restrictions.launch.py
new file mode 100644
index 0000000..6cdfd23
--- /dev/null
+++ b/launch/topological_restrictions.launch.py
@@ -0,0 +1,124 @@
+# -*- coding: utf-8 -*-
+#! /usr/bin/env python3
+# ----------------------------------
+# @author: jheselden
+# @email: jheselden@lincoln.ac.uk
+# @date:
+# ----------------------------------
+
+import os
+from os.path import join
+
+
+from ament_index_python.packages import get_package_share_directory
+
+from launch_ros.actions import Node, SetParameter
+
+from launch import LaunchDescription
+from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument, GroupAction
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration, Command
+
+
+def either(folder, file1, file2):
+ return f"{folder}/{file1}" if os.path.exists(f"{folder}/{file1}") else f"{folder}/{file2}"
+
+def generate_launch_description():
+ CONF = join(get_package_share_directory('environment_common'), 'config')
+ ENV = join(get_package_share_directory('environment_template'), 'config')
+ LD = LaunchDescription()
+
+ # Define default values for parameters
+ metric_default_value = either(join(ENV, 'metric', 'map'), 'map.yaml', 'map_autogen.yaml')
+ tmap_default_value = either(join(ENV, 'topological'), 'network.tmap2.yaml', 'network_autogen.tmap2.yaml')
+ gazebo_default_value = either(join(ENV, 'world'), 'gazebo.world', 'gazebo_autogen.world')
+ #
+ rviz_default_value = join(CONF, 'topomap_marker.rviz')
+
+
+ # Declare the launch arguments
+ LD.add_action(DeclareLaunchArgument('map', default_value=metric_default_value))
+ LD.add_action(DeclareLaunchArgument('tmap', default_value=tmap_default_value))
+ LD.add_action(DeclareLaunchArgument('world', default_value=gazebo_default_value))
+ #
+ LD.add_action(DeclareLaunchArgument('rviz', default_value=rviz_default_value))
+
+
+ # Define references for the arg inputs to be saved
+ map_input = LaunchConfiguration('map')
+ tmap_input = LaunchConfiguration('tmap')
+ gazebo_input = LaunchConfiguration('world')
+ #
+ rviz_input = LaunchConfiguration('rviz')
+
+
+ # Declare namespace
+ #namespace = LaunchConfiguration('namespace')
+ #LD.add_action(DeclareLaunchArgument('namespace', default_value=namespace, description='Top-level namespace'))
+
+
+ # Display status
+ print('\n'*5)
+ print('--'*10)
+ print('Default map:', metric_default_value)
+ print('Default tmap:', tmap_default_value)
+ print('Default gazebo:', gazebo_default_value)
+ print('--'*10)
+ print('Loading map:', map_input)
+ print('Loading tmap:', tmap_input)
+ print('Loading gazebo:', gazebo_input)
+ print('--'*10)
+ print('\n'*5)
+
+
+ ## Topological Map Server
+ LD.add_action(Node(
+ package='topological_navigation',
+ executable='map_manager2.py',
+ name='topomap2_server',
+ arguments=[tmap_input]
+ ))
+ LD.add_action(Node(
+ package='topological_navigation',
+ executable='topological_transform_publisher.py',
+ name='topological_transform_publisher'
+ ))
+ LD.add_action(Node(
+ package='topological_navigation',
+ executable='topomap_marker2.py',
+ name='topomap_marker2'
+ ))
+
+ ## Restrictions Handler Example
+ LD.add_action(Node(
+ package='topological_navigation',
+ executable='restrictions_handler.py',
+ name='restrictions_handler',
+ parameters=[{'enable_eval_sub': True},
+ {'initial_restriction': "'robot_short' in '$' or '$' == 'True'"}],
+ remappings=[('/topological_map_2', '/topological_map_2')]
+ ))
+ LD.add_action(Node(
+ package='topological_navigation',
+ executable='topological_transform_publisher.py',
+ name='restricted_topological_transform_publisher',
+ remappings=[('/topological_map_2', '/restrictions_handler/topological_map_2')]
+ ))
+ LD.add_action(Node(
+ package='topological_navigation',
+ executable='topomap_marker2.py',
+ name='restricted_topomap_marker2',
+ remappings=[('/topological_map_2', '/restrictions_handler/topological_map_2')]
+ ))
+
+
+ ## RViz2
+ LD.add_action(Node(
+ package='rviz2',
+ executable='rviz2',
+ arguments=['-d', rviz_input]
+ ))
+
+
+ ## Execute all Components
+ return LD
diff --git a/package.xml b/package.xml
index d921ff6..158c07c 100644
--- a/package.xml
+++ b/package.xml
@@ -9,6 +9,7 @@
Apache 2.0
nav2_map_server
+ python3-shapely
ament_python
diff --git a/setup.py b/setup.py
index 67fd691..b2069cb 100644
--- a/setup.py
+++ b/setup.py
@@ -23,6 +23,8 @@
'console_scripts': [
'kml_to_datum.py = environment_common.convertors.kml_to_datum:main',
'kml_to_tmap.py = environment_common.convertors.kml_to_tmap:main',
+ 'kml_regions_to_tmap.py = environment_common.convertors.kml_regions_to_tmap:main',
+ 'kml_points_to_tmap.py = environment_common.convertors.kml_points_to_tmap:main',
'osm_to_datum.py = environment_common.convertors.osm_to_datum:main',
'osm_to_kml.py = environment_common.convertors.osm_to_kml:main',
'osm_to_tmap.py = environment_common.convertors.osm_to_tmap:main',