MAVLink Camera API Discussion

As an example, take a look at this current MAVLink command:

523 MAV_CMD_SET_CAMERA_SETTINGS_1   WIP: Set the camera settings part 1 (CAMERA_SETTINGS). Use NAN for values you don't want to change.
Mission Param #1    Camera ID (1 for first, 2 for second, etc.)
Mission Param #2    Aperture (1/value)
Mission Param #3    Shutter speed in seconds
Mission Param #4    ISO sensitivity
Mission Param #5    AE mode (Auto Exposure) (0: full auto 1: full manual 2: aperture priority 3: shutter priority)
Mission Param #6    EV value (when in auto exposure)
Mission Param #7    White balance (color temperature in K) (0: Auto WB)

How is the GCS supposed to know what to give the user as options? The GCS has no way to know what are the different options for Aperture, Shutter Speed, ISO, etc.

The Basic Set should have instead abstract options. Something like “High”, “Medium” and “Low” for ISO as an example. Same for Shutter Speed, It would be up to the camera to interpret those in any way it sees fit. If you want the UI to show the full range of options, you need to give the GCS something to work with.

The current set of options for AE only make sense if you have full control over Shutter Speed and/or Aperture. If you don’t have full control, Auto is the only option that works. And so it goes for the rest of settings currently defined.

@dogmaphobic I propose you publish your latest json spec here as soon as possible and we have a round of feedback.

Here is a JSON proposal Gus made:

This is just a draft, trying to come up with something that can be used. The idea is to use the same interface used for vehicle parameters. It expands on that by providing parameter exclusions, localization and different option limits based on parameter’s option selections. The file is grossly incomplete. It’s just a sketch to see if it’s worth going forward. I would need to implement this within the scope of real cameras to see what works and what doesn’t.

“definition”

It starts with a description of the hardware. The model of the camera, its hardware characteristics, definition file version etc.

“settings"

It then proceeds to list all of the settings (parameters) and their options.

“videoStreams”

A list of available video streams (0 or more)

“settingLimts”

A list of rules defining what options are available given a current selection. That is, if CameraMode is set to Video, the valid ISO values (index) are listed. If VideoResolution is set to "3840x2160 30P”, the possible ShutterSpeed values are those greater than its fps (1/30 or faster).

“settingExclusions”

Set of mutually exclusive options. That is, if ExposureMode is set to Auto, setting Aperture and ShutterSpeed is not allowed. If set to Manual, EV is not allowed (disabled).

“localization”

Self explanatory. A list of the original text strings and their corresponding, localized strings in the given locale.

{
    "definition": {
        "version":          1,
        "model":            "SD II",
        "manufacturer":     "Super Dupper Industries",
        "minFocalLength":   9.2,
        "maxFocalLength":   9.2,
        "sensorWidthPix":   4000,
        "sensorHeightPix":  3000,
        "sensorWidth":      12.4,
        "sensorHeight":     9.3
    },
    "settings": 
    [
        {
            "name":         "CameraMode",
            "title":        "Camera Mode",
            "type":         "uint32",
            "enumStrings":  ["Photo", "Video"],
            "enumValues":   [0, 1],
            "defaultValue": 1
        },
        {
            "name":         "ExposureMode",
            "title":        "Exposure Mode",
            "type":         "uint32",
            "enumStrings":  ["Auto" , "Manual", "Shutter Priority", "Aperture Priority"],
            "enumValues":   [0, 1, 2, 3 , 4],
            "defaultValue": 1
        },
        {
            "name":         "Aperture",
            "title":        "Aperture",
            "type":         "uint32",
            "enumStrings":  ["1.8", "2.0", "2.4", "2.8"],
            "enumValues":   [0, 1, 2, 3 , 4],
            "defaultValue": 0
        },
        {
            "name":         "ShutterSpeed",
            "title":        "Shutter Speed",
            "type":         "float",
            "enumStrings":  ["4", "3", "2", "1", "1/4", "1/8", "1/15", "1/30", "1/60", "1/125", "1/250", "1/500", "1/1000"],
            "enumValues":   [4.0, 3.0, 2.0, 1.0, 0.25, 0.125, 0.066666, 0.033333, 0.016666, 0.008, 0.004, 0.002, 0.001],
            "defaultValue": 8
        },
        {
            "name":         "ISO",
            "title":        "ISO",
            "type":         "uint32",
            "enumStrings":  ["100", "200", "400", "800", "1600", "3200", "6400"],
            "enumValues":   [100, 200, 400, 800, 1600, 3200, 6400],
            "defaultValue": 100
        },
        {
            "name":         "EV",
            "title":        "Exposure Compensation",
            "type":         "float",
            "enumStrings":  ["-2.0", "-1.5", "-1.0", "-0.5", "0", "+0.5", "+1.0", "+1.5", "+2.0"],
            "enumValues":   [-2.0, -1.5, -0.5, 0, 0.5, 1.0, 1.5, 2.0],
            "defaultValue": 0
        },
        {
            "name":         "VideoResolution",
            "title":        "Video Resolution",
            "type":         "uint32",
            "enumStrings":  ["3840x2160 30P", "3840x2160 24P", "1920x1080 60P", "1920x1080 30P", "1920x1080 24P"],
            "enumValues":   [0, 1, 2, 3, 4],
            "defaultValue": 0
        },
        {
            "name":         "MeteringMode",
            "title":        "Metering Mode",
            "type":         "uint32",
            "enumStrings":  ["Average", "Center", "Spot"],
            "enumValues":   [0, 1, 2],
            "defaultValue": 0
        },
        {
            "name":         "ColorMode",
            "title":        "Color Mode",
            "type":         "uint32",
            "enumStrings":  ["Neutral", "Vivid", "Black and White"],
            "enumValues":   [0, 1, 2],
            "defaultValue": 0
        }
    ],
    "videoStreams":
    [
        {
            "VisibleLight":
            {
                "description":  "Visible Light",
                "url":          "rtsp://192.168.92.1:1525/live",
            }
        },
        {
            "ThermalImaging":
            {
                "description":  "Thermal Imaging",
                "url":          "rtsp://192.168.92.1:4525/live",
            }
        }
    ],
    "settingLimts":
    {
        "CameraMode":
        {
            "Video":
            {
                "ISO":
                {
                    "validIndex":   [0, 1, 2, 3, 4, 5]
                }
            }
        },
        "VideoResolution":
        {
            "3840x2160 30P":
            {
                "ShutterSpeed":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            },
            "3840x2160 24P":
            {
                "ShutterSpeed":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            },
            "1920x1080 60P":
            {
                "ShutterSpeed":
                {
                    "validIndex":   [8, 9, 10, 11, 12]
                }
            },
            "1920x1080 30P":
            {
                "ShutterSpeed":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            },
            "1920x1080 24P":
            {
                "ShutterSpeed":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            }
        }
    },
    "settingExclusions":
    {
        "ExposureMode":
        {
            "Auto":     ["Aperture", "ShutterSpeed"],
            "Manual":   ["EV"]
        }
    },
    "localization":
    [
        {
            "locale":       "pt_BR",
            "strings":
            {
                "Camera Mode":              "Modo de Camera",
                "Photo":                    "Fotografia",
                "Video":                    "Videografia",
                "Exposure Mode":            "Modo de Exposição",
                "Auto":                     "Automático",
                "Manual":                   "Manual",
                "Shutter Priority":         "Prioridade de Exposição",
                "Aperture Priority":        "Prioridade de Abertura",
                "Aperture":                 "Abertura",
                "Shutter Speed":            "Velocidade",
                "Exposure Compensation":    "Compensação de Exposição",
                "Video Resolution":         "Resolução de Video"
            }    
        }
    ]
}

