Skip to main content

Perception Python API

intrinsic.perception.client.v1.python.image_utils

Miscellaneous image helper methods.

image_buffer_encoding

def image_buffer_encoding(
image_buffer: image_buffer_pb2.ImageBuffer) -> Optional[str]

Returns the encoding of the given image buffer.

serialize_image_buffer

def serialize_image_buffer(
image_array: np.ndarray,
encoding: Optional[str] = None,
pixel_type: image_buffer_pb2.PixelType = image_buffer_pb2.PixelType.
PIXEL_UNSPECIFIED,
packing_type: image_buffer_pb2.PackingType = image_buffer_pb2.PackingType.
PACKING_TYPE_INTERLEAVED
) -> image_buffer_pb2.ImageBuffer

Serializes image provided as a numpy array to the ImageBuffer proto format.

Arguments:

  • image_array - The image to serialize.
  • encoding - The encoding to use for the image.
  • pixel_type - The pixel type of the image. If unspecified, it will be retrieved from the metadata of the numpy array type.
  • packing_type - The packing type of the image.

Returns:

The serialized image buffer proto.

Raises:

ValueError if the buffer size is invalid.

deserialize_image_buffer

def deserialize_image_buffer(
image: image_buffer_pb2.ImageBuffer) -> np.ndarray

Deserializes image from proto format.

Computes the number of channels per pixel from the total data size, the per-channel data type, and the number of pixels, and returns the decoded image.

Arguments:

  • image - The serialized image.

Returns:

The unpacked image of size [height, width, num_channels].

Raises:

ValueError if the buffer size is invalid.

intrinsic.perception.client.v1.python.camera.cameras

Convenience class for Camera use within skills.

make_camera_resource_selector

def make_camera_resource_selector() -> equipment_pb2.ResourceSelector

Creates the default resource selector for a camera equipment slot.

Used in a skill's required_equipment implementation.

Returns:

A resource selector that is valid for cameras.

Camera Objects

class Camera()

Convenience class for Camera use within skills.

This class provides a more pythonic interface than the CameraClient which wraps the gRPC calls for interacting with cameras.

Typical usage example:

  • Add a camera slot to the skill, e.g.:

    @classmethod
    @overrides(skl.Skill)
    def required_equipment(cls) -> Mapping[str,
    equipment_pb2.ResourceSelector]:
    # create a camera equipment slot for the skill
    return {
    camera_slot: cameras.make_camera_resource_selector()
    }
  • Create and use a camera in the skill:

    def execute(
    self, request: skl.ExecuteRequest, context: skl.ExecuteContext
    ) -> ...:
    ...

    # access the camera equipment slot added in `required_equipment`
    camera = cameras.Camera.create(context, 'camera_slot')

    # get the camera's intrinsic matrix (for a particular sensor) as a numpy
    # array
    intrinsic_matrix = camera.intrinsic_matrix('sensor_name')

    # capture from all of the camera's currently configured sensors
    capture_result = camera.capture()
    for sensor_name, sensor_image in capture_result.sensor_images.items():
    # access each sensor's image buffer using sensor_image.array, e.g.:
    array = sensor_image.array # type: np.ndarray
    logging.info("Sensor name: %s", sensor_name)
    pixel_type = None
    if array.dtype.metadata is not None:
    pixel_type = array.dtype.metadata.get(
    image_utils.Metadata.Keys.PIXEL_TYPE
    )
    logging.info("Pixel type: %s", pixel_type)
    logging.info("Image size and shape: %s, %s", array.size, array.shape)
    logging.info("Image min and max: %s, %s", array.min(), array.max())
    logging.info("Intrinsic matrix: %s", sensor_image.intrinsic_matrix)

    ...

create

@classmethod
def create(cls, context: skill_interface.ExecuteContext, slot: str) -> Camera

Creates a Camera object from the skill's execution context.

Arguments:

  • context - The skill's current skill_interface.ExecuteContext.
  • slot - The camera slot created in skill's required_equipment implementation.

Returns:

A connected Camera object with sensor information cached.

create_from_resource_registry

@classmethod
def create_from_resource_registry(
cls,
resource_registry: resource_registry_client.ResourceRegistryClient,
resource_name: str,
world_client: Optional[object_world_client.ObjectWorldClient] = None,
channel: Optional[grpc.Channel] = None,
channel_creds: Optional[grpc.ChannelCredentials] = None) -> Camera

Creates a Camera object from the given resource registry and resource name.

