camera_definition_example.xml 15.1 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301
<?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>