def AcquirePluginData(self, request, context):
        """Trigger a data acquisition and store results in the data acquisition store service.

        Args:
            request (data_acquisition_pb2.AcquirePluginDataRequest): The data acquisition request.
            context (GRPC ClientContext): tracks internal grpc statuses and information.

        Returns:
            An AcquirePluginDataResponse containing a request_id to use with GetStatus.
        """
        response = data_acquisition_pb2.AcquirePluginDataResponse()
        if self.acquire_response_fn is not None:
            try:
                if not self.acquire_response_fn(request, response):
                    return response
            except Exception as e:
                self.logger.exception(
                    'Failed during call to user acquire response function')
                populate_response_header(
                    response,
                    request,
                    error_code=header_pb2.CommonError.CODE_INTERNAL_ERROR,
                    error_msg=str(e))
                return response
        self.request_manager.cleanup_requests()
        response.request_id, state = self.request_manager.add_request()
        self.logger.info('Beginning request %d for %s', response.request_id, [
            capture.name
            for capture in request.acquisition_requests.data_captures
        ])
        self.executor.submit(self._data_collection_wrapper,
                             response.request_id, request, state)
        response.status = data_acquisition_pb2.AcquireDataResponse.STATUS_OK
        populate_response_header(response, request)
        return response
    def _start_plugin_acquire(self, request, response):
        """Initiates the data collection function and mutates the AcquirePluginDataResponse rpc.

        Args:
            request (data_acquisition_pb2.AcquirePluginDataRequest): The data acquisition request.
            response (data_acquisition_pb2.AcquirePluginDataResponse): The data acquisition response.

        Returns:
            Mutates the AcquirePluginDataResponse proto and also returns it.
        """
        if self.acquire_response_fn is not None:
            try:
                if not self.acquire_response_fn(request, response):
                    return response
            except Exception as e:
                self.logger.exception(
                    'Failed during call to user acquire response function')
                populate_response_header(
                    response,
                    request,
                    error_code=header_pb2.CommonError.CODE_INTERNAL_ERROR,
                    error_msg=str(e))
                return response
        self.request_manager.cleanup_requests()
        response.request_id, state = self.request_manager.add_request()
        self.logger.info('Beginning request %d for %s', response.request_id, [
            capture.name
            for capture in request.acquisition_requests.data_captures
        ])
        self.executor.submit(self._data_collection_wrapper,
                             response.request_id, request, state)
        response.status = data_acquisition_pb2.AcquireDataResponse.STATUS_OK
        populate_response_header(response, request)
        return response
    def GetServiceInfo(self, request, context):
        """Get a list of data acquisition capabilities.

        Args:
            request (data_acquisition_pb2.GetServiceInfoRequest): The get service info request.
            context (GRPC ClientContext): tracks internal grpc statuses and information.

        Returns:
            An GetServiceInfoResponse containing the list of data acquisition capabilities for the plugin.
        """
        response = data_acquisition_pb2.GetServiceInfoResponse()
        response.capabilities.data_sources.extend(self.capabilities)
        populate_response_header(response, request)
        return response
Esempio n. 4
0
    def ListImageSources(self, request, context):
        """Obtain the list of ImageSources for this given service.

        Args:
            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.
        """
        response = image_pb2.ListImageSourcesResponse()
        for source in self.image_sources_mapped.values():
            response.image_sources.add().CopyFrom(source.image_source_proto)
        populate_response_header(response, request)
        return response
Esempio n. 5
0
def test_stripped_headers():
    request = daq_store.StoreImageRequest()
    request.header.client_name = "my_client"
    request.image.image.data = bytes("mybytes", 'utf-8')
    request.image.image.cols = 21
    response = daq_store.StoreImageResponse()

    populate_response_header(response, request)

    assert response.header.request_header.client_name == "my_client"
    req_unpacked = daq_store.StoreImageRequest()
    response.header.request.Unpack(req_unpacked)
    assert req_unpacked.image.image.cols == 21
    assert len(req_unpacked.image.image.data) == 0
    # check that the original request is unchanged.
    assert len(request.image.image.data) > 0
