Image
For clients to use the image service.
- exception bosdyn.client.image.ImageResponseError(response, error_message=None)[source]
Bases:
ResponseError
General class of errors for Image service.
- exception bosdyn.client.image.UnknownImageSourceError(response, error_message=None)[source]
Bases:
ImageResponseError
System cannot find the requested image source name.
- exception bosdyn.client.image.SourceDataError(response, error_message=None)[source]
Bases:
ImageResponseError
System cannot generate the ImageSource at this time.
- exception bosdyn.client.image.ImageDataError(response, error_message=None)[source]
Bases:
ImageResponseError
System cannot generate image data for the ImageCapture at this time.
- exception bosdyn.client.image.UnsupportedImageFormatRequestedError(response, error_message=None)[source]
Bases:
ImageResponseError
The image service cannot return data in the requested format.
- exception bosdyn.client.image.UnsupportedPixelFormatRequestedError(response, error_message=None)[source]
Bases:
ImageResponseError
The image service cannot return data in the requested pixel format.
- exception bosdyn.client.image.UnsupportedResizeRatioRequestedError(response, error_message=None)[source]
Bases:
ImageResponseError
The image service cannot return data with the requested resize ratio.
- class bosdyn.client.image.ImageClient[source]
Bases:
BaseClient
Client for the image service.
- default_service_name = 'image'
- service_type = 'bosdyn.api.ImageService'
- list_image_sources(**kwargs)[source]
Obtain the list of ImageSources.
- Returns:
A list of the different image sources as strings.
- Raises:
RpcError – Problem communicating with the robot.
- get_image_from_sources(image_sources, **kwargs)[source]
Obtain images from sources using default parameters.
- Parameters:
image_sources (list of strings) – The different image sources to request images from.
- Returns:
A list of image responses for each of the requested sources.
- Raises:
RpcError – Problem communicating with the robot.
UnknownImageSourceError – Provided image source was invalid or not found
image.SourceDataError – Failed to fill out ImageSource. All other fields are not filled
UnsetStatusError – An internal ImageService issue has happened
ImageDataError – Problem with the image data. Only ImageSource is filled
- get_image_from_sources_async(image_sources, **kwargs)[source]
Obtain images from sources using default parameters.
- get_image(image_requests, **kwargs)[source]
Obtain the set of images from the robot.
- Parameters:
image_requests (list of ImageRequest) – A list of the ImageRequest protobuf messages which specify which images to collect.
- Returns:
A list of image responses for each of the requested sources.
- Raises:
RpcError – Problem communicating with the robot.
UnknownImageSourceError – Provided image source was invalid or not found
image.SourceDataError – Failed to fill out ImageSource. All other fields are not filled
UnsetStatusError – An internal ImageService issue has happened
ImageDataError – Problem with the image data. Only ImageSource is filled
- bosdyn.client.image.build_image_request(image_source_name, quality_percent=75, image_format=None, pixel_format=None, resize_ratio=None, fallback_formats=None)[source]
Helper function which builds an ImageRequest from an image source name.
By default the robot will choose an appropriate format when no image format is provided. For example, it will choose JPEG for visual images, or RAW for depth images. Clients can provide an image_format for other cases.
- Parameters:
image_source_name (string) – The image source to query.
quality_percent (int) – The image quality from [0,100] (percent-value).
image_format (image_pb2.Image.Format) – The type of format for the image data, such as JPEG, RAW, or RLE.
pixel_format (image_pb2.Image.PixelFormat) –
resize_ratio (double) – Resize ratio for image dimensions.
fallback_formats (image_pb2.Image.PixelFormat) –
invalid. (if the pixel_format is) –
- Returns:
The ImageRequest protobuf message for the given parameters.
- bosdyn.client.image.write_pgm_or_ppm(image_response, filename='', filepath='.', include_pixel_format=False)[source]
Write raw data from image_response to a PGM file.
- Parameters:
image_response (image_pb2.ImageResponse) – The ImageResponse proto to parse.
filename (string) – Name of the output file, if None is passed, then “image-{SOURCENAME}.pgm” is used.
filepath (string) – The directory to save the image.
include_pixel_format (bool) – append the pixel format to the image name when generating a filename (“image-{SOURCENAME}-{PIXELFORMAT}.pgm”).
- bosdyn.client.image.write_image_data(image_response, filename='', filepath='.', include_pixel_format=False)[source]
Write image data from image_response to a file.
- Parameters:
image_response (image_pb2.ImageResponse) – The ImageResponse proto to parse.
filename (string) – Name of the output file (including the file extension), if None is passed, then “image-{SOURCENAME}.jpg” is used.
filepath (string) – The directory to save the image.
include_pixel_format (bool) – append the pixel format to the image name when generating a filename (“image-{SOURCENAME}-{PIXELFORMAT}.jpg”).
- bosdyn.client.image.save_images_as_files(image_responses, filename='', filepath='.', include_pixel_format=False)[source]
Write image responses to files.
- Parameters:
image_responses (List[image_pb2.ImageResponse]) – The list of image responses to save.
filename (string) – Name prefix of the output files (made unique by an integer suffix), if None is passed the image source name is used.
filepath (string) – The directory to save the image files.
include_pixel_format (bool) – append the pixel format to the image name when generating a filename (“image-{SOURCENAME}-{PIXELFORMAT}.jpg”).
- bosdyn.client.image.pixel_to_camera_space(image_proto, pixel_x, pixel_y, depth=1.0)[source]
Using the camera intrinsics, determine the (x,y,z) point in the camera frame for the (u,v) pixel coordinates.
- Parameters:
image_proto (image_pb2.ImageSource) – The image source proto which the pixel coordinates are from. Use of image_pb2.ImageCaptureAndSource or image_pb2.ImageResponse types here have been deprecated.
pixel_x (int) – x-coordinate.
pixel_y (int) – y-coordinate.
depth (double) – The depth from the camera to the point of interest.
- Returns:
An (x,y,z) tuple representing the pixel point of interest now described as a point in the camera frame.
- bosdyn.client.image.depth_image_to_pointcloud(image_response, min_dist=0, max_dist=1000)[source]
Converts a depth image into a point cloud using the camera intrinsics. The point cloud is represented as a numpy array of (x,y,z) values. Requests can optionally filter the results based on the points distance to the image plane. A depth image is represented with an unsigned 16-bit integer and a scale factor to convert that distance to meters. In addition, values of zero and 2^16 (uint 16 maximum) are used to represent invalid indices. A (min_dist * depth_scale) value that casts to an integer value <=0 will be assigned a value of 1 (the minimum representational distance). Similarly, a (max_dist * depth_scale) value that casts to >= 2^16 will be assigned a value of 2^16 - 1 (the maximum representational distance).
- Parameters:
image_response (image_pb2.ImageResponse) – An ImageResponse containing a depth image.
min_dist (double) – All points in the returned point cloud will be greater than min_dist from the image plane [meters].
max_dist (double) – All points in the returned point cloud will be less than max_dist from the image plane [meters].
- Returns:
A numpy stack of (x,y,z) values representing depth image as a point cloud expressed in the sensor frame.