soccer_common.camera.Camera

class soccer_common.camera.Camera(robot_name: str)[source]

Bases: object

This is a reusable class that instantiates an instance of a Camera object that listens to the camera related topics related to a robot and has useful functions that use geometry to determine the 3d/2d projection and location of things

__init__(robot_name: str)[source]

Initializes the camera object

Parameters:

robot_name – Name of the robot, to be used in subscribers

Methods

__init__(robot_name)

Initializes the camera object

calculateBallFromBoundingBoxes([...])

Reverse function for calculateBoundingBoxesFromBall(), takes the bounding boxes of the ball as seen on the camera and return the 3D position of the ball assuming that the ball is on the ground

calculateBoundingBoxesFromBall(ball_position)

Takes a 3D ball transformation and returns the bounding boxes of the ball if seen on camera

calculateHorizonCoverArea()

Given the camera's position, return the area that is covered by the horizon (that is not the field area) in pixels from the top position :return: Pixel length from the top of the image to the point where it meets the horizon

cameraInfoCallback(camera_info)

Callback function for the camera info subscriber

findCameraCoordinate(pos)

From a 3d position on the field, get the camera coordinate, opposite of findFloorCoordinate()

findCameraCoordinateFixedCamera(pos)

Helper function for findCameraCoordinate(), finds the camera coordinate if the camera were fixed at the origin

findFloorCoordinate(pos)

From a camera pixel, get a coordinate on the floor

imageToWorldFrame(pixel_x, pixel_y)

From image pixel coordinates, get the coordinates of the pixel as if they have been projected ot the camera plane, which is positioned at (0,0) in 3D world coordinates https://docs.google.com/presentation/d/10DKYteySkw8dYXDMqL2Klby-Kq4FlJRnc4XUZyJcKsw/edit#slide=id.g163680c589a_0_0

ready()

Function to determine when the camera object has recieved the necessary information and is ready to be used

reset_position([from_world_frame, ...])

Resets the position of the camera, it uses a series of methods that fall back on each other to get the location of the camera

worldToImageFrame(pos_x, pos_y)

Reverse function for imageToWorldFrame(), takes the 3D world coordinates of the camera plane and returns pixels

Attributes

HORIZONTAL_FOV

imageSensorHeight

The height of the image sensor (m)

imageSensorWidth

The width of the image sensor (m)

pixelHeight

The height of a pixel in real 3d measurements (m)

pixelWidth

The wdith of a pixel in real 3d measurements (m)

resolution_x

The X resolution of the camera or the width of the screen in pixels

resolution_y

The Y resolution of the camera or the height of the screen in pixels

verticalFOV

The vertical field of vision of the camera.

robot_name

Name of the robot

pose

Pose of the camera

pose_base_link_straight

Pose of the camera

camera_info

Camera info object recieved from the subscriber

focal_length

Focal length of the camera (meters) distance to the camera plane as projected in 3D

calculateBallFromBoundingBoxes(ball_radius: float = 0.07, bounding_boxes: [<class 'float'>] = []) Transformation[source]

Reverse function for calculateBoundingBoxesFromBall(), takes the bounding boxes of the ball as seen on the camera and return the 3D position of the ball assuming that the ball is on the ground

Parameters:
  • ball_radius – The radius of the ball in meters

  • bounding_boxes – The bounding boxes of the ball on the camera in the format [[x1,y1], [x1,y1]] which are the top left and bottom right of the bounding box respectively

Returns:

3D coordinates of the ball stored in the Transformation format

calculateBoundingBoxesFromBall(ball_position: Transformation, ball_radius: float = 0.07)[source]

Takes a 3D ball transformation and returns the bounding boxes of the ball if seen on camera

Parameters:
  • ball_position – 3D coordinates of the ball stored in the Transformation format

  • ball_radius – The radious of the ball in centimeters

Returns:

The bounding boxes of the ball on the camera in the format [[x1,y1], [x1,y1]] which are the top left

and bottom right of the bounding box respectively

calculateHorizonCoverArea() int[source]

Given the camera’s position, return the area that is covered by the horizon (that is not the field area) in pixels from the top position :return: Pixel length from the top of the image to the point where it meets the horizon

cameraInfoCallback(camera_info: CameraInfo)[source]

Callback function for the camera info subscriber

Parameters:

camera_info – from the camera info topic

camera_info

Camera info object recieved from the subscriber

findCameraCoordinate(pos: [<class 'int'>]) [<class 'int'>][source]

From a 3d position on the field, get the camera coordinate, opposite of findFloorCoordinate()

Parameters:

pos – The 3D coordinate of the object

Returns:

The 2D pixel (x, y) on the camera, if the object was projected on the camera

findCameraCoordinateFixedCamera(pos: [<class 'int'>]) [<class 'int'>][source]

Helper function for findCameraCoordinate(), finds the camera coordinate if the camera were fixed at the origin

Parameters:

pos – The 3D coordinate of the object

Returns:

The 2D pixel (x, y) on the camera, if the object was projected on the camera and the camera is placed at the origin

findFloorCoordinate(pos: [<class 'int'>]) [<class 'int'>][source]

From a camera pixel, get a coordinate on the floor

Parameters:

pos – The position on the screen in pixels (x, y)

Returns:

The 3D coordinate of the pixel as projected to the floor

focal_length

Focal length of the camera (meters) distance to the camera plane as projected in 3D

property imageSensorHeight

The height of the image sensor (m)

property imageSensorWidth

The width of the image sensor (m)

imageToWorldFrame(pixel_x: int, pixel_y: int) tuple[source]

From image pixel coordinates, get the coordinates of the pixel as if they have been projected ot the camera plane, which is positioned at (0,0) in 3D world coordinates https://docs.google.com/presentation/d/10DKYteySkw8dYXDMqL2Klby-Kq4FlJRnc4XUZyJcKsw/edit#slide=id.g163680c589a_0_0

Parameters:
  • pixel_x – x pixel of the camera

  • pixel_y – y pixel of the camera

Returns:

3D position (X, Y) of the pixel in meters

property pixelHeight

The height of a pixel in real 3d measurements (m)

property pixelWidth

The wdith of a pixel in real 3d measurements (m)

pose

Pose of the camera

Pose of the camera

ready() bool[source]

Function to determine when the camera object has recieved the necessary information and is ready to be used

Returns:

True if the camera is ready, else False

reset_position(from_world_frame=False, timestamp=rospy.Time[0], camera_frame='/camera', skip_if_not_found=False)[source]

Resets the position of the camera, it uses a series of methods that fall back on each other to get the location of the camera

Parameters:
  • from_world_frame – If this is set to true, the camera position transformation will be from the world instead of the robot odom frame

  • timestamp – What time do we want the camera tf frame, rospy.Time(0) if get the latest transform

  • camera_frame – The name of the camera frame

  • skip_if_not_found – If set to true, then will not wait if it cannot find the camera transform after the specified duration (1 second), it will just return

property resolution_x: int

The X resolution of the camera or the width of the screen in pixels

Returns:

width in pixels

property resolution_y

The Y resolution of the camera or the height of the screen in pixels

Returns:

height in pixels

robot_name

Name of the robot

property verticalFOV

The vertical field of vision of the camera. See Field of View

worldToImageFrame(pos_x: float, pos_y: float) tuple[source]

Reverse function for imageToWorldFrame(), takes the 3D world coordinates of the camera plane and returns pixels

Parameters:
  • pos_x – X position of the pixel on the world plane in meters

  • pos_y – Y position of the pixel on the world plane in meters

Returns:

Tuple (x, y) of the pixel coordinates of in the image