Esempio n. 6
0
    def ListImageSources(self, request, context):
        """Obtain the list of ImageSources for this image source.

        Args:
            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, this service is setup to run a
            single client connection to a Ricoh Theta camera, so that will be the only returned source.
        """
        response = image_pb2.ListImageSourcesResponse()
        add_source = response.image_sources.add()
        add_source.CopyFrom(self.ricoh_image_src_proto)
        populate_response_header(response, request)
        return response
    def GetStatus(self, request, context):
        """Query the status of a data acquisition by ID.

        Args:
            request (data_acquisition_pb2.GetStatusRequest): The get status request.
            context (GRPC ClientContext): tracks internal grpc statuses and information.

        Returns:
            An GetStatusResponse containing the details of the data acquisition.
        """
        try:
            response = self.request_manager.get_status_proto(
                request.request_id)
        except KeyError:
            response = data_acquisition_pb2.GetStatusResponse()
            response.status = response.STATUS_REQUEST_ID_DOES_NOT_EXIST
        populate_response_header(response, request)
        return response
    def GetStatus(self, request, context):
        """Query the status of a data acquisition by ID.

        Args:
            request (data_acquisition_pb2.GetStatusRequest): The get status request.
            context (GRPC ClientContext): tracks internal grpc statuses and information.

        Returns:
            An GetStatusResponse containing the details of the data acquisition.
        """
        response = data_acquisition_pb2.GetStatusResponse()
        with ResponseContext(response, request, self.data_buffer_client):
            try:
                # Note: this needs to be a copy from and not '=' such that the response that is logged
                # in the request context gets updated.
                response.CopyFrom(
                    self.request_manager.get_status_proto(request.request_id))
            except KeyError:
                response.status = response.STATUS_REQUEST_ID_DOES_NOT_EXIST
            populate_response_header(response, request)
        return response
    def CancelAcquisition(self, request, context):
        """Cancel a data acquisition by ID.

        Args:
            request (data_acquisition_pb2.CancelAcquisitionRequest): The cancel acquisition request.
            context (GRPC ClientContext): tracks internal grpc statuses and information.

        Returns:
            An CancelAcquisitionResponse containing the status of the cancel operation.
        """
        response = data_acquisition_pb2.CancelAcquisitionResponse()
        try:
            self.request_manager.mark_request_cancelled(request.request_id)
            self.logger.info('Cancelling request %d', request.request_id)

        except KeyError:
            response.status = response.STATUS_REQUEST_ID_DOES_NOT_EXIST
        else:
            response.status = response.STATUS_OK
        populate_response_header(response, request)
        return response
Esempio n. 10
0
    def GetImage(self, request, context):
        """Gets the latest image capture from all the image sources specified in the request.

        Args:
            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.
        """
        response = image_pb2.GetImageResponse()
        for img_req in request.image_requests:
            img_resp = response.image_responses.add()
            src_name = img_req.image_source_name
            if src_name not in self.image_sources_mapped:
                # The requested camera source does not match the name of the Ricoh Theta camera, so if cannot
                # be completed and will have a failure status in the response message.
                img_resp.status = image_pb2.ImageResponse.STATUS_UNKNOWN_CAMERA
                self.logger.warning("Camera source '%s' is unknown.", src_name)
                continue

            # Set the image source information in the response.
            img_resp.source.CopyFrom(
                self.image_sources_mapped[src_name].image_source_proto)

            # Set the image capture parameters in the response.
            img_resp.shot.capture_params.CopyFrom(
                self.image_sources_mapped[src_name].get_image_capture_params())

            captured_image, img_time_seconds = self.image_sources_mapped[
                src_name].get_image_and_timestamp()
            if captured_image is None or img_time_seconds is None:
                img_resp.status = image_pb2.ImageResponse.STATUS_IMAGE_DATA_ERROR
                error_message = "Failed to capture an image from %s on the server." % src_name
                response.header.error.message = error_message
                self.logger.warning(error_message)
                continue

            # Convert the image capture time from the local clock time into the robot's time. Then set it as
            # the acquisition timestamp for the image data.
            img_resp.shot.acquisition_time.CopyFrom(
                self.bosdyn_sdk_robot.time_sync.
                robot_timestamp_from_local_secs(sec_to_nsec(img_time_seconds)))

            img_resp.shot.image.rows = img_resp.source.rows
            img_resp.shot.image.cols = img_resp.source.cols

            # Set the image data.
            img_resp.shot.image.format = img_req.image_format
            success = self._set_format_and_decode(captured_image,
                                                  img_resp.shot.image,
                                                  img_req.image_format,
                                                  img_req.quality_percent,
                                                  src_name)
            if not success:
                img_resp.status = image_pb2.ImageResponse.STATUS_UNSUPPORTED_IMAGE_FORMAT_REQUESTED

            # Set that we successfully got the image.
            if img_resp.status == image_pb2.ImageResponse.STATUS_UNKNOWN:
                img_resp.status = image_pb2.ImageResponse.STATUS_OK

        # No header error codes, so set the response header as CODE_OK.
        populate_response_header(response, request)
        return response
