simulation.utils.geometry package

Submodules

simulation.utils.geometry.frame module

Coordinate frame class that can be connected to other frames.

The idea of this class is to provide a simple API of dealing with geometric objects in multiple coordinate frames easily.

Classes:

Frame(name)

Functions:

validate_and_maintain_frames(func)

Ensure that both objects are in the same coordinate frame.

class Frame(name: str)[source]

Bases: object

Attributes:

name

Name of the frame.

_connected_frames

Dictionary with other connected frames.

Methods:

connect_to(frame, *, transformation_to_frame)

Connect this frame to another frame through a transformation.

name: str

Name of the frame.

_connected_frames: Dict[str, Transform]

Dictionary with other connected frames.

connect_to(frame: simulation.utils.geometry.frame.Frame, *, transformation_to_frame: Transform)[source]

Connect this frame to another frame through a transformation.

This also connects the other frame to this one.

validate_and_maintain_frames(func)[source]

Ensure that both objects are in the same coordinate frame.

simulation.utils.geometry.line module

Line.

Functions:

ensure_valid_arc_length(*[, approx_distance])

Check if an arc length is on the line and can be used for approximation.

Classes:

Line(*args[, frame])

List of points as a Line class inheriting from shapely’s LineString class.

ensure_valid_arc_length(*, approx_distance=5e-05)Callable[source]

Check if an arc length is on the line and can be used for approximation.

If the arc_length is too close to the end points of the line, it is moved further away from the edges.

Parameters

approx_distance (float) – Approximation step length to be used in further calculations. Arc length will be at least that far away from the end of the line.

class Line(*args, frame=None)[source]

Bases: shapely.geometry.linestring.LineString

List of points as a Line class inheriting from shapely’s LineString class.

Inheriting from shapely enables to use their powerful operations in combination with other objects, e.g. polygon intersections.

Initialization can be done in one of the following ways.

Parameters
  • 1 ([Point]) – List of points or anything that can be initialized as a point, e.g. Vector, geometry_msgs.Point,np.array)

  • 2 ([]) – Empty list creates an empty line.

Methods:

cut(line, arc_length)

Cuts a line in two at a arc_length from its starting point.

get_points()

Points of line.

parallel_offset(*args, **kwargs)

Returns a LineString or MultiLineString geometry at a distance from the object on its right or its left side.

simplify(*args, **kwargs)

Returns a simplified geometry produced by the Douglas-Peucker algorithm

smooth(*args, **kwargs)

interpolate_direction(arc_length)

interpolate_curvature(arc_length)

Interpolate the curvature at a given arc_length.

interpolate_pose(arc_length)

to_geometry_msgs()

To ROS geometry_msgs.

to_numpy()

To numpy array.

classmethod cut(line: simulation.utils.geometry.line.Line, arc_length: float)Tuple[simulation.utils.geometry.line.Line, simulation.utils.geometry.line.Line][source]

Cuts a line in two at a arc_length from its starting point.

See: https://shapely.readthedocs.io/en/latest/manual.html?highlight=cut#linear-referencing-methods

get_points()List[simulation.utils.geometry.point.Point][source]

Points of line.

Returns

list of points on the line.

Rotate the line tf.rotation around (0,0,0) and translate by tf.xyz

parallel_offset(*args, **kwargs)

Returns a LineString or MultiLineString geometry at a distance from the object on its right or its left side.

The side parameter may be ‘left’ or ‘right’ (default is ‘right’). The resolution of the buffer around each vertex of the object increases by increasing the resolution keyword parameter or third positional parameter. Vertices of right hand offset lines will be ordered in reverse.

The join style is for outside corners between line segments. Accepted values are JOIN_STYLE.round (1), JOIN_STYLE.mitre (2), and JOIN_STYLE.bevel (3).

The mitre ratio limit is used for very sharp corners. It is the ratio of the distance from the corner to the end of the mitred offset corner. When two line segments meet at a sharp angle, a miter join will extend far beyond the original geometry. To prevent unreasonable geometry, the mitre limit allows controlling the maximum length of the join corner. Corners with a ratio which exceed the limit will be beveled.

simplify(*args, **kwargs)

Returns a simplified geometry produced by the Douglas-Peucker algorithm