As I understand, the idea of the definition file is to define the entire system that can have one or multiple cameras. The proposed file(@dogmaphobic ) is centered around camera and their parameters. Instead of having camera definition file, I suggest we use camera-usecase definition file. Define the file with the set of use cases supported. Each usecase inturn will have the list of settings supported. GCS will send mavlink messages to set the parameters and invoke the use case. Just to give an idea -

{
"fileDescription": {
	"name":	"camera-usecase-def.json"
	"description": "Camera usecase definition file"
	"version":	1
},
"systemDescription": 
{
	"name": "Intel Aero"
	"version: 1
	"cameraDescription":
	[
		{
			"name": "OV8858",
			"description":	"8MP RGB Camera"
			"uid": 1,
		},
		{
			"name": "OV7251",
			"description":	"VGA Camera"
			"uid": 2,
		},
		{
			"name": "R200",
			"description":	"Depth Sensing and Vision Camera"
			"uid": 3,
		}
	]
},
"usecase-image-capture-front": {
	"Description" : "8MP Front Camera Image Capture"
	"uid" : 11
	"settings":
	[
		{
			"name": "Resolution"
			"title": "Image Resolution"
			"type": "uint32"
			"enumStrings": ["3264x2448","3264x1836","2112x1188","1920x1080","1408x792"],
			"enumValues": [0,1,2,3,4],
			"defaultValue": 0
		},
		{
			"name":         "ExposureMode",
			"title":        "Exposure Mode",
			"type":         "uint32",
			"enumStrings":  ["Auto" , "Manual", "Shutter Priority", "Aperture Priority"],
			"enumValues":   [0, 1, 2, 3 , 4],
			"defaultValue": 1
		},
		...
	]
	"settingLimits": 
	{
	},
	"settingExclusions":
	{
	}
},
"usecase-video-capture-front": {
	"Description" : "8MP Front Camera Video Capture"
	"uuid" : 12
	"settings":
	[
		{
			"name": "streamFormat",
			"title": "Stream Format",
			"type": "uint32",
			"enumStrings": ["AVC1", "H264", "X264"],
			"enumValues": [0,1,2],
			"defaultValue": 1
		},
		{
			"name": "FileFormat",
			"title": "File Container Format",
			"type": "uint32",
			"enumStrings": ["3GP", "MP4"],
			"enumValues": [0,1],
			"defaultValue": 1
		},
		...
		
	]
	"settingLimits": 
	{
	},
	"settingExclusions":
	{
	}	
},
"usecase-video-streaming-front": {
	"Description" : "8MP Front Camera Video Streaming"
	"uuid" : 13
	"settings":
	[
		{
			"name": "streamFormat",
			"title": "Stream Format",
			"type": "uint32",
			"enumStrings": ["AVC1", "H264", "X264"],
			"enumValues": [0,1,2],
			"defaultValue": 1
		},
		{
			"name": "streamingProtocol",
			"title": "Video Streaming Protocol",
			"type": "uint32",
			"enumStrings": ["UDP", "RTSP"],
			"enumValues": [0,1],
			"defaultValue": 1
		},
		...
		
	]
	"settingLimits": 
	{
	},
	"settingExclusions":
	{
	}
},
"usecase-image-capture-bottom": {
},
"usecase-video-capture-bottom": {
},
"usecase-video-streaming-bottom": {
},
"usecase-video-streaming-infrared": {
},
"usecase-video-streaming-360": {
},
"usecase-video-snapshot": {
},

}

