Skip to content

Commit

Permalink
camera: use component ID rather than camera ID
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Oct 28, 2024
1 parent 334d9b3 commit 829ac00
Showing 1 changed file with 46 additions and 45 deletions.
91 changes: 46 additions & 45 deletions protos/camera/camera.proto
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ message Setting {

// Type to represent a setting with a list of options to choose from.
message SettingOptions {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
string setting_id = 2; // Name of the setting (machine readable)
string setting_description = 3; // Description of the setting (human readable)
repeated Option options = 4; // List of options or if range [min, max] or [min, max, interval]
Expand Down Expand Up @@ -223,74 +223,74 @@ message VideoStreamInfo {
VIDEO_STREAM_SPECTRUM_INFRARED = 2; // Infrared
}

int32 camera_id = 1; // Camera ID
int32 stream_id = 1; // Stream ID
VideoStreamSettings settings = 2; // Video stream settings
VideoStreamStatus status = 3; // Current status of video streaming
VideoStreamSpectrum spectrum = 4; // Light-spectrum of the video stream
}

message TakePhotoRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message TakePhotoResponse {
CameraResult camera_result = 1;
}

message StartPhotoIntervalRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
float interval_s = 2; // Interval between photos (in seconds)
}
message StartPhotoIntervalResponse {
CameraResult camera_result = 1;
}

message StopPhotoIntervalRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message StopPhotoIntervalResponse {
CameraResult camera_result = 1;
}

message StartVideoRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message StartVideoResponse {
CameraResult camera_result = 1;
}

message StopVideoRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message StopVideoResponse {
CameraResult camera_result = 1;
}

message StartVideoStreamingRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
int32 stream_id = 2; // video stream id
}
message StartVideoStreamingResponse {
CameraResult camera_result = 1;
}

message StopVideoStreamingRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
int32 stream_id = 2; // video stream id
}
message StopVideoStreamingResponse {
CameraResult camera_result = 1;
}

message SetModeRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
Mode mode = 2; // Camera mode to set
}
message SetModeResponse {
CameraResult camera_result = 1;
}

message ListPhotosRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
PhotosRange photos_range = 2; // Which photos should be listed (all or since connection)
}
message ListPhotosResponse {
Expand All @@ -304,7 +304,7 @@ message CameraListResponse {
}

message ModeUpdate {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
Mode mode = 2; // Camera mode
}

Expand All @@ -314,7 +314,7 @@ message ModeResponse {
}

message VideoStreamUpdate {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
VideoStreamInfo video_stream_info = 2; // Video stream info
}

Expand Down Expand Up @@ -348,7 +348,7 @@ message Storage {
STORAGE_TYPE_OTHER = 254; // Storage type other, not listed
}

int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
bool video_on = 2; // Whether video recording is currently in process
bool photo_interval_on = 3; // Whether a photo interval is currently in process

Expand All @@ -366,7 +366,7 @@ message Storage {
}

message StorageUpdate {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
Storage storage = 2; // Storage
}

Expand All @@ -376,7 +376,7 @@ message StorageResponse {
}

message CurrentSettingsUpdate {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
repeated Setting current_settings = 2; // List of current settings
}

Expand All @@ -386,7 +386,7 @@ message CurrentSettingsResponse {
}

message PossibleSettingOptionsUpdate {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
repeated SettingOptions setting_options = 2; // List of settings that can be changed
}

Expand All @@ -396,55 +396,55 @@ message PossibleSettingOptionsResponse {
}

message SetSettingRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
Setting setting = 2; // Desired setting
}
message SetSettingResponse {
CameraResult camera_result = 1;
}

message GetModeRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message GetModeResponse {
CameraResult camera_result = 1;
Mode mode = 2; // Mode
}

message GetVideoStreamInfoRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message GetVideoStreamInfoResponse {
CameraResult camera_result = 1;
VideoStreamInfo video_stream_info = 2; // Video stream info
}

message GetStorageRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message GetStorageResponse {
CameraResult camera_result = 1;
Storage storage = 2; // Camera's storage status
}

message GetCurrentSettingsRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message GetCurrentSettingsResponse {
CameraResult camera_result = 1;
repeated Setting current_settings = 2; // List of current settings
}

message GetPossibleSettingOptionsRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message GetPossibleSettingOptionsResponse {
CameraResult camera_result = 1;
repeated SettingOptions setting_options = 2; // List of settings that can be changed
}

message GetSettingRequest {
int32 camera_id = 1; // Camera ID (0/all not available)
int32 component_id = 1; // Component ID (0/all not available)
Setting setting = 2; // Requested setting
}
message GetSettingResponse {
Expand All @@ -453,51 +453,51 @@ message GetSettingResponse {
}

message FormatStorageRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
int32 storage_id = 2; //Storage identify to be format
}
message FormatStorageResponse {
CameraResult camera_result = 1;
}

message ResetSettingsRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message ResetSettingsResponse {
CameraResult camera_result = 1;
}

message ZoomInStartRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message ZoomInStartResponse {
CameraResult camera_result = 1;
}

message ZoomOutStartRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message ZoomOutStartResponse {
CameraResult camera_result = 1;
}

message ZoomStopRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message ZoomStopResponse {
CameraResult camera_result = 1;
}

message ZoomRangeRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
float range = 2; // Range must be between 0.0 and 100.0
}
message ZoomRangeResponse {
CameraResult camera_result = 1;
}

message TrackPointRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
float point_x = 2; // Point in X axis (0..1, 0 is left, 1 is right)
float point_y = 3; // Point in Y axis (0..1, 0 is top, 1 is bottom)
float radius = 4; // Radius (0 is one pixel, 1 is full image width)
Expand All @@ -507,7 +507,7 @@ message TrackPointResponse {
}

message TrackRectangleRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
float top_left_x = 2; // Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right)
float top_left_y = 3; // Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom)
float bottom_right_x = 4; // Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right)
Expand All @@ -519,35 +519,35 @@ message TrackRectangleResponse {
}

message TrackStopRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message TrackStopResponse {
CameraResult camera_result = 1;
}

message FocusInStartRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message FocusInStartResponse {
CameraResult camera_result = 1;
}

message FocusOutStartRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message FocusOutStartResponse {
CameraResult camera_result = 1;
}

message FocusStopRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
}
message FocusStopResponse {
CameraResult camera_result = 1;
}

message FocusRangeRequest {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
float range = 2; // Range must be between 0.0 - 100.0
}
message FocusRangeResponse {
Expand Down Expand Up @@ -632,7 +632,7 @@ message EulerAngle {

// Information about a picture just captured.
message CaptureInfo {
int32 camera_id = 1; // Camera ID
int32 component_id = 1; // Component ID
Position position = 2; // Location where the picture was taken
Quaternion attitude_quaternion = 3; // Attitude of the camera when the picture was taken (quaternion)
EulerAngle attitude_euler_angle = 4; // Attitude of the camera when the picture was taken (euler angle)
Expand All @@ -644,13 +644,14 @@ message CaptureInfo {

// Type to represent a camera information.
message Information {
string vendor_name = 1; // Name of the camera vendor
string model_name = 2; // Name of the camera model
float focal_length_mm = 3; // Focal length
float horizontal_sensor_size_mm = 4; // Horizontal sensor size
float vertical_sensor_size_mm = 5; // Vertical sensor size
uint32 horizontal_resolution_px = 6; // Horizontal image resolution in pixels
uint32 vertical_resolution_px = 7; // Vertical image resolution in pixels
int32 component_id = 1; // Component ID
string vendor_name = 2; // Name of the camera vendor
string model_name = 3; // Name of the camera model
float focal_length_mm = 4; // Focal length
float horizontal_sensor_size_mm = 5; // Horizontal sensor size
float vertical_sensor_size_mm = 6; // Vertical sensor size
uint32 horizontal_resolution_px = 7; // Horizontal image resolution in pixels
uint32 vertical_resolution_px = 8; // Vertical image resolution in pixels
}

// Camera list
Expand Down

0 comments on commit 829ac00

Please sign in to comment.