Image Service Helpers¶
- bosdyn.client.image_service_helpers.convert_RGB_to_grayscale(image_data_RGB_np)[source]¶
Convert numpy image from RGB to grayscale using Pillow’s formula.
- Parameters
image_data_RGB_np (numpy array) – The RGB image data output from a capture as a 3D numpy
R (array with) –
G –
array. (B channels in that order in the) –
- Returns
Converted image_data_np as another 2D numpy array.
- class bosdyn.client.image_service_helpers.CameraInterface[source]¶
Bases:
ABC
Abstract class interface for capturing and decoding images from a camera.
This interface is used by the VisualImageSource to ensure that each image source has the expected capture and decoding methods with the right specification.
- abstract blocking_capture(*, custom_params=None, **kwargs)[source]¶
Communicates with the camera payload to collect the image data. Ensure this is threadsafe as multiple threads/requests may try to call blocking_capture at the same time. A Lock (self.capture_lock) is provided as a convenience to help with this.
- Keyword Arguments
custom_params (service_customization_pb2.DictParam) – Custom parameters defined by the image source affecting the resulting capture
**kwargs – Other keyword arguments including future additions to the request that affect the capture. If an implementer is looking to use kwargs, it is expected that they update their blocking_capture function signature to accept named keyword arguments such as custom_params
- Returns
A tuple with image data (in any format), and the capture timestamp in seconds (float) in the service computer’s clock.
- abstract image_decode(image_data, image_proto, image_req)[source]¶
Decode the image data into an Image proto based on the requested format and quality.
- Parameters
image_data (Same format as the output of blocking_capture) – The image data output from a capture.
image_proto (image_pb2.Image) – The proto message to populate with decoded image data.
image_req (image_pb2.ImageRequest) – The image request associated with the image_data.
- Returns
None. Mutates the image_proto message with the decoded data. This function should set the image data, pixel format, image format, and potentially the transform snapshot fields within the image_proto protobuf message.
- class bosdyn.client.image_service_helpers.VisualImageSource(image_name, camera_interface, rows=None, cols=None, gain=None, exposure=None, pixel_formats=[], logger=None, param_spec=None)[source]¶
Bases:
object
Helper class to represent a single image source.
This helper class can be used to track state associated with an image source. It can capture images and decode image data for an image service. It can be configured to: - throw faults for capture or decode failures - request images continuously on a background thread to allow image services to respond more rapidly to GetImage requests.
- Parameters
image_name (string) – The name of the image source.
camera_interface (subclass of CameraInterface) – A camera class which inherits from and implements the abstract methods of the CameraInterface class.
rows (int) – The number of rows of pixels in the image.
cols (int) – The number of cols of pixels in the image.
gain (float | function) – The sensor’s gain in dB. This can be a fixed value or a function which returns the gain as a float.
exposure (float | function) – The exposure time for an image in seconds. This can be a fixed value or a function which returns the exposure time as a float.
pixel_formats (image_pb2.Image.PixelFormat[]) – Supported pixel formats.
param_spec (service_customization_pb2.DictParam.Spec) – A set of custom parameters passed into this image source
logger (logging.Logger) – Logger for debug and warning messages.
- create_capture_thread(custom_params=None)[source]¶
Initialize a background thread to continuously capture images.
- initialize_faults(fault_client, image_service)[source]¶
Initialize a fault client and faults for the image source (linked to the image service).
The fault client can be used to throw faults for capture and decode errors. All faults associated with the image service name provided will be cleared.
- Parameters
fault_client (FaultClient) – The fault client to communicate with the robot.
image_service (string) – The image service name to associate faults with.
- trigger_fault(error_message, fault)[source]¶
Trigger a service fault for a failure to the fault service.
- Parameters
error_message (string) – The error message to provide in the camera capture fault.
fault (service_fault_pb2.ServiceFault) – The complete service fault to be issued.
- clear_fault(fault)[source]¶
Attempts to clear the camera capture fault from the fault service.
- Parameters
fault (service_fault_pb2.ServiceFault) – The fault (which contains an ID) to be cleared.
- get_image_and_timestamp(custom_params=None, **capture_func_kwargs)[source]¶
Retrieve the latest captured image and timestamp.
- Parameters
custom_params (service_customization_pb2.DictParam) – Custom parameters passed to the object’s capture_function affecting the resulting capture
**capture_func_kwargs – Other keyword arguments for the capture_function
- Returns
The latest captured image and the time (in seconds) associated with that image capture. Throws a camera capture fault and returns None if the image cannot be retrieved.
- image_decode_with_error_checking(image_data, image_proto, image_req)[source]¶
Decode the image data into an Image proto based on the requested format and quality.
- Parameters
image_data (any format) – The image data returned by the camera interface’s blocking_capture function.
image_proto (image_pb2.Image) – The image proto to be mutated with the decoded data.
image_req (image_pb2.ImageRequest) – The image request associated with the image_data.
- Returns
image_pb2.ImageResponse.Status indicating if the decode succeeds, or image format conversion or pixel conversion failed. Throws a decode data fault if the image or pixels cannot be decoded to the desired format. Mutates the image_proto Image proto with the decoded data if successful.
- stop_capturing(timeout_secs=10)[source]¶
Stop the image capture thread if one exists.
- Parameters
timeout_secs (int) – The timeout [seconds] for attempting to join and destroy the capture thread.
- static make_image_source(source_name, rows=None, cols=None, pixel_formats=[], image_type=1, image_formats=[1], param_spec=None)[source]¶
Create an instance of the image_pb2.ImageSource for a given source name.
- Parameters
source_name (string) – The name for the camera source.
rows (int) – The number of rows of pixels in the image.
cols (int) – The number of cols of pixels in the image.
image_type (image_pb2.ImageType) – The type of image (e.g. visual, depth).
image_formats (image_pb2.Image.Format) – The image formats supported (jpeg, raw)
pixel_formats (image_pb2.Image.PixelFormat) – The pixel formats supported
param_spec (service_customization_pb2.DictParam.Spec) – A set of custom parameters passed into this image source
- Returns
An ImageSource with the cols, rows, and image type populated.
- static make_capture_parameters(gain=None, exposure=None, request_custom_params=None)[source]¶
Creates an instance of the image_pb2.CaptureParameters protobuf message.
- Parameters
gain (float | function) – The sensor’s gain in dB. This can be a fixed value or a function which returns the gain as a float.
exposure (float | function) – The exposure time for an image in seconds. This can be a fixed value or a function which returns the exposure time as a float.
request_custom_params (service_customization_pb2.DictParam) – Custom Params associated with the image request. Should not be ‘None’, but left as an option to accomodate old callers
- Returns
An instance of the protobuf CaptureParameters message.
- class bosdyn.client.image_service_helpers.ThreadCaptureOutput(is_valid, image, timestamp)[source]¶
Bases:
object
Small struct to represent the output of an ImageCaptureThread’s get_latest_captured_image in a future-compatible way
- Parameters
is_valid (Boolean) – Whether the latest capture uses the custom parameters and other arguments supplied in the latest request, and is therefore returned
image (Any | None) – If the latest capture is valid, the image data in any format (e.g. numpy, bytes, array)
timestamp (float) – The timestamp that the latest valid capture was taken
- class bosdyn.client.image_service_helpers.ImageCaptureThread(image_source_name, capture_func, capture_period_secs=0.05, custom_params=None, **capture_func_kwargs)[source]¶
Bases:
object
Continuously query and store the last successfully captured image and its associated timestamp for a single camera device.
- Parameters
image_source_name (string) – The image source name.
capture_func (CameraInterface.blocking_capture) – The function capturing the image data and timestamp.
capture_period_secs (int) – Amount of time (in seconds) between captures to wait before triggering the next capture. Defaults to 0.05s between captures.
custom_params (service_customization_pb2.DictParam) – Custom parameters passed to capture_func affecting the resulting capture
**capture_func_kwargs – Other keyword arguments for the capture_func
- set_last_captured_image(image_frame, capture_time)[source]¶
Update the last image capture and timestamp.
- class bosdyn.client.image_service_helpers.CameraBaseImageServicer(bosdyn_sdk_robot, service_name, image_sources, logger=None, use_background_capture_thread=True, background_capture_params=None)[source]¶
Bases:
ImageServiceServicer
GRPC service to provide access to multiple different image sources.
The service can list the available image (device) sources and query each source for image data.
- Parameters
bosdyn_sdk_robot (Robot) – The robot instance for the service to connect to.
service_name (string) – The name of the image service.
image_sources (List[VisualImageSource]) – The list of image sources (provided as a VisualImageSource).
logger (logging.Logger) – Logger for debug and warning messages.
use_background_capture_thread (bool) – If true, the image service will create a thread that continuously captures images so the image service can respond rapidly to the GetImage request. If false, the image service will call an image sources’ blocking_capture_function during the GetImage request.
background_capture_params (service_customization_pb2.DictParam) – If use_background_capture_thread is true, custom image source parameters used for all of the background captures. Otherwise ignored
- ListImageSources(request, context)[source]¶
Obtain the list of ImageSources for this given service.
- Parameters
request (image_pb2.ListImageSourcesRequest) – The list images request.
context (GRPC ClientContext) – tracks internal grpc statuses and information.
- Returns
A list of all image sources known to this image service. Note, there could be multiple image services registered with the robot’s directory service that can have different image sources.
- GetImage(request, context)[source]¶
Gets the latest image capture from all the image sources specified in the request.
- Parameters
request (image_pb2.GetImageRequest) – The image request, which specifies the image sources to query, and other format parameters.
context (GRPC ClientContext) – tracks internal grpc statuses and information.
- Returns
The ImageSource and Image data for the last captured image from each image source name specified in the request.