Interesting concept. I guess the end result will be a combination of all of the above.

Random thoughts:

We have Video Streaming and Video/Photo capturing. Invariably, and by far more common, these are within the same camera. The stream shows what the camera sees so you can control it as a “Viewfinder” on a regular camera. Using these camera-usecases, how do you reconcile a camera that is used for both streaming and capturing?

There are cases where you have a front facing camera (some times called FPV) and a cinematography camera. In this scenario you have two simultaneous streams but normally only the cine camera is used for capturing videos (and require all the camera parameter controls).

There are other cases where one single camera produces two or more video streams. A thermal imaging camera will stream a “live” video and a “thermal” imaging video. You would then overlay both within the UI.

Also, how do you handle rules and exceptions for parameters?

We can discuss this further at tomorrow’s meeting.

I’m a bit behind schedule on this. After talking to Julian and Don, I have a better grasp on the definition file (the Json file) but I have yet to come up with a mechanism to get/set these parameters. The original idea was to use the existing parameter protocol (PARAM_VALUE) but that does not gives us the responses we need (when compared to COMMAND_LONG). The idea is to come up with a new COMMAND_KEYVALUE_PAIR message, which would respond in the same manner COMMAND_LONG responds. That part I have not yet sorted out.

In summary:

Camera discovery is done by issuing MAV_CMD_REQUEST_CAMERA_INFORMATION

You get in response either nothing (no camera is available) or one or more CAMERA_INFORMATION messages. These messages may or may not include an URI to retrieve the camera definition file,

If no file exists (but a camera is present), only a basic set of camera commands will be used:

MAV_CMD_SET_CAMERA_MODE
MAV_CMD_IMAGE_START_CAPTURE
MAV_CMD_IMAGE_STOP_CAPTURE
MAV_CMD_VIDEO_START_CAPTURE
MAV_CMD_VIDEO_STOP_CAPTURE

And a subset of the existing:

MAV_CMD_REQUEST_CAMERA_SETTINGS
CAMERA_SETTINGS

In this case, both video and image capture will occur at the camera’s maximum resolution (or whatever manual settings is allowed by the camera using its own, hardware controls). It also means a few new bits of information will need to be added to the CAMERA_INFORMATION message. It should tells us if the camera is able to capture photos and/or videos. It should also tells us if these are exclusive of each other. That is, can it capture both but it is modal? If so we will need to use MAV_CMD_SET_CAMERA_MODE to set the desired mode. Most cameras allow capturing images when in video mode but not the other way around. This information will also need to be added to this bitmap to tell us if we are allowed to start/stop video recording when in photo mode (or start/stop still capture when in video mode).

If a camera definition file does exist, the GCS will load it and build its UI based on the information provided within. The GCS loads the file, immediately performs all the localization replacements if that is available and/or needed and hold in memory a class responsible for controlling/setting the camera. That includes changing the available settings and options based on the rules and limits described within the definition file.

The next step after the file is loaded, parsed and validated is to request from the camera all the parameters so the GCS can update the current values. At that point the GCS is ready to display the UI to the user.

Once the user changes a value, the GCS will use a command to send it to the camera and it will expect an ACK from the camera to know if the value was received and accepted.

The command used to send to the camera is included in the definition value along with the possible options for each command.

An extremely short description of the file:

The definition file starts with a set of constants describing the camera. It proceeds to list all the parameters available along with their possible options. In addition, it list rules for limits and exceptions depending on how certain parameters are set. It ends with a list of strings used for localization.

The oddball item in the file is the videoStreams section. This is an optional section and I only listed here because I run into a situation where a camera has two streams that must be overlaid on top of each other. This videoStreams section allows to define how this is supposed to work. It gives the URL for each stream, it tells us these are not “exclusive” streams and it tells us the order in which they are to be overlaid. In all other scenarios, streams are exclusive. You normally only have one stream running. In those cases, you don’t need to define them in this file. You use the existing set of MAVLink messages to discover/define/start/stop them. In other words, if the videoStreams section is not included, the GCS will use the Video Stream set of messages to handle video streams.

And updated version of the Definition File (note that I have not updated the localization section):

