// Copyright (c) 2022 Boston Dynamics, Inc.  All rights reserved.
//
// Downloading, reproducing, distributing or otherwise using the SDK Software
// is subject to the terms and conditions of the Boston Dynamics Software
// Development Kit License (20191101-BDSDK-SL).

syntax = "proto3";

package bosdyn.api;
option java_outer_classname = "ImageProto";

import "bosdyn/api/header.proto";
import "bosdyn/api/geometry.proto";
import "google/protobuf/duration.proto";
import "google/protobuf/timestamp.proto";

// Rectangular color/greyscale/depth images.
message Image {
    enum Format {
        // Unknown image format.
        FORMAT_UNKNOWN = 0;

        // Color/greyscale formats.
        // JPEG format.
        FORMAT_JPEG = 1;

        // Uncompressed.  Requires pixel_format.
        FORMAT_RAW = 2;

        // 1 byte run-length before each pixel value.
        FORMAT_RLE = 3;
    }

    enum PixelFormat {
        // Unspecified value -- should not be used.
        PIXEL_FORMAT_UNKNOWN = 0;

        // One byte per pixel.
        PIXEL_FORMAT_GREYSCALE_U8 = 1;

        // Three bytes per pixel.
        PIXEL_FORMAT_RGB_U8 = 3;

        // Four bytes per pixel.
        PIXEL_FORMAT_RGBA_U8 = 4;

        // Little-endian uint16 z-distance from camera (mm).
        PIXEL_FORMAT_DEPTH_U16 = 5;

        // Two bytes per pixel.
        PIXEL_FORMAT_GREYSCALE_U16 = 6;
    }

    // Number of columns in the image (in pixels).
    int32 cols = 2;
    // Number of rows in the image (in pixels).
    int32 rows = 3;

    // Raw image data.
    bytes data = 4;

    // How the image is encoded.
    Format format = 5;

    // Pixel format of the image; this will be set even when the Format implies
    // the pixel format.
    PixelFormat pixel_format = 6;
}

// Sensor parameters associated with an image capture.
message CaptureParameters {
    // The duration of exposure in microseconds.
    google.protobuf.Duration exposure_duration = 1;

    // Sensor gain in dB.
    double gain = 2;
}

// Rectangular color/greyscale images.
message ImageCapture {
    // The time at which the image data was acquired in the robot's time basis.
    google.protobuf.Timestamp acquisition_time = 30;

    // A tree-based collection of transformations, which will include the transformations to each image's
    // sensor in addition to transformations to the common frames ("vision", "body", "odom").
    // All transforms within the snapshot are at the acquistion time of the image.
    FrameTreeSnapshot transforms_snapshot = 31;

    // The frame name for the image's sensor source. This will be included in the transform snapshot.
    string frame_name_image_sensor = 5;

    // Image data.
    Image image = 3;

    // Sensor parameters associated with this image capture.
    CaptureParameters capture_params = 4;

    // Previous fields in the protobuf that are now reserved.
    reserved 1, 2;
}

// Proto for a description of an image source on the robot.
message ImageSource {

    // The camera can be modeled as a pinhole camera described with a matrix.
    // Camera Matrix can be constructed by the camera intrinsics:
    // [[focal_length.x,         skew.x, principal_point.x],
    // [[        skew.y, focal_length.y, principal_point.y],
    // [[             0,              0,                 1]]
    message PinholeModel {
        // Intrinsic parameters are in pixel space.
        message CameraIntrinsics {
            // The focal length of the camera.
            Vec2 focal_length = 1;
            // The optical center in sensor coordinates.
            Vec2 principal_point = 2;
            // The skew for the intrinsic matrix.
            Vec2 skew = 3;
        }
        // The camera intrinsics are necessary for descrbing the pinhole camera matrix.
        CameraIntrinsics intrinsics = 1;
    }

    // The name of this image source used to get images.
    string name = 2;

    // Number of columns in the image (in pixels).
    int32 cols = 4;
    // Number of rows in the image (in pixels).
    int32 rows = 5;

    // For depth images, the pixel value that represents a depth of one meter.
    // Depth in meters can be computed by dividing the raw pixel value by this scale factor.
    double depth_scale = 6;

    // Fields reserved for deprecated messages.
    reserved 3, 7;

    oneof camera_models {
        // Rectilinear camera model.
        PinholeModel pinhole = 8;
    }

    enum ImageType {
        // Unspecified image type.
        IMAGE_TYPE_UNKNOWN = 0;

        // Color or greyscale intensity image.
        IMAGE_TYPE_VISUAL = 1;

        // Pixel values represent distances to objects/surfaces.
        IMAGE_TYPE_DEPTH = 2;
    };
    // The kind of images returned by this image source.
    ImageType image_type = 9;

    // The pixel formats a specific image source supports.
    repeated Image.PixelFormat pixel_formats = 10;

    // The image formats a specific image source supports.
    repeated Image.Format image_formats = 11;
}