Arguments:

  • resource_registry - The resource registry client.
  • resource_name - The resource name of the camera.
  • world_client - Optional. The current world client, for camera pose information.
  • channel - Optional. The gRPC channel to the camera service.
  • channel_creds - Optional. The gRPC channel credentials to use for the connection.

Returns:

A connected Camera object with sensor information cached. If no object or world information is available, an identity pose will be used for world_t_camera and all the world update methods will be a no-op.

create_from_resource_handle

@classmethod
def create_from_resource_handle(
cls,
resource_handle: resource_handle_pb2.ResourceHandle,
world_client: Optional[object_world_client.ObjectWorldClient] = None,
channel: Optional[grpc.Channel] = None,
channel_creds: Optional[grpc.ChannelCredentials] = None) -> Camera

Creates a Camera object from the given resource handle.

Arguments:

  • resource_handle - The resource handle with which to connect to the camera.
  • world_client - Optional. The current world client, for camera pose information.
  • channel - Optional. The gRPC channel to the camera service.
  • channel_creds - Optional. The gRPC channel credentials to use for the connection.

Returns:

A connected Camera object with sensor information cached. If no object or world information is available, an identity pose will be used for world_t_camera and all the world update methods will be a no-op.

__init__

def __init__(
channel: grpc.Channel,
resource_handle: resource_handle_pb2.ResourceHandle,
world_client: Optional[object_world_client.ObjectWorldClient] = None)

Creates a Camera object from the given camera equipment and world.

Arguments:

  • channel - The gRPC channel to the camera service.
  • resource_handle - The resource handle with which to connect to the camera.
  • world_client - Optional. The current world client, for camera pose information.

Raises:

  • RuntimeError - The camera's config could not be parsed from the resource handle.

identifier

@property
def identifier() -> Optional[str]

Camera identifier.

display_name

@property
def display_name() -> str

Camera display name.

resource_handle

@property
def resource_handle() -> resource_handle_pb2.ResourceHandle

Camera resource handle.

sensor_names

@property
def sensor_names() -> list[str]

List of sensor names.

sensor_ids

@property
def sensor_ids() -> list[int]

List of sensor ids.

sensor_id_to_name

@property
def sensor_id_to_name() -> Mapping[int, str]

Mapping of sensor ids to sensor names.

sensor_dimensions

@property
def sensor_dimensions() -> Mapping[str, tuple[int, int]]

Mapping of sensor name to the sensor's intrinsic dimensions (width, height).

intrinsic_matrix

def intrinsic_matrix(sensor_name: str) -> Optional[np.ndarray]

Get the intrinsic matrix of a specific sensor (for multi-sensor cameras), falling back to factory settings if the intrinsic params are missing from the sensor config.

Arguments:

  • sensor_name - The desired sensor name.

Returns:

The sensor's intrinsic matrix or None if it could not be found.

distortion_params

def distortion_params(sensor_name: str) -> Optional[np.ndarray]

Get the distortion params of a specific sensor (for multi-sensor cameras), falling back to factory settings if distortion params are missing from the sensor config.

Arguments:

  • sensor_name - The desired sensor name.

Returns:

The distortion params (k1, k2, p1, p2, [k3, [k4, k5, k6, [s1, s2, s3, s4, [tx, ty]]]]) or None if it couldn't be found.

world_object

@property
def world_object() -> Optional[object_world_resources.WorldObject]

Camera world object.

world_t_camera

@property
def world_t_camera() -> pose3.Pose3

Camera world pose.

camera_t_sensor

def camera_t_sensor(sensor_name: str) -> Optional[pose3.Pose3]

Get the sensor camera_t_sensor pose, falling back to factory settings if pose is missing from the sensor config.

Arguments:

  • sensor_name - The desired sensor's name.

Returns:

The pose3.Pose3 of the sensor relative to the pose of the camera itself or None if it couldn't be found.

world_t_sensor

def world_t_sensor(sensor_name: str) -> Optional[pose3.Pose3]

Get the sensor world_t_sensor pose, falling back to factory settings for camera_t_sensor if pose is missing from the sensor config.

Arguments:

  • sensor_name - The desired sensor's name.

Returns:

The pose3.Pose3 of the sensor relative to the pose of the world or None if it couldn't be found.

update_world_t_camera

def update_world_t_camera(world_t_camera: pose3.Pose3) -> None

Update camera world pose relative to world root.

Arguments:

  • world_t_camera - The new world_t_camera pose.

