[Documentation] [TitleIndex] [WordIndex

Overview

VoronoiGraph.png

This package includes the tuw_voronoi_graph_node, which generates a voronoi graph out of a pixel map and the tuw_segment_to_graph_node, which generates a graph out of segments.

tuw voronoi graph node

Receives a pixel map (occupancy_grid) and converts it into a tuw_multi_robot_msgs/Graph message spanning the whole free space of the map. Additionally the graph is saved to a given folder. If a map is already converted to a graph the graph is loaded from memory to save computation time.

Subscribed Topics

~map (nav_msgs/OccupancyGrid)

Published Topics

~segments (tuw_multi_robot_msgs/VoronoiGraph)

~map_eroded (nav_msgs/OccupancyGrid)

Parameters

~map_inflation (double default: "0.1" [m])

~segment_length (float default: "0.9")

~crossing_opimization (float default: "0.2")

~end_segment_optimization (float default: "0.4")

~graph_path (string default: ".")

~custom_graph_path (string default: "")

~publish_map_eroded (bool default: "false")

tuw dxf to graph node

This is a standard executable which takes a .dxf file as input and generates a graph which is saved to be loaded with the tuw_voronoi_graph_node.

The dxf file must contain the original map.pgm (e.g. used by map server) transformed by scale and offset, to give scale and offset to the application (Theoretically any image with the right scale and offset would work as well). Additionally lines, circles and arcs can be included, which are included to generate the segments. All elements which share an endpoint are connected.

Each resulting segment has a width, given by the command-line argument -w and a length, which has at least the length of the command-line argument [-l] and at max the length of [2*(-l) - epsilon].

Arguments

-h [ --help ]

-i [ --input ] arg (=./segments.dxf)

-o [ --output ] arg (=./graphs/segments)

-w [ --width ] arg (=0.600000024)

-l [ --length ] arg (=1)

tuw segment to graph node

Receives a pixel map (occupancy_grid) and converts it into a tuw_multi_robot_msgs/Graph message spanning the whole free space of the map. Additionally the graph is saved to a given folder. If a map is already converted to a graph the graph is loaded from memory to save computation time.

Subscribed Topics

Published Topics

~segments (tuw_multi_robot_msgs/VoronoiGraph)

Parameters

~segment_file (string default: "segments.yaml")

~segments_topic (string default: "/segments")

~segment_length (float default: "0.9")

Sample Segments File

start_x:      [      0,        2,   3.2,    5]
start_y:      [   -1.5,     -1.5,    -2,   -4]
end_x:        [      2,      3.2,     5,    3]
end_y:        [   -1.5,       -2,    -4,   -4]
space:        [    1.0,      1.0,   1.0,  1.0]
origin_x:     -15
origin_y:     -15
resolution:   0.05

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]


2024-07-13 14:39