// The ListImageSources request message for the robot image service.
message ListImageSourcesRequest {
    // Common request header.
    RequestHeader header = 1;
}

// The ListImageSources response message which contains all known image sources for the robot.
message ListImageSourcesResponse {
    // Common response Header.
    ResponseHeader header = 1;

    // The set of ImageSources available from this service.
    // May be empty if the service serves no cameras (e.g., if no cameras were found on startup).
    repeated ImageSource image_sources = 2;
}

// The image request specifying the image source and data format desired.
message ImageRequest {
    // The string name of the image source to get image data from.
    string image_source_name = 1;

    // Image quality: a number from 0 (worst) to 100 (highest).
    // Note that jpeg quality 100 is still lossy.
    double quality_percent = 2;

    // Specify the desired image encoding (e.g. JPEG, RAW). If no format is specified (e.g. FORMAT_UNKNOWN), the image
    // service will choose the best format for the data.
    Image.Format image_format = 3;

    // Optional specification of the desired image dimensions.
    // If the original image is 1920x1080, a resize_ratio of (2/3) will return an image with size 1280x720
    // The range is clipped to [0.01, 1] while maintaining the original aspect ratio.
    // For backwards compatibliity, a value of 0 means no resizing.
    double resize_ratio = 4;

    // Specify the desired pixel format (e.g. GREYSCALE_U8, RGB_U8). If no format is specified
    // (e.g. PIXEL_FORMAT_UNKNOWN), the image service will choose the best format for the data.
    Image.PixelFormat pixel_format = 5;
}

// The GetImage request message which can send multiple different image source requests at once.
message GetImageRequest {
    // Common request header.
    RequestHeader header = 1;

    // The different image requests for this rpc call.
    repeated ImageRequest image_requests = 2;
}

// The image response for each request, that includes image data and image source information.
message ImageResponse {
    // The image capture contains the image data and information about the state of the camera and robot
    // at the time the image was collected.
    ImageCapture shot = 1;

    // The source describes general information about the camera source the image data was collected from.
    ImageSource source = 2;

    enum Status {
        // UNKNOWN should never be used.
        // An internal ImageService issue has happened if UNKNOWN is set.
        // None of the other fields are filled out.
        STATUS_UNKNOWN = 0;

        // Call succeeded at filling out all the fields.
        STATUS_OK = 1;

        // Image source name in request is unknown.  Other fields are not filled out.
        STATUS_UNKNOWN_CAMERA = 2;

        // Failed to fill out ImageSource.  All the other fields are not filled out.
        STATUS_SOURCE_DATA_ERROR = 3;

        // There was a problem with the image data.  Only the ImageSource is filled out.
        STATUS_IMAGE_DATA_ERROR = 4;

        // The requested image format is unsupported for the image-source named. The image data will
        // not be filled out. Note, if an image request has "FORMAT_UNKNOWN", the service should choose the
        // best format to provide the data in.
        STATUS_UNSUPPORTED_IMAGE_FORMAT_REQUESTED = 5;

        // The requested pixel format is unsupported for the image-source named. The image data will
        // not be filled out. Note, if an image request has "PIXEL_FORMAT_UNKNOWN", the service
        // should choose the best format to provide the data in.
        STATUS_UNSUPPORTED_PIXEL_FORMAT_REQUESTED = 6;

        // The requested ratio is out of bounds [0,1] or unsupported by the image service
        STATUS_UNSUPPORTED_RESIZE_RATIO_REQUESTED = 7;
    }
    // Return status of the request.
    Status status = 4;

    // Previous fields in the protobuf that are now reserved.
    reserved 3, 5;
}

// The GetImage response message which includes image data for all requested sources.
message GetImageResponse {
    // Common response header.
    ResponseHeader header = 1;

    // The ordering of these image responses is defined by the order of the ImageRequests.
    repeated ImageResponse image_responses = 2;
}