{
    "definition": {
        "version":          1,
        "model":            "SD II",
        "manufacturer":     "Super Dupper Industries",
        "minFocalLength":   9.2,
        "maxFocalLength":   9.2,
        "sensorWidthPix":   4000,
        "sensorHeightPix":  3000,
        "sensorWidth":      12.4,
        "sensorHeight":     9.3,
        "capturePhoto":     1,
        "captureVideo":     1,
        "hasSeparateModes": 1,
        "spotWsize":        0.1,
        "spotHsize":        0.1,
        "centerWSize":      0.1,
        "centerHSize":      0.1,
    },
    "settings": 
    [
        {
            "name":             "CAM_MODE",
            "shortDescription": "Camera Mode",
            "type":             "uint32",
            "enumStrings":      ["Photo", "Video"],
            "enumValues":       [0, 1],
            "defaultValue":     1,
            "control":          0
        },
        {
            "name":             "CAM_WBMODE",
            "shortDescription": "White Balance Mode",
            "type":             "uint32",
            "enumStrings":      ["Auto" , "Sunny", "Cloudy", "Fluorescent", "Incandescent", "Sunset"],
            "enumValues":       [0, 1, 2, 3 , 4, 5],
            "defaultValue":     0
        },
        {
            "name":             "CAM_EXPMODE",
            "shortDescription": "Exposure Mode",
            "type":             "uint32",
            "enumStrings":      ["Auto" , "Manual", "Shutter Priority", "Aperture Priority"],
            "enumValues":       [0, 1, 2, 3],
            "defaultValue":     0
        },
        {
            "name":             "CAM_APERTURE",
            "shortDescription": "Aperture",
            "type":             "uint32",
            "enumStrings":      ["1.8", "2.0", "2.4", "2.8"],
            "enumValues":       [0, 1, 2, 3],
            "defaultValue":     0
        },
        {
            "name":             "CAM_SHUTTERSPD",
            "shortDescription": "Shutter Speed",
            "type":             "float",
            "enumStrings":      ["4", "3", "2", "1", "1/4", "1/8", "1/15", "1/30", "1/60", "1/125", "1/250", "1/500", "1/1000"],
            "enumValues":       [4.0, 3.0, 2.0, 1.0, 0.25, 0.125, 0.066666, 0.033333, 0.016666, 0.008, 0.004, 0.002, 0.001],
            "defaultValue":     8
        },
        {
            "name":             "CAM_ISO",
            "shortDescription": "ISO",
            "type":             "uint32",
            "enumStrings":      ["100", "200", "400", "800", "1600", "3200", "6400"],
            "enumValues":       [100, 200, 400, 800, 1600, 3200, 6400],
            "defaultValue":     100
        },
        {
            "name":             "CAM_EV",
            "shortDescription": "Exposure Compensation",
            "type":             "float",
            "enumStrings":      ["-2.0", "-1.5", "-1.0", "-0.5", "0", "+0.5", "+1.0", "+1.5", "+2.0"],
            "enumValues":       [-2.0, -1.5, -0.5, 0, 0.5, 1.0, 1.5, 2.0],
            "defaultValue":     0
        },
        {
            "name":             "CAM_VIDRES",
            "shortDescription": "Video Resolution",
            "type":             "uint32",
            "enumStrings":      ["3840x2160 30P", "3840x2160 24P", "1920x1080 60P", "1920x1080 30P", "1920x1080 24P"],
            "enumValues":       [0, 1, 2, 3, 4],
            "defaultValue":     0
        },
        {
            "name":             "CAM_VIDFMT",
            "shortDescription": "Video Format",
            "type":             "uint32",
            "enumStrings":      ["h.264", "HEVC"],
            "enumValues":       [0, 1],
            "defaultValue":     0
        },
        {
            "name":             "CAM_AUDIOREC",
            "shortDescription": "Record Audio",
            "type":             "bool",
            "defaultValue":     0
        },
        {
            "name":             "CAM_METERING",
            "shortDescription": "Metering Mode",
            "type":             "uint32",
            "enumStrings":      ["Average", "Center", "Spot"],
            "enumValues":       [0, 1, 2],
            "defaultValue":     0
        },
        {
            "name":             "CAM_SPOTX",
            "shortDescription": "Spot Metering X Coordinate",
            "type":             "double",
            "defaultValue":     0.45,
            "min":              0,
            "max":              0.9,
            "control:":         0
        },
        {
            "name":             "CAM_SPOTY",
            "shortDescription": "Spot Metering Y Coordinate",
            "type":             "double",
            "defaultValue":     0.45,
            "min":              0,
            "max":              0.9,
            "control:":         0
        },
        {
            "name":             "CAM_COLORMODE",
            "shortDescription": "Color Mode",
            "type":             "uint32",
            "enumStrings":      ["Neutral", "Enhanced", "Unprocessed", "Night"],
            "enumValues":       [0, 1, 2, 4],
            "defaultValue":     1
        },
        {
            "name":             "CAM_PHOTORES",
            "shortDescription": "Photo Resolution",
            "type":             "uint32",
            "enumStrings":      ["Large", "Medium", "Small"],
            "enumValues":       [0, 1, 2],
            "defaultValue":     0
        },
        {
            "name":             "CAM_PHOTOFMT",
            "shortDescription": "Image Format",
            "type":             "uint32",
            "enumStrings":      ["Jpeg", "Raw", "Jpeg+Raw"],
            "enumValues":       [0, 1, 2],
            "defaultValue":     0
        },
        {
            "name":             "CAM_PHOTOQUAL",
            "shortDescription": "Image Quality",
            "type":             "uint32",
            "enumStrings":      ["Fine", "Medium", "Low"],
            "enumValues":       [0, 1, 2],
            "defaultValue":     1
        },
        {
            "name":             "CAM_FLICKER",
            "shortDescription": "Flickering Mode",
            "type":             "uint32",
            "enumStrings":      ["Auto", "50Hz", "60Hz"],
            "enumValues":       [0, 1, 2],
            "defaultValue":     0
        }
    ],
    "videoStreams":
    [
        {
            "VisibleLight":
            {
                "description":  "Visible Light",
                "url":          "rtsp://192.168.92.1:1525/live",
                "exclusive":    0,
                "layer":        0
            }
        },
        {
            "ThermalImaging":
            {
                "description":  "Thermal Imaging",
                "url":          "rtsp://192.168.92.1:4525/live",
                "exclusive":    0,
                "layer":        1
            }
        }
    ],
    "settingLimts":
    {
        "CAM_MODE":
        {
            "1":
            {
                "CAM_ISO":
                {
                    "validIndex":   [0, 1, 2, 3, 4, 5]
                }
            }
        },
        "CAM_VIDRES":
        {
            "0":
            {
                "CAM_SHUTTERSPD":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            },
            "1":
            {
                "CAM_SHUTTERSPD":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            },
            "2":
            {
                "CAM_SHUTTERSPD":
                {
                    "validIndex":   [8, 9, 10, 11, 12]
                }
            },
            "3":
            {
                "CAM_SHUTTERSPD":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            },
            "4":
            {
                "CAM_SHUTTERSPD":
                {
                    "validIndex":   [7, 8, 9, 10, 11, 12]
                }
            }
        }
    },
    "settingExclusions":
    {
        "CAM_EXPMODE":
        {
            "0":        ["CAM_ISO", "CAM_SHUTTERSPD"],
            "1":        ["CAM_EV"]
        },
        "CAM_MODE":
        {
            "0":        ["CAM_VIDRES", "CAM_VIDFMT", "CAM_AUDIOREC"],
            "1":        ["CAM_PHOTOFMT", "CAM_PHOTOQUAL", "CAM_PHOTORES"]
        },
        "CAM_PHOTOFMT":
        {
            "1":        ["CAM_PHOTOQUAL", "CAM_PHOTORES"]
        }
    },
    "localization":
    [
        {
            "locale":       "pt_BR",
            "strings":
            {
                "Camera Mode":              "Modo de Camera",
                "Photo":                    "Fotografia",
                "Video":                    "Videografia",
                "Exposure Mode":            "Modo de Exposição",
                "Auto":                     "Automático",
                "Manual":                   "Manual",
                "Shutter Priority":         "Prioridade de Exposição",
                "Aperture Priority":        "Prioridade de Abertura",
                "Aperture":                 "Abertura",
                "Shutter Speed":            "Velocidade",
                "Exposure Compensation":    "Compensação de Exposição",
                "Video Resolution":         "Resolução de Video"
            }    
        }
    ]
}