Coordinates of the simplified geometry will be no more than the tolerance distance from the original. Unless the topology preserving option is used, the algorithm may produce self-intersecting or otherwise invalid geometries.

smooth(*args, **kwargs)
interpolate_direction(arc_length)[source]
interpolate_curvature(arc_length: float)float[source]

Interpolate the curvature at a given arc_length.

The curvature is approximated by calculating the Menger curvature as defined and described here: https://en.wikipedia.org/wiki/Menger_curvature#Definition

Parameters

arc_length (float) – Length along the line starting from the first point

Raises

ValueError – If the arc_length is <0 or more than the length of the line.

Returns

Corresponding curvature.

interpolate_pose(arc_length)[source]
to_geometry_msgs()List[geometry_msgs.msg._Point.Point][source]

To ROS geometry_msgs.

Returns

This line as a list of geometry_msgs/Point.

to_numpy()numpy.ndarray[source]

To numpy array.

Returns

Line as a numpy array of np.arrays.

simulation.utils.geometry.point module

Basic point class which is compatible with all needed formats.

Exceptions:

InvalidPointOperationError

Classes:

Point(*args, **kwargs)

Point subclass of Vector which implements a point.

exception InvalidPointOperationError[source]

Bases: Exception

class Point(*args, **kwargs)[source]

Bases: simulation.utils.geometry.vector.Vector

Point subclass of Vector which implements a point.

Compared with its Superclass, this class imposes some restrictions to better fit the interpretation of a point in the mathematical sense.

Uses vector’s initializer.

Methods:

to_geometry_msg()

To ROS geometry_msg.

rotated(*args, **kwargs)

to_geometry_msg()geometry_msgs.msg._Point.Point[source]

To ROS geometry_msg.

Returns

This point as a geometry_msgs/Point

rotated(*args, **kwargs)[source]

simulation.utils.geometry.polygon module

Polygon.

Classes:

Polygon(*args[, frame])

Polygon class inheriting from shapely’s Polygon class.

class Polygon(*args, frame=None)[source]

Bases: shapely.geometry.polygon.Polygon

Polygon class inheriting from shapely’s Polygon class.

Inheriting from shapely enables to use their powerful operations in combination with other objects, e.g. polygon intersections.

Initialization can be done in one of the following ways.

Parameters
  • 1 ([Point]) – List of points or anything that can be initialized as a point, e.g. Vector, geometry_msgs.Point,np.array

  • 2 (geometry_msgs.Polygon) –

  • 3 ((Line,Line)) – Two lines which are interpreted as the left and right boundary of the polygon, e.g. a road lane

Methods:

get_points()

Points of polygon.

to_geometry_msg()

To ROS geometry_msg.

to_numpy()

To numpy array.

get_points()List[simulation.utils.geometry.point.Point][source]

Points of polygon.

Returns

list of points on the polygon.

to_geometry_msg()[source]

To ROS geometry_msg.

Returns

This polygon as a geometry_msgs.Polygon.

to_numpy()[source]

To numpy array.

Returns

Polygon as a numpy array of np.arrays.

simulation.utils.geometry.pose module

Pose.

Classes:

Pose(*args[, frame])

Pose class consisting of a position and an orientation.

class Pose(*args, frame=None)[source]

Bases: object

Pose class consisting of a position and an orientation.

A Pose object can be used to describe the state of an object with a position and an orientation. Initialization can be done in one of the following ways:

Parameters
  • 1 (geometry_msgs/Pose) – initialize from geometry_msgs.

  • 2 (Point, float) – Second argument is the poses’s orientation angle in radians.

  • 3 (Point, pyquaternion.Quaternion) – Point and quaternion.

position
Type

Point

orientation
Type

pyquaternion.Quaternion

Methods:

get_angle([axis])

Angle of orientation.

to_geometry_msg()

To ROS geometry_msg.

get_angle(axis=Vector(0.0, 0.0, 1.0))float[source]

Angle of orientation.

Returns

The angle that a vector is rotated, when this transformation is applied.

to_geometry_msg()geometry_msgs.msg._Pose.Pose[source]

To ROS geometry_msg.

Returns

This pose as a geometry_msgs/Pose.

simulation.utils.geometry.transform module

Transformation.

Classes:

Transform(*args[, frame])

Transformation class consisting of a translation and a rotation.

class Transform(*args, frame=None)[source]

Bases: object