Esempio n. 11
0
    def GetImage(self, request, context):
        """The image service's GetImage implementation that gets the latest image capture from
        all the image sources specified in the request.

        Args:
            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.
        """
        response = image_pb2.GetImageResponse()
        for img_req in request.image_requests:
            img_resp = response.image_responses.add()
            src_name = img_req.image_source_name
            if src_name not in self.image_sources and src_name not in self.image_name_to_video:
                # This camera is not known, therefore set a failure status in the response message.
                img_resp.status = image_pb2.ImageResponse.STATUS_UNKNOWN_CAMERA
                continue

            if src_name in self.image_sources:
                img_resp.source.CopyFrom(self.image_sources[src_name])
            else:
                # Couldn't find the image source information for the device name.
                img_resp.status = image_pb2.ImageResponse.STATUS_SOURCE_DATA_ERROR

            if src_name not in self.image_name_to_video:
                # Couldn't find the image capture information for the device name.
                img_resp.status = image_pb2.ImageResponse.STATUS_IMAGE_DATA_ERROR
                continue

            capture_instance = self.image_name_to_video[src_name]
            img_resp.shot.capture_params.CopyFrom(
                capture_instance.get_capture_parameters())
            frame, img_time = capture_instance.get_last_frame()
            if frame is None or img_time is None:
                response.header.error.code = header_pb2.CommonError.CODE_INTERNAL_SERVER_ERROR
                response.header.error.message = 'Failed to capture an image from {} on the server.'.format(
                    src_name)
                return response

            # Convert the image capture time from the local clock time into the robot's time. Then set it as
            # the acquisition timestamp for the image data.
            img_resp.shot.acquisition_time.CopyFrom(
                self.bosdyn_sdk_robot.time_sync.
                robot_timestamp_from_local_secs(sec_to_nsec(img_time)))
            img_resp.shot.image.rows = int(frame.shape[0])
            img_resp.shot.image.cols = int(frame.shape[1])

            # Determine the pixel format for the data.
            if frame.shape[2] == 3:
                # RGB image.
                img_resp.shot.image.pixel_format = image_pb2.Image.PIXEL_FORMAT_RGB_U8
            elif frame.shape[2] == 1:
                # Greyscale image.
                img_resp.shot.image.pixel_format = image_pb2.Image.PIXEL_FORMAT_GREYSCALE_U8
            elif frame.shape[2] == 4:
                # RGBA image.
                img_resp.shot.image.pixel_format = image_pb2.Image.PIXEL_FORMAT_RGBA_U8
            else:
                # The number of pixel channels did not match any of the known formats.
                img_resp.shot.image.pixel_format = image_pb2.Image.PIXEL_FORMAT_UNKNOWN

            # Note, we are currently not setting any information for the transform snapshot or the frame
            # name for an image sensor since this information can't be determined with openCV.

            # Set the image data.
            if img_req.image_format == image_pb2.Image.FORMAT_RAW:
                img_resp.shot.image.data = np.ndarray.tobytes(frame)
                img_resp.shot.image.format = image_pb2.Image.FORMAT_RAW
            elif img_req.image_format == image_pb2.Image.FORMAT_JPEG:
                # If the image format is requested as UNKNOWN or JPEG, return a JPEG. Since this service
                # is for a webcam, we choose a sane default for the return if the request format is unpopulated.
                quality = self.default_jpeg_quality
                if img_req.quality_percent > 0 and img_req.quality_percent <= 100:
                    # A valid image quality percentage was passed with the image request,
                    # so use this value instead of the service's default.
                    quality = img_req.quality_percent
                encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), quality]
                img_resp.shot.image.data = cv2.imencode(
                    '.jpg', frame, encode_param)[1].tostring()
                img_resp.shot.image.format = image_pb2.Image.FORMAT_JPEG
            else:
                # If the image format is requested as UNKNOWN, return a JPEG. Since this service
                # is for a webcam, we choose a sane default for the return if the request "image_format"
                # field is unpopulated.
                quality = self.default_jpeg_quality
                if img_req.quality_percent > 0 and img_req.quality_percent <= 100:
                    # A valid image quality percentage was passed with the image request,
                    # so use this value instead of the service's default.
                    quality = img_req.quality_percent
                encode_param = [int(cv2.IMWRITE_JPEG_QUALITY), quality]
                img_resp.shot.image.data = cv2.imencode(
                    '.jpg', frame, encode_param)[1].tostring()
                img_resp.shot.image.format = image_pb2.Image.FORMAT_JPEG

            # Set that we successfully got the image.
            if img_resp.status == image_pb2.ImageResponse.STATUS_UNKNOWN:
                img_resp.status = image_pb2.ImageResponse.STATUS_OK

        # No header error codes, so set the response header as CODE_OK.
        populate_response_header(response, request)
        return response