update_camera_t_other

def update_camera_t_other(other: object_world_resources.TransformNode,
camera_t_other: pose3.Pose3) -> None

Update camera world pose relative to another object.

Arguments:

  • other - The other object.
  • camera_t_other - The relative transform.

update_other_t_camera

def update_other_t_camera(other: object_world_resources.TransformNode,
other_t_camera: pose3.Pose3) -> None

Update camera world pose relative to another object.

Arguments:

  • other - The other object.
  • other_t_camera - The relative transform.

capture

def capture(camera_config: Optional[data_classes.CameraConfig] = None,
sensor_names: Optional[list[str]] = None,
timeout: Optional[datetime.timedelta] = None,
skip_undistortion: bool = False) -> data_classes.CaptureResult

Capture from the camera and return a CaptureResult.

Arguments:

  • camera_config - Optional. The camera config to use. If not specified, the config that was used to instantiate this class will be used. This can be the camera config which was retrieved from the skill context or the resource handle.
  • sensor_names - An optional list of sensor names that will be transmitted in the response, if data was collected for them. This acts as a mask to limit the number of transmitted SensorImages. If it is None or empty, all SensorImages will be transferred.
  • timeout - An optional timeout which is used for retrieving sensor images from the underlying driver implementation. If this timeout is implemented by the underlying camera driver, it will not spend more than the specified time when waiting for new sensor images, after which it will throw a deadline exceeded error. The timeout should be greater than the combined exposure and processing time. Processing times can be roughly estimated as a value between 10 - 50 ms. The timeout just serves as an upper limit to prevent blocking calls within the camera driver. In case of intermittent network errors users can try to increase the timeout. The default timeout (if None) of 500 ms works well in common setups.
  • skip_undistortion - Whether to skip undistortion.

Returns:

A CaptureResult which contains the selected sensor images.

Raises:

  • ValueError - The matching sensors could not be found or the capture result could not be parsed.
  • ValueError - The identifier in camera_config does not match the identifier this camera was instantiated with.
  • grpc.RpcError - A gRPC error occurred.

read_camera_setting_properties

def read_camera_setting_properties(
name: str
) -> Union[
settings_pb2.FloatSettingProperties,
settings_pb2.IntegerSettingProperties,
settings_pb2.EnumSettingProperties,
]

Read the properties of a camera setting by name.

These settings vary for different types of cameras, but generally conform to the GenICam Standard Features Naming Convention (SFNC): https://www.emva.org/wp-content/uploads/GenICam_SFNC_v2_7.pdf.

Arguments:

  • name - The setting name.

Returns:

The setting properties, which can be used to validate that a particular setting is supported.

Raises:

  • ValueError - Setting properties type could not be parsed.
  • grpc.RpcError - A gRPC error occurred.

read_camera_setting

def read_camera_setting(name: str) -> Union[int, float, bool, str]

Read a camera setting by name.

These settings vary for different types of cameras, but generally conform to the GenICam Standard Features Naming Convention (SFNC): https://www.emva.org/wp-content/uploads/GenICam_SFNC_v2_7.pdf.

Arguments:

  • name - The setting name.

Returns:

The current camera setting.

Raises:

  • ValueError - Setting type could not be parsed.
  • grpc.RpcError - A gRPC error occurred.

update_camera_setting

def update_camera_setting(name: str, value: Union[int, float, bool,
str]) -> None

Update a camera setting.

These settings vary for different types of cameras, but generally conform to the GenICam Standard Features Naming Convention (SFNC): https://www.emva.org/wp-content/uploads/GenICam_SFNC_v2_7.pdf.

Arguments:

  • name - The setting name.
  • value - The desired setting value.

Raises:

  • ValueError - Setting type could not be parsed or value doesn't match type.
  • grpc.RpcError - A gRPC error occurred.

intrinsic.perception.client.v1.python.camera.camera_client

Base camera class wrapping gRPC connection and calls.

CameraClient Objects

class CameraClient()

Base camera class wrapping gRPC connection and calls.

Skill users should use the Camera class, which provides a more pythonic interface.

__init__

def __init__(camera_channel: grpc.Channel,
connection_params: connection.ConnectionParams,
camera_identifier: camera_identifier_pb2.CameraIdentifier)

Creates a CameraClient object.

describe_camera

@error_handling.retry_on_grpc_unavailable
def describe_camera() -> camera_service_pb2.DescribeCameraResponse

Enumerates connected sensors.

Returns:

