Code Documentation

class rogata_library.GameObject(name, area, holes)[source]

A class defining the most basic game objects of the engine

Parameters:
  • name (string) – The name of the object
  • area (numpy array) – A array containin all borders of the object as a contour <https://docs.opencv.org/3.4/d4/d73/tutorial_py_contours_begin.html>
  • holes (numpy array) – Array specifying which border constitutes a inner or outer border
get_position()[source]

returns the position of the objects center

The center in this case refers to the mean position of the object. For a disjointed area this center can be outside of the object itself.

Returns:2D position of the objects center
Return type:numpy array
is_inside(point)[source]

Checks wheter a point is inside the area of the object

A point directl on the border is also considered inside

Parameters:point (2D numpy array) – A point which is to be checked
Returns:a truthvalue indicating wheter or not the point is inside the game object
Return type:bool
line_intersect(start, direction, length, iterations=100, precision=0.001)[source]

calculates the intersection between a line and the border of the object

Iterations and precision are kept at standart values if non are provided

Parameters:
  • start (numpy array) – a 2D point which specifies the start of the line
  • direction (numpy array) – a vector specifiying the direction of the line (it will be automatically normalized)
  • length (scalar) – a scalar specifiying the maximum length of the line
  • iterations (scalar) – the number of iterations for the ray marching algorithm used (Default value = 100)
  • precision (scalar) – the precision with which the intersection is being calculated (Default value = 0.001)
Returns:

2D position of the intersection

Return type:

numpy array

move_object(new_pos, rotate=0)[source]

moves the object to a new position and orientation

Parameters:
  • new_pos (numpy array) – new 2D position of the object
  • rotate (scalar) – angle of rotation in radians (Default value = 0)
shortest_distance(point)[source]

calculates the shortest distance between the point and the border of the object

Also returns a positive distance when inside the object

Parameters:point (numpy array) – A 2D point which is to be checked
Returns:distance to border of the object
Return type:scalar
class rogata_library.Scene(game_object_list)[source]

A class implemennting scene objects comprised of multiple GameObject objects. It offers Ros Client interfaces which allow other nodes to request information about the game objects. the communication interfaces are described in the documentation

Parameters:game_object_list – A list of containing :py:class`GameObject` objects.
handle_get_distance(request)[source]

Handles requests to the get_distance ROS service server

Parameters:request (RequestDistRequest) –
handle_get_position(request)[source]

Handles requests to get_position ROS service server

Parameters:request (GetPosRequest) –
handle_inside_check(request)[source]

Handles requests to the check_inside ROS service server

Parameters:request (CheckInsideRequest) –
handle_line_intersect(request)[source]

Handles requests to the intersect_line ROS service server

Parameters:request (RequestInterRequest) –
handle_set_position(request)[source]

Handles requests to the set_position ROS service server

Parameters:request (SetPosRequest) –
rogata_library.cart2pol(cart_x, cart_y)[source]

Converts a point (x,y) into polar coordinates (theta, rho)

rogata_library.detect_area(hsv_img, lower_color, upper_color, marker_id, min_size, draw=False)[source]

Detects the contour of an object containing a marker based on color

It always returns the smallest contour which still contains the marker The contour is detected using an image with hsv color space to be robust under different lighting conditions. If draw=True the systems draws all found contours as well as the current smalles one containing the marker onto hsv_img

Parameters:
  • hsv_image (numpy array) – a Image in hsv color space in which the contours should be detected
  • lower_color (numpy array) – a 3x1 array containing the lower boundary for the color detection
  • upper_color (numpy array) – a 3x1 array containing the upper boundary for the color detection
  • marker_id (scalar) – the ID of a 4x4 aruco marker which identifies the object
  • hsv_img
  • min_size
  • draw – (Default value = False)
class rogata_library.dynamic_object(name, hitbox, ID, initial_ori=0)[source]

A subclass of the basic GameObject.

Dynamic objects are able to change their position and can be tracked via aruco markers. Their current position is published by each :py:class`Scene` containing them.

Instead of initializing the object using a contour a dictionary describing a hitbox needs to be provided. The dynamic object then builds the contour.

Currently only rectangular hitboxes are supported. The dictionary of such a hitbox can be set up as follows:

{'type':'rectangle','height':HEIGHT,'width':WIDTH}

Where HEIGHT and WIDTH are the objects height and width in the game area.

Parameters:
  • name (string) – The name of the object
  • hitbox (dictionary) – A dictionary describing the shape of the objects contour
  • ID – The ID of an aruco marker which can be used to track the object
  • initial_ori – The inital orientation of the object in radians [0,2*pi]. Standart value is 0

;type number:

rogata_library.pol2cart(theta, rho)[source]

Converts polar coordinates (theta, rho) into cartesian coordinates (x,y)

class rogata_library.rogata_helper[source]

A class for people unfarmiliar with ROS.

It abstracts the ROS service communication with the Scene class into simply python functions.

dist(game_object, point)[source]
Abstracts the get_distance ROS service communication
to get the distance between a GameObject and a point
Parameters:
  • game_object (string) – The name of the game object whoose distance should be measured
  • point (2D numpy array) – the point to which the distance should be measured
get_pos(game_object)[source]
Abstracts the get_position ROS service communication
to set the position of a GameObject
Parameters:game_object (string) – The name of the game object
inside(game_object, point)[source]
Abstracts the check_inside Ros Service communication
to check wheter a given point is inside of a GameObject
Parameters:
  • game_object (string) – the name of the game object to check
  • point (2D numpy array) – The point to check
intersect(game_object, start_point, direction, length)[source]
Abstracts the intersect_line ROS service communication
to get the intersection between a GameObject and a line
Parameters:
  • game_object (string) – The name of the game object to intersect with
  • start_point (2D numpy array) – The start of the line
  • direction (scalar) – The direction of the line as an angle following ROS convetion
  • length (scalar) – The length of the line
set_pos(game_object, position)[source]
Abstracts the set_position ROS service communication
to set the position of a GameObject
Parameters:
  • game_object (string) – The name of the game object
  • position (2D numpy array) – The new position of the object
rogata_library.track_aruco_marker(gray_image, marker_id_list)[source]

Tracks a list of aruco markers

Returns None if the marker was not found in gray_image

Parameters:
  • gray_image – A grayscale image in which the marker is to be found
  • marker_id_list (list of numbers) – A list of marker ids
Returns:

A dictionary of marker positions with the marker_ids as keys

rogata_library.track_dynamic_objects(gray_image, object_name_list)[source]
Function which automatically tracks a list of dynamic_object
that are part of a Scene

The functions returns no position and instead updates the internal state of each dynamic_object. This position can be accessed using the interfaces of the Scene containing the objects.

Parameters:
  • gray_image – A grayscale image in which the objects should be tracked
  • object_name_list – A list of containing the names of the objects that should be tracked
calibrate_scene.calibrate_colors(image)[source]

Utility to calibrate the colors for contour detection

Allows the visual calibration of contours which can be saved by pressing the s key. Colors are defined in HSV color space. For each Value H, S and V the median value as well as the acceptable range can be defined. Additionally the ID of a aruco marker used to specify the wanted contour can be specified. Since this can sometimes lead to the contour being the outline of the marker, the minimum hole size in pixels can be specified.