Here is one of the scenarios that I had mentioned during the call and that needs to be handled -

The processing block can be something like this - Home · intel/libxcam Wiki · GitHub

The idea is to use the PARAM_SET/PARAM_VALUE interface for getting/setting camera parameters. The issue is that currently, there is no proper ACK response when using that protocol.

Here is a suggestion for an Extended version of PARAM_SET/PARAM_GET for discussion.

PARAM_EXT_SET
target_sys_id   uint8_t
target_comp_id  uint8_t
param_id        char[16]
param_value     char[128]   (cast to whatever)
param_type      uint8_t     MAV_PARAM_TYPE enum, where char[128] would be added

enum
PARAM_ACK_RESULT_ACCEPTED
PARAM_ACK_RESULT_TEMPORARILY_REJECTED
PARAM_ACK_RESULT_UNSUPPORTED
PARAM_ACK_RESULT_FAILED
PARAM_ACK_RESULT_IN_PROGRESS

PARAM_EXT_ACK
param_id        char[16]
param_value     char[128]   (cast to whatever)
param_result    uint8_t     PARAM_ACK_RESULT enum
param_type      uint8_t     MAV_PARAM_TYPE enum

Example messages abbreviated to only relevant fields.

• When the parameter is received, set and accepted immediately (which is the case for most settings) you get only one ACK:

PARAM_EXT_ACK
param_value  = value set
param_result = PARAM_ACK_RESULT_ACCEPTED

• When the parameter is received but it will take a while to deal with it (such as camera mode switch):

PARAM_EXT_ACK
param_value  = current value
param_result = PARAM_ACK_RESULT_IN_PROGRESS

• Once the camera is done setting it, it would send an appropriate second PARAM_EXT_ACK

PARAM_EXT_ACK
param_value  = value set
param_result = PARAM_ACK_RESULT_ACCEPTED

• When there is a problem setting the parameter:

PARAM_EXT_ACK
param_value  = current value
param_result = PARAM_ACK_some_error_above

Similar changes to PARAM_REQUEST_LIST, PARAM_REQUEST_READ, etc.

Ok, all new stuff pushed and/or updated. Once this is in I can add this part of the implementation



@dogmaphobic Do you see a need to reserve multiple component IDs for camera? Currently we have only one for -
100 MAV_COMP_ID_CAMERA

Good question. When I asked Julian, he said just to use MAV_COMP_ID_CAMERA, MAV_COMP_ID_CAMERA+1, etc. (on the camera side)

In my discovery code (within QGC), I send a MAV_CMD_REQUEST_CAMERA_INFORMATION command to any heartbeat I see other than from the autopilot, which doesn’t seem too kosher. I agree that we should probably limit to a known set of component IDs. On the other hand, by not limiting the listening to heartbeats to a preset set of component IDs, anything that responds to a MAV_CMD_REQUEST_CAMERA_INFORMATION gets added.

I’m open to any suggestions.

New, XML camera definition. This is already being parsed and all functionality defined within is done within QGC. Now I need to get the parameter protocol working so I can actually communicate with the camera(s).

<?xml version="1.0" encoding="UTF-8" ?>
<mavlinkcamera>
    <definition version="1">
        <model>SD II</model>
        <vendor>Super Dupper Industries</vendor>
    </definition>
    <parameters>
        <parameter name="CAM_MODE" type="uint32" default="1">
            <description>Camera Mode</description>
            <options>
                <option name="Photo" value="0">
                    <!-- This tells us when Camera Mode is set to Photo mode, the following parameters should be ignored (hidden from UI or disabled)-->
                    <exclusions>
                        <exclude>CAM_VIDRES</exclude>
                        <exclude>CAM_VIDFMT</exclude>
                        <exclude>CAM_AUDIOREC</exclude>
                    </exclusions>
                </option>
                <option name="Video" value="1">
                    <exclusions>
                        <exclude>CAM_PHOTOFMT</exclude>
                        <exclude>CAM_PHOTOQUAL</exclude>
                        <exclude>CAM_PHOTORES</exclude>
                    </exclusions>
                    <parameterranges>
                       <!-- This tells us when Camera Mode is set to Video mode, the CAM_ISO parameter has only a subset of its normal options. -->
                        <parameterrange parameter="CAM_ISO">
                            <roption name="100" value="100" />
                            <roption name="200" value="200" />
                            <roption name="400" value="400" />
                            <roption name="800" value="800" />
                            <roption name="1600" value="1600" />
                            <roption name="3200" value="3200" />
                        </parameterrange>
                    </parameterranges>
                </option>
            </options>
        </parameter>
        <parameter name="CAM_WBMODE" type="uint32" default="0">
            <description>White Balance Mode</description>
            <options>
                <option name="Auto" value="0" />
                <option name="Sunny" value="1" />
                <option name="Cloudy" value="2" />
                <option name="Fluorescent" value="3" />
                <option name="Incandescent" value="4" />
                <option name="Sunset" value="5" />
            </options>
        </parameter>
        <parameter name="CAM_EXPMODE" type="uint32" default="0">
            <description>Exposure Mode</description>
            <options default="0">
                <option name="Auto" value="0">
                    <exclusions>
                        <exclude>CAM_ISO</exclude>
                        <exclude>CAM_SHUTTERSPD</exclude>
                        <exclude>CAM_APERTURE</exclude>
                    </exclusions>
                </option>
                <option name="Manual" value="1">
                    <exclusions>
                        <exclude>CAM_EV</exclude>
                    </exclusions>
                </option>
            </options>
        </parameter>
        <parameter name="CAM_APERTURE" type="uint32" default="0">
            <description>Aperture</description>
            <options>
                <option name="1.8" value="0" />
                <option name="2.0" value="1" />
                <option name="2.4" value="2" />
                <option name="4" value="3" />
                <option name="5.6" value="4" />
                <option name="8" value="5" />
                <option name="11" value="6" />
                <option name="16" value="7" />
                <option name="22" value="8" />
            </options>
        </parameter>
        <parameter name="CAM_SHUTTERSPD" type="float" default="0.016666">
            <description>Shutter Speed</description>
            <options>
                <option name="4" value="4" />
                <option name="3" value="3" />
                <option name="2" value="2" />
                <option name="1" value="1" />
                <option name="1/4" value="0.25" />
                <option name="1/8" value="0.125" />
                <option name="1/15" value="0.066666" />
                <option name="1/30" value="0.033333" />
                <option name="1/60" value="0.016666" />
                <option name="1/125" value="0.008" />
                <option name="1/250" value="0.004" />
                <option name="1/500" value="0.002" />
                <option name="1/1000" value="0.001" />
            </options>
        </parameter>
        <parameter name="CAM_ISO" type="uint32" default="100">
            <description>ISO</description>
            <options>
                <option name="100" value="100" />
                <option name="200" value="200" />
                <option name="400" value="400" />
                <option name="800" value="800" />
                <option name="1600" value="1600" />
                <option name="3200" value="3200" />
                <option name="6400" value="6400" />
            </options>
        </parameter>
        <parameter name="CAM_EV" type="float" default="0">
            <description>Exposure Compensation</description>
            <options>
                <option name="-2" value="-2" />
                <option name="-1.5" value="-1.5" />
                <option name="-1" value="-1" />
                <option name="-0.5" value="-0.5" />
                <option name="0" value="0" />
                <option name="+0.5" value="0.5" />
                <option name="+1" value="1" />
                <option name="+1.5" value="1.5" />
                <option name="+2" value="2" />
            </options>
        </parameter>
        <parameter name="CAM_VIDRES" type="uint32" default="0">
            <description>Video Resolution</description>
            <options>
                <option name="3840x2160 30P" value="0">
                    <parameterranges>
                        <!-- When Camera Mode is Video and Exposure Mode is Manual, Shutter Speed cannot be slower than the frame rate -->
                        <parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
                            <roption name="1/30" value="0.033333" />
                            <roption name="1/60" value="0.016666" />
                            <roption name="1/125" value="0.008" />
                            <roption name="1/250" value="0.004" />
                            <roption name="1/500" value="0.002" />
                            <roption name="1/1000" value="0.001" />
                        </parameterrange>
                    </parameterranges>
                </option>
                <option name="3840x2160 24P" value="1">
                    <parameterranges>
                        <parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
                            <roption name="1/30" value="0.033333" />
                            <roption name="1/60" value="0.016666" />
                            <roption name="1/125" value="0.008" />
                            <roption name="1/250" value="0.004" />
                            <roption name="1/500" value="0.002" />
                            <roption name="1/1000" value="0.001" />
                        </parameterrange>
                    </parameterranges>
                </option>
                <option name="1920x1080 60P" value="2">
                    <parameterranges>
                        <parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
                            <roption name="1/60" value="0.016666" />
                            <roption name="1/125" value="0.008" />
                            <roption name="1/250" value="0.004" />
                            <roption name="1/500" value="0.002" />
                            <roption name="1/1000" value="0.001" />
                        </parameterrange>
                    </parameterranges>
                </option>
                <option name="1920x1080 30P" value="3">
                    <parameterranges>
                        <parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
                            <roption name="1/30" value="0.033333" />
                            <roption name="1/60" value="0.016666" />
                            <roption name="1/125" value="0.008" />
                            <roption name="1/250" value="0.004" />
                            <roption name="1/500" value="0.002" />
                            <roption name="1/1000" value="0.001" />
                        </parameterrange>
                    </parameterranges>
                </option>
                <option name="1920x1080 24P" value="4">
                    <parameterranges>
                        <parameterrange parameter="CAM_SHUTTERSPD" condition="CAM_MODE=1 AND CAM_EXPMODE=1">
                            <roption name="1/30" value="0.033333" />
                            <roption name="1/60" value="0.016666" />
                            <roption name="1/125" value="0.008" />
                            <roption name="1/250" value="0.004" />
                            <roption name="1/500" value="0.002" />
                            <roption name="1/1000" value="0.001" />
                        </parameterrange>
                    </parameterranges>
                </option>
            </options>
        </parameter>
        <parameter name="CAM_VIDFMT" type="uint32" default="0">
            <description>Video Format</description>
            <options>
                <option name="h.264" value="0" />
                <option name="HEVC" value="1" />
            </options>
        </parameter>
        <parameter name="CAM_AUDIOREC" type="bool" default="0">
            <description>Record Audio</description>
        </parameter>
        <parameter name="CAM_METERING" type="uint32" default="0">
            <description>Metering Mode</description>
            <options>
                <option name="Average" value="0" />
                <option name="Center" value="1" />
                <option name="Spot" value="2" />
            </options>
        </parameter>
        <parameter name="CAM_COLORMODE" type="uint32" default="1">
            <description>Color Mode</description>
            <options>
                <option name="Neutral" value="0" />
                <option name="Enhanced" value="1" />
                <option name="Unprocessed" value="2" />
                <option name="Black &amp; White" value="3" />
            </options>
        </parameter>
        <parameter name="CAM_PHOTORES" type="uint32" default="0">
            <description>Photo Resolution</description>
            <options>
                <option name="Large" value="0" />
                <option name="Medium" value="1" />
                <option name="Small" value="2" />
            </options>
        </parameter>
        <parameter name="CAM_PHOTOFMT" type="uint32" default="0">
            <description>Image Format</description>
            <options>
                <option name="Jpeg" value="0" />
                <option name="Raw" value="1">
                    <exclusions>
                        <exclude>CAM_PHOTOQUAL</exclude>
                        <exclude>CAM_PHOTORES</exclude>
                    </exclusions>
                </option>
                <option name="Jpeg+Raw" value="2" />
            </options>
        </parameter>
        <parameter name="CAM_PHOTOQUAL" type="uint32" default="1">
            <description>Image Quality</description>
            <options>
                <option name="Fine" value="0" />
                <option name="Medium" value="1" />
                <option name="Low" value="2" />
            </options>
        </parameter>
    </parameters>
    <!-- Video Streams (Optional. If not present, the standard MAVLink video stream discovery will be used instead) -->
    <videostreams>
        <!-- If exclusive is 0, all streams run at the same time. The layer defines the order. -->
        <!-- If exclusive is 1, the user will select one of the availabe streams and only that one is shown. -->
        <videostream exclusive="0" layer="0">
            <description>Visible Light</description>
            <url>rtsp://192.168.92.1:1525/live</url>
        </videostream>
        <videostream exclusive="0" layer="1">
            <description>Thermal Imaging</description>
            <url>rtsp://192.168.92.1:4525/live</url>
        </videostream>
    </videostreams>
    <localization>
        <!-- If no appropriate locale is found, the original (above) will be used -->
        <!-- At runtime, the code will go through every "description" and "option name" looking for "original" and replace it with "translated" -->
        <locale name="pt_BR"> 
            <strings original="Aperture" translated="Abertura" />
            <strings original="Auto" translated="Automático" />
            <strings original="Average" translated="Média" />
            <strings original="Black &amp; White" translated="Preto e Branco" />
            <strings original="Camera Mode" translated="Modo de Operação" />
            <strings original="Center" translated="Centro" />
            <strings original="Cloudy" translated="Nublado" />
            <strings original="Color Mode" translated="Processo de Cor" />
            <strings original="Enhanced" translated="Realçado" />
            <strings original="Exposure Compensation" translated="Compensação de Exposição" />
            <strings original="Exposure Mode" translated="Modo de Exposição" />
            <strings original="Fine" translated="Fino" />
            <strings original="Fluorescent" translated="Fluorescente" />
            <strings original="Image Format" translated="Formato de Imagem" />
            <strings original="Image Quality" translated="Qualidade de Imagem" />
            <strings original="Incandescent" translated="Incandescente" />
            <strings original="Large" translated="Grande" />
            <strings original="Low" translated="Baixa" />
            <strings original="Manual" translated="Manual" />
            <strings original="Medium" translated="Média" />
            <strings original="Metering Mode" translated="Modo de Fotogrametria" />
            <strings original="Neutral" translated="Neutro" />
            <strings original="Photo Resolution" translated="Resolução de Foto" />
            <strings original="Photo" translated="Foto" />
            <strings original="Record Audio" translated="Gravar Áudio" />
            <strings original="Shutter Priority" translated="Prioridade de Exposição" />
            <strings original="Shutter Speed" translated="Velocidade" />
            <strings original="Small" translated="Pequena" />
            <strings original="Sunny" translated="Ensolarado" />
            <strings original="Sunset" translated="Por do Sol" />
            <strings original="Unprocessed" translated="Não Processado" />
            <strings original="Video Format" translated="Format de Vídeo" />
            <strings original="Video Resolution" translated="Resolução de Video" />
            <strings original="Video" translated="Vídeo" />
            <strings original="White Balance Mode" translated="Modo de Balanço Cromático" />
        </locale>
    </localization>