A camera_server_pb2.DescribeCameraResponse with the camera's sensor information.

Raises:

  • grpc.RpcError - A gRPC error occurred.

capture

def capture(
camera_config: Optional[camera_config_pb2.CameraConfig] = None,
timeout: Optional[datetime.timedelta] = None,
deadline: Optional[datetime.datetime] = None,
sensor_ids: Optional[list[int]] = None,
skip_undistortion: bool = False) -> capture_result_pb2.CaptureResult

Captures image data from the requested sensors of the specified camera.

Arguments:

  • camera_config - Optional. The camera config to use. If not specified, a default camera config will be created from the camera identifier that was used to instantiate this camera client.
  • timeout - Optional. The timeout which is used for retrieving frames from the underlying driver implementation. If this timeout is implemented by the underlying camera driver, it will not spend more than the specified time when waiting for new frames. The timeout should be greater than the combined exposure and processing time. Processing times can be roughly estimated as a value between 10 - 50 ms. The timeout just serves as an upper limit to prevent blocking calls within the camera driver. In case of intermittent network errors users can try to increase the timeout. The default timeout (if unspecified) of 500 ms works well in common setups.
  • deadline - Optional. The deadline corresponding to the timeout. This takes priority over the timeout.
  • sensor_ids - Optional. Request data only for the following sensor ids (i.e. transmit mask). Empty returns all sensor images.
  • skip_undistortion - Whether to skip undistortion.

Returns:

A capture_result_pb2.CaptureResult with the requested sensor images.

Raises:

  • grpc.RpcError - A gRPC error occurred.
  • ValueError - When the identifier in camera_config does not match the identifier this client was instantiated with.

read_camera_setting_properties

@error_handling.retry_on_grpc_unavailable
def read_camera_setting_properties(
name: str) -> camera_settings_pb2.CameraSettingProperties

Read the properties of the setting.

The function returns an error if the setting is not supported. If specific properties of a setting are not supported, they are not added to the result. The function only returns existing properties and triggers no errors for non-existing properties as these are optional to be implemented by the camera vendors.

Arguments:

  • name - The setting name. The setting name must be defined by the Standard Feature Naming Conventions (SFNC) which is part of the GenICam standard.

Returns:

A camera_settings_pb2.CameraSettingProperties with the requested setting properties.

Raises:

  • grpc.RpcError - A gRPC error occurred.

read_camera_setting

@error_handling.retry_on_grpc_unavailable
def read_camera_setting(name: str) -> camera_settings_pb2.CameraSetting

Reads and returns the current value of a specific setting from a camera.

The function returns an error if the setting is not supported.

Arguments:

  • name - The setting name. The setting name must be defined by the Standard Feature Naming Conventions (SFNC) which is part of the GenICam standard.

Returns:

A camera_settings_pb2.CameraSetting with the requested setting value.

Raises:

  • grpc.RpcError - A gRPC error occurred.

update_camera_setting

@error_handling.retry_on_grpc_unavailable
def update_camera_setting(setting: camera_settings_pb2.CameraSetting) -> None

Update the value of a specific camera setting.

The function returns an error if the setting is not supported. Note: When updating camera parameters, beware that the modifications will apply to all instances. I.e. it will also affect all other clients who are using the same camera.

Arguments:

  • setting - A camera_settings_pb2.CameraSetting with a value to update to.

Raises:

  • grpc.RpcError - A gRPC error occurred.

intrinsic.perception.client.v1.python.camera.data_classes

Common camera data classes.

CameraParams Objects

class CameraParams()

Convenience wrapper for CameraParams.

proto

@property
def proto() -> camera_params_pb2.CameraParams

Returns the camera params proto.

dimensions

@property
def dimensions() -> tuple[int, int]

Camera intrinsic dimensions (width, height).

intrinsic_matrix

@property
def intrinsic_matrix() -> np.ndarray

Camera intrinsic matrix.

distortion_params

@property
def distortion_params() -> Optional[np.ndarray]

Camera distortion params; (k1, k2, p1, p2, [k3, [k4, k5, k6, [s1, s2, s3, s4, [tx, ty]]]]) or None.

SensorInformation Objects

class SensorInformation()

Convenience wrapper for SensorInformation.

proto

@property
def proto() -> camera_service_pb2.SensorInformation

Returns the sensor information proto.

sensor_id

@property
def sensor_id() -> int

Sensor id.

display_name

@property
def display_name() -> str

Sensor name.

factory_camera_params