Esempio n. 12
0
    def GetImage(self, request, context):
        """The image service's GetImage implementation that gets the latest image from the ricoh theta
        camera. This will return the last "processed" image; the Ricoh Theta camera will processes the
        images internally before outputting a jpeg.
        Note, this can take upwards of 3 seconds, so the image could be slightly older.

        Args:
            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 the Ricoh Theta camera.
        """
        response = image_pb2.GetImageResponse()
        for img_req in request.image_requests:
            img_resp = response.image_responses.add()
            if img_req.image_source_name != self.device_name:
                # The requested camera source does not match the name of the Ricoh Theta camera, so if cannot
                # be completed and will have a failure status in the response message.
                img_resp.status = image_pb2.ImageResponse.STATUS_UNKNOWN_CAMERA
                _LOGGER.info("Camera source '%s' is unknown to the Ricoh Theta image service.", img_req.image_source_name)
                continue
            # Set the image source information for the Ricoh Theta camera.
            img_resp.source.CopyFrom(self.ricoh_image_src_proto)

            # Set the image capture parameters.
            img_resp.shot.capture_params.CopyFrom(self.capture_parameters)

            # Get the last image from the camera.
            img_info_json, img_bytes = None, None
            camera_acquisition_errored = False
            try:
                img_info_json, img_bytes = self.get_last_processed_image()
            except Exception as err:
                _LOGGER.info("GetImage request threw an error: %s %s", str(type(err)), str(err))
                camera_acquisition_errored = True

            if camera_acquisition_errored:
                # Image acquisition request failed (and the camera connection is working).
                img_resp.status = image_pb2.ImageResponse.STATUS_IMAGE_DATA_ERROR
                _LOGGER.info("Setting status DATA_ERROR for the GetImage request because the get_last_processed_image() "
                            "function threw an error.")
                # Trigger a fault for the capture failure.
                fault = CAPTURE_FAILURE_FAULT
                fault.error_message = "Failed to get an image for %s." % img_req.image_source_name
                self.fault_client.trigger_service_fault_async(fault)
                continue
            else:
                # No camera errors. Clear faults for any capture failures or initialization failures since
                # images are being captured and no weird HTTP error codes are being thrown for the post
                # requests to get the images.
                self.fault_client.clear_service_fault_async(CAPTURE_FAILURE_FAULT.fault_id)

            if img_info_json is None or img_bytes is None:
                # Could not get the image data from the Ricoh Theta camera.
                img_resp.status = image_pb2.ImageResponse.STATUS_IMAGE_DATA_ERROR
                continue

            # Read the image into local memory. Apparently, the action of reading the buffer can only be performed
            # one time unless it is converted to a stream or copied.
            img_bytes_read = img_bytes.read()

            # Split on the "-" to remove the timezone information from the string.
            date_time = img_info_json["dateTimeZone"].split("-")[0]
            # Shorten the year (the first value) from a four digit year to two digit value such that the format
            # matches the datetime expectation. (Ex. 2021 --> 21).
            date_time_str = date_time[2:]
            # Convert from string to an actual datetime object
            date_time_obj = datetime.strptime(date_time_str, "%y:%m:%d %H:%M:%S")
            # Convert from a datetime object to a time object (seconds) in the local clock's time.
            time_obj = time.mktime(date_time_obj.timetuple())
            # Convert the time object in local clock into the robot's clock, and set it as the acquisition timestamp
            # for the image.
            img_resp.shot.acquisition_time.CopyFrom(self.robot.time_sync.robot_timestamp_from_local_secs(sec_to_nsec(time_obj)))

            # Set the height and width of the image.
            if "width" in img_info_json:
                img_resp.shot.image.cols = int(img_info_json["width"])
            if "height" in img_info_json:
                img_resp.shot.image.rows = int(img_info_json["height"])

            # Ricoh Theta takes colored JPEG images, so it's pixel type is RGB.
            img_resp.shot.image.pixel_format = image_pb2.Image.PIXEL_FORMAT_RGB_U8

            # Note, we are currently not setting any information for the transform snapshot or the frame
            # name for an image sensor since this information can't be determined with HTTP calls to ricoh
            # theta's api.

            # Set the image data.
            if img_req.image_format == image_pb2.Image.FORMAT_RAW:
                # Note, the returned raw bytes array from the Ricoh Theta camera is often around 8MB, so the GRPC server
                # must be setup to have an increased message size limit. The run_ricoh_image_service script does increase
                # the size to allow for the larger raw images.
                pil_image = Image.open(io.BytesIO(img_bytes_read))
                compressed_byte_buffer = io.BytesIO()
                # PIL will not do any JPEG compression if the quality is specifed as 100. It effectively treats
                # requests with quality > 95 as a request for a raw image.
                pil_image.save(compressed_byte_buffer, format=pil_image.format, quality=100)
                img_resp.shot.image.data = compressed_byte_buffer.getvalue()
                img_resp.shot.image.format = image_pb2.Image.FORMAT_RAW
            elif img_req.image_format == image_pb2.Image.FORMAT_JPEG or img_req.image_format == image_pb2.Image.FORMAT_UNKNOWN:
                # Choose the best image format if the request does not specify the image format, which is JPEG since it matches
                # the output of the ricoh theta camera and is compact enough to transmit.
                # Decode the bytes into a PIL jpeg image. This allows for the formatting to be compressed. This is then
                # converted back into a bytes array.
                pil_image = Image.open(io.BytesIO(img_bytes_read))
                compressed_byte_buffer = io.BytesIO()
                quality = self.default_jpeg_quality
                if img_req.quality_percent > 0 and img_req.quality_percent <= 100:
                    # A valid image quality percentage was passed with the image request,
                    # so use this value instead of the service's default.
                    if img_req.quality_percent > 95:
                        # PIL will not do any JPEG compression if the quality is specifed as 100. It effectively treats
                        # requests with quality > 95 as a request for a raw image.
                        quality = 95
                    else:
                        quality = img_req.quality_percent
                pil_image.save(compressed_byte_buffer, format=pil_image.format, quality=int(quality))
                img_resp.shot.image.data = compressed_byte_buffer.getvalue()
                img_resp.shot.image.format = image_pb2.Image.FORMAT_JPEG
            else:
                # Don't support RLE for ricoh theta cameras.
                img_resp.status = image_pb2.ImageResponse.STATUS_UNSUPPORTED_REQUESTED_IMAGE_FORMAT
                _LOGGER.info("GetImage request for unsupported format %s", str(image_pb2.Image.Format.Name(img_req.image_format)))

            # Set that we successfully got the image.
            if img_resp.status == image_pb2.ImageResponse.STATUS_UNKNOWN:
                img_resp.status = image_pb2.ImageResponse.STATUS_OK

        # Set the header after all image sources requested have been processed.
        populate_response_header(response, request)
        return response