</mavlinkcamera>

I would like to point to two locations in the simulator that would lend themselves for end-to-end tests. What I would propose is to implement a library implementing a camera event loop and to test this library in SITL:

Hi. I’m working on my drone control software with camera support. I’ve seen your latest camera commits to QGC and successfully added support for my camera controller software.
I’d write few ideas:

  1. We could dedicate a value in autopilot field in heartbeat message and then use it to determine if component has camera capabilities.
    Using this way we don’t need to ping each component in order to check if it is a camera.
  2. I’d use different component IDs for each camera instead of adding camera_id field for related messages.
  3. I also like the idea of using PARAM_SET for camera settings.

Maybe it is offtopic, but I also think that binding component IDs to some specific device type adds limitations. We may proceed with some more flexible way like using comp_id flag only for addressing purposes, but using some another field like “device_type” for determining component type.

@dogmaphobic Hi. I’m still working on camera integration. I guess that the easiest way to make camera discoverable would be to add MAV_CAMERA to MAV_TYPE enum (but currently I still use the way suggested by you).
What do you think? I just want to make my system to be supported by QGCS as well.

What to you mean by that? QGC will probe any heartbeat with a component ID different from the autopilot (not just the defined camera component IDs).

Check Redirecting... Page moved

Sorry that I didn’t explain it well.
I’m suggesting to add new enum value MAV_CAMERA to be used in “type” field in heartbeat messages.
So if we see that type is set to MAV_CAMERA we can be sure that there is a camera without sending MAV_CMD_REQUEST_CAMERA_INFORMATION (in fact we need to send it to cameras anyway but we don’t need to poll each detected device).

I think you’ll find camera management in ArduPilot differs: you really need to look at what messages they’ve implemented. Perhaps ask at discuss.ardupilot.org

Thanks for response. If I understood correctly, this is not Cube related “problem”. The communication is done only between the Entire and the QGC. Basically all initiation packets instead of CAMERA_SETTINGS seems to be the same. Do I have any other chance to discover (LOG options) why QGC is seeing proper CAMERA_SETTINGS packet, but does not accept its content?

edit:
QGC Code repos seems to be linked to standard c_library_v2 library which is using mavlink_msg_camera_settings.h different to here posted by dogmaphobic upper. Sorry for my basic confusion, which Mavlink lib is used by QGC for camera control?