@property
def factory_camera_params() -> Optional[CameraParams]

Sensor factory camera params.

factory_intrinsic_matrix

@property
def factory_intrinsic_matrix() -> Optional[np.ndarray]

Sensor factory intrinsic matrix.

factory_distortion_params

@property
def factory_distortion_params() -> Optional[np.ndarray]

Sensor factory distortion params; (k1, k2, p1, p2, [k3, [k4, k5, k6, [s1, s2, s3, s4, [tx, ty]]]]) or None.

camera_t_sensor

@property
def camera_t_sensor() -> Optional[pose3.Pose3]

Camera to sensor pose.

dimensions

@property
def dimensions() -> tuple[int, int]

Sensor dimensions (width, height).

SensorConfig Objects

class SensorConfig()

Convenience wrapper for SensorConfig.

proto

@property
def proto() -> sensor_config_pb2.SensorConfig

Returns the sensor config proto.

sensor_id

@property
def sensor_id() -> int

Sensor id.

camera_t_sensor

@property
def camera_t_sensor() -> Optional[pose3.Pose3]

Camera to sensor pose.

camera_params

@property
def camera_params() -> Optional[CameraParams]

Sensor camera params.

dimensions

@property
def dimensions() -> Optional[tuple[int, int]]

Sensor intrinsic dimensions (width, height).

intrinsic_matrix

@property
def intrinsic_matrix() -> Optional[np.ndarray]

Sensor intrinsic matrix.

distortion_params

@property
def distortion_params() -> Optional[np.ndarray]

Sensor distortion params; (k1, k2, p1, p2, [k3, [k4, k5, k6, [s1, s2, s3, s4, [tx, ty]]]]) or None.

CameraConfig Objects

class CameraConfig()

Convenience wrapper for CameraConfig.

proto

@property
def proto() -> camera_config_pb2.CameraConfig

Returns the camera config proto.

identifier

@property
def identifier() -> Optional[str]

Camera identifier.

SensorImage Objects

class SensorImage()

Convenience wrapper for SensorImage.

__init__

def __init__(sensor_image: sensor_image_pb2.SensorImage,
sensor_name: str,
world_t_camera: Optional[pose3.Pose3] = None)

Creates a SensorImage object.

proto

@property
def proto() -> sensor_image_pb2.SensorImage

Returns the sensor image proto.

sensor_id

@property
def sensor_id() -> int

Sensor id.

sensor_name

@property
def sensor_name() -> str

Sensor name.

camera_t_sensor

@property
def camera_t_sensor() -> Optional[pose3.Pose3]

Sensor pose relative to camera.

world_t_sensor

@property
def world_t_sensor() -> Optional[pose3.Pose3]

Sensor world pose.

camera_params

@property
def camera_params() -> Optional[CameraParams]

Sensor camera params.

dimensions

@property
def dimensions() -> Optional[tuple[int, int]]

Sensor intrinsic dimensions (width, height).

intrinsic_matrix

@property
def intrinsic_matrix() -> Optional[np.ndarray]

Sensor intrinsic matrix.

distortion_params

@property
def distortion_params() -> Optional[np.ndarray]

Sensor distortion params; (k1, k2, p1, p2, [k3, [k4, k5, k6, [s1, s2, s3, s4, [tx, ty]]]]) or None.

capture_at

@property
def capture_at() -> datetime.datetime

Returns the capture time of the sensor image.

array

@property
def array() -> np.ndarray

Converts the sensor image to a numpy array.

shape

@property
def shape() -> tuple[int, int, int]

Returns the shape of the sensor image.

CaptureResult Objects

class CaptureResult()

Convenience wrapper for CaptureResult.

__init__

def __init__(capture_result: capture_result_pb2.CaptureResult,
sensor_names: Optional[Mapping[int, str]] = None,
world_t_camera: Optional[pose3.Pose3] = None)

Creates a CaptureResult object.

proto

@property
def proto() -> capture_result_pb2.CaptureResult

Returns the capture result proto.

capture_at

@property
def capture_at() -> datetime.datetime

Returns the capture time of the capture result.

sensor_names

@property
def sensor_names() -> list[str]

Returns the sensor names from the capture result.

sensor_images

@property
def sensor_images() -> Mapping[str, SensorImage]

Returns the sensor images from the capture result.

sensor_image_buffers

@property
def sensor_image_buffers() -> Mapping[str, np.ndarray]

Returns the sensor images from the capture result as numpy arrays.