Transformation class consisting of a translation and a rotation.

A Transform object can be used to easily interchange between multiple coordinate systems (which can be transformed in one another via a rotation and a translation.

Initialization can be done in one of the following ways:

Parameters
  • 1 (geometry_msgs/Transformation) – initialize from geometry_msgs.

  • 2 (Vector, float) – Second argument is the transformation’s rotation angle in radian.

  • 3 (Vector, pyquaternion.Quaternion) – Vector and quaternion.

tranlation
Type

Vector

rotation
Type

pyquaternion.Quaternion

Attributes:

inverse

Methods:

get_angle([axis])

Angle of rotation.

to_geometry_msg()

Convert transform to ROS geometry_msg.

to_affine_matrix()

Get transformation as an affine matrix.

property inverse
get_angle(axis=Vector(0.0, 0.0, 1.0))float[source]

Angle of rotation.

Parameters

axis – Axis the rotation is projected onto.

Returns

The angle that a vector is rotated, when this transformation is applied.

to_geometry_msg()geometry_msgs.msg._Transform.Transform[source]

Convert transform to ROS geometry_msg.

Returns

This transformation as a geometry_msgs/Transform.

to_affine_matrix()numpy.ndarray[source]

Get transformation as an affine matrix.

simulation.utils.geometry.vector module

Vector.

Classes:

Vector(*args, **kwargs)

Implementation of the mathematical vector object.

class Vector(*args, **kwargs)[source]

Bases: shapely.geometry.point.Point

Implementation of the mathematical vector object.

Inheriting from shapely enables to use their powerful operations in combination with other objects, e.g. lines, polygons.

Initialization can be done in one of the following ways.

Parameters
  • [x (np.array) –

  • y (np.array) –

  • z] (np.array) –

  • geometry_msgs/Vector

  • (x (float) –

  • y* (float) –

  • z*) (float) –

Keyword Arguments
  • r (float) – length of vector

  • phi (float) – angle between vector and x-y-plane

A vector is always initialized with 3 coordinates. If there’s no third coordinate provided, z:=0.

Methods:

from_geometry_msg(geometry_msg)

Initialize from ROS geometry_msg.

to_geometry_msg()

To ROS geometry_msg.

to_numpy()

To numpy array.

rotated(*args, **kwargs)

cross(*args, **kwargs)

Attributes:

argument

Return the argument of the vector in radian.

xy

xy-coordinates as a tuple.

classmethod from_geometry_msg(geometry_msg: geometry_msgs.msg._Vector3.Vector3)[source]

Initialize from ROS geometry_msg.

to_geometry_msg()geometry_msgs.msg._Vector3.Vector3[source]

To ROS geometry_msg.

Returns

This vector as a geometry_msgs/Vector3

to_numpy()numpy.ndarray[source]

To numpy array.

Returns

Vector as a numpy array.

rotated(*args, **kwargs)
cross(*args, **kwargs)
property argument: float

Return the argument of the vector in radian.

Type

float

property xy: Tuple[float, float]

xy-coordinates as a tuple.

Type

Tuple[float, float]

Module contents

Definition of the geometry module.

Collect classes and functions which should be included in the geometry module.

Classes:

Vector(*args, **kwargs)

Implementation of the mathematical vector object.

Point(*args, **kwargs)

Point subclass of Vector which implements a point.

Transform(*args[, frame])

Transformation class consisting of a translation and a rotation.

Pose(*args[, frame])

Pose class consisting of a position and an orientation.

Line(*args[, frame])

List of points as a Line class inheriting from shapely’s LineString class.

Polygon(*args[, frame])

Polygon class inheriting from shapely’s Polygon class.

class Vector(*args, **kwargs)[source]

Bases: shapely.geometry.point.Point

Implementation of the mathematical vector object.

Inheriting from shapely enables to use their powerful operations in combination with other objects, e.g. lines, polygons.

Initialization can be done in one of the following ways.

Parameters
  • [x (np.array) –

  • y (np.array) –

  • z] (np.array) –

  • geometry_msgs/Vector

  • (x (float) –

  • y* (float) –

  • z*) (float) –

Keyword Arguments
  • r (float) – length of vector

  • phi (float) – angle between vector and x-y-plane

A vector is always initialized with 3 coordinates. If there’s no third coordinate provided, z:=0.

Methods:

from_geometry_msg(geometry_msg)

Initialize from ROS geometry_msg.

to_geometry_msg()

To ROS geometry_msg.

to_numpy()

To numpy array.

rotated(*args, **kwargs)

cross(*args, **kwargs)

Attributes:

argument

Return the argument of the vector in radian.

xy

xy-coordinates as a tuple.

classmethod from_geometry_msg(geometry_msg: geometry_msgs.msg._Vector3.Vector3)[source]

Initialize from ROS geometry_msg.

to_geometry_msg()geometry_msgs.msg._Vector3.Vector3[source]

To ROS geometry_msg.

Returns

This vector as a geometry_msgs/Vector3

to_numpy()numpy.ndarray[source]

To numpy array.

Returns

Vector as a numpy array.

rotated(*args, **kwargs)
cross(*args, **kwargs)
property argument: float

Return the argument of the vector in radian.

Type

float

property xy: Tuple[float, float]

xy-coordinates as a tuple.

Type

Tuple[float, float]

class Point(*args, **kwargs)[source]

Bases: simulation.utils.geometry.vector.Vector

Point subclass of Vector which implements a point.

Compared with its Superclass, this class imposes some restrictions to better fit the interpretation of a point in the mathematical sense.

Uses vector’s initializer.

Methods:

to_geometry_msg()

To ROS geometry_msg.

rotated(*args, **kwargs)

to_geometry_msg()geometry_msgs.msg._Point.Point[source]

To ROS geometry_msg.

Returns

This point as a geometry_msgs/Point

rotated(*args, **kwargs)[source]
class Transform(*args, frame=None)[source]

Bases: object

Transformation class consisting of a translation and a rotation.

A Transform object can be used to easily interchange between multiple coordinate systems (which can be transformed in one another via a rotation and a translation.

Initialization can be done in one of the following ways:

Parameters
  • 1 (geometry_msgs/Transformation) – initialize from geometry_msgs.

  • 2 (Vector, float) – Second argument is the transformation’s rotation angle in radian.

  • 3 (Vector, pyquaternion.Quaternion) – Vector and quaternion.

tranlation
Type

Vector

rotation
Type

pyquaternion.Quaternion

Attributes:

inverse

Methods:

get_angle([axis])

Angle of rotation.

to_geometry_msg()

Convert transform to ROS geometry_msg.

to_affine_matrix()

Get transformation as an affine matrix.

property inverse
get_angle(axis=Vector(0.0, 0.0, 1.0))float[source]

Angle of rotation.

Parameters

axis – Axis the rotation is projected onto.

Returns

The angle that a vector is rotated, when this transformation is applied.

to_geometry_msg()geometry_msgs.msg._Transform.Transform[source]

Convert transform to ROS geometry_msg.

Returns

This transformation as a geometry_msgs/Transform.

to_affine_matrix()numpy.ndarray[source]

Get transformation as an affine matrix.

class Pose(*args, frame=None)[source]

Bases: object

Pose class consisting of a position and an orientation.

A Pose object can be used to describe the state of an object with a position and an orientation. Initialization can be done in one of the following ways:

Parameters
  • 1 (geometry_msgs/Pose) – initialize from geometry_msgs.

  • 2 (Point, float) – Second argument is the poses’s orientation angle in radians.

  • 3 (Point, pyquaternion.Quaternion) – Point and quaternion.

position
Type

Point

orientation
Type

pyquaternion.Quaternion

Methods:

get_angle([axis])

Angle of orientation.

to_geometry_msg()

To ROS geometry_msg.

get_angle(axis=Vector(0.0, 0.0, 1.0))float[source]

Angle of orientation.

Returns

The angle that a vector is rotated, when this transformation is applied.

to_geometry_msg()geometry_msgs.msg._Pose.Pose[source]

To ROS geometry_msg.

Returns

This pose as a geometry_msgs/Pose.

class Line(*args, frame=None)[source]

Bases: shapely.geometry.linestring.LineString

List of points as a Line class inheriting from shapely’s LineString class.

Inheriting from shapely enables to use their powerful operations in combination with other objects, e.g. polygon intersections.

Initialization can be done in one of the following ways.

Parameters
  • 1 ([Point]) – List of points or anything that can be initialized as a point, e.g. Vector, geometry_msgs.Point,np.array)

  • 2 ([]) – Empty list creates an empty line.

Methods:

cut(line, arc_length)

Cuts a line in two at a arc_length from its starting point.

get_points()

Points of line.

parallel_offset(*args, **kwargs)

Returns a LineString or MultiLineString geometry at a distance from the object on its right or its left side.

simplify(*args, **kwargs)

Returns a simplified geometry produced by the Douglas-Peucker algorithm

smooth(*args, **kwargs)

interpolate_direction(arc_length)

interpolate_curvature(arc_length)

Interpolate the curvature at a given arc_length.

interpolate_pose(arc_length)

to_geometry_msgs()

To ROS geometry_msgs.

to_numpy()

To numpy array.

classmethod cut(line: simulation.utils.geometry.line.Line, arc_length: float)Tuple[simulation.utils.geometry.line.Line, simulation.utils.geometry.line.Line][source]

Cuts a line in two at a arc_length from its starting point.

See: https://shapely.readthedocs.io/en/latest/manual.html?highlight=cut#linear-referencing-methods

get_points()List[simulation.utils.geometry.point.Point][source]

Points of line.

Returns

list of points on the line.

Rotate the line tf.rotation around (0,0,0) and translate by tf.xyz

parallel_offset(*args, **kwargs)

Returns a LineString or MultiLineString geometry at a distance from the object on its right or its left side.

The side parameter may be ‘left’ or ‘right’ (default is ‘right’). The resolution of the buffer around each vertex of the object increases by increasing the resolution keyword parameter or third positional parameter. Vertices of right hand offset lines will be ordered in reverse.

The join style is for outside corners between line segments. Accepted values are JOIN_STYLE.round (1), JOIN_STYLE.mitre (2), and JOIN_STYLE.bevel (3).

The mitre ratio limit is used for very sharp corners. It is the ratio of the distance from the corner to the end of the mitred offset corner. When two line segments meet at a sharp angle, a miter join will extend far beyond the original geometry. To prevent unreasonable geometry, the mitre limit allows controlling the maximum length of the join corner. Corners with a ratio which exceed the limit will be beveled.

simplify(*args, **kwargs)

Returns a simplified geometry produced by the Douglas-Peucker algorithm

Coordinates of the simplified geometry will be no more than the tolerance distance from the original. Unless the topology preserving option is used, the algorithm may produce self-intersecting or otherwise invalid geometries.

smooth(*args, **kwargs)
interpolate_direction(arc_length)[source]
interpolate_curvature(arc_length: float)float[source]

Interpolate the curvature at a given arc_length.

The curvature is approximated by calculating the Menger curvature as defined and described here: https://en.wikipedia.org/wiki/Menger_curvature#Definition

Parameters

arc_length (float) – Length along the line starting from the first point

Raises

ValueError – If the arc_length is <0 or more than the length of the line.

Returns

Corresponding curvature.

interpolate_pose(arc_length)[source]
to_geometry_msgs()List[geometry_msgs.msg._Point.Point][source]

To ROS geometry_msgs.

Returns

This line as a list of geometry_msgs/Point.

to_numpy()numpy.ndarray[source]

To numpy array.

Returns

Line as a numpy array of np.arrays.

class Polygon(*args, frame=None)[source]

Bases: shapely.geometry.polygon.Polygon

Polygon class inheriting from shapely’s Polygon class.

Inheriting from shapely enables to use their powerful operations in combination with other objects, e.g. polygon intersections.

Initialization can be done in one of the following ways.

Parameters
  • 1 ([Point]) – List of points or anything that can be initialized as a point, e.g. Vector, geometry_msgs.Point,np.array

  • 2 (geometry_msgs.Polygon) –

  • 3 ((Line,Line)) – Two lines which are interpreted as the left and right boundary of the polygon, e.g. a road lane

Methods:

get_points()

Points of polygon.

to_geometry_msg()

To ROS geometry_msg.

to_numpy()

To numpy array.

get_points()List[simulation.utils.geometry.point.Point][source]

Points of polygon.

Returns

list of points on the polygon.

to_geometry_msg()[source]

To ROS geometry_msg.

Returns

This polygon as a geometry_msgs.Polygon.

to_numpy()[source]

To numpy array.

Returns

Polygon as a numpy array of np.arrays.