Subversion Repositories Projects

Rev

Blame | Last modification | View Log | RSS feed

<?xml version='1.0'?>
<mavlink>
     <include>common.xml</include>
     <!-- note that APM specific messages should use the command id
      range from 150 to 250, to leave plenty of room for growth
      of common.xml

      If you prototype a message here, then you should consider if it
      is general enough to move into common.xml later
    -->


        <enums>
          <!-- Camera Mount mode Enumeration -->
          <enum name="MAV_MOUNT_MODE">
            <description>Enumeration of possible mount operation modes</description>
            <entry name="MAV_MOUNT_MODE_RETRACT" value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry>
            <entry name="MAV_MOUNT_MODE_NEUTRAL" value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry>
            <entry name="MAV_MOUNT_MODE_MAVLINK_TARGETING" value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry>
            <entry name="MAV_MOUNT_MODE_RC_TARGETING" value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry>
            <entry name="MAV_MOUNT_MODE_GPS_POINT" value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry>
          </enum>

          <enum name="MAV_CMD" >
            <!-- Camera Controller Mission Commands Enumeration -->
            <entry name="MAV_CMD_DO_DIGICAM_CONFIGURE" value="202">
              <description>Mission command to configure an on-board camera controller system.</description>
              <param index="1">Modes: P, TV, AV, M, Etc</param>
              <param index="2">Shutter speed: Divisor number for one second</param>
              <param index="3">Aperture: F stop number</param>
              <param index="4">ISO number e.g. 80, 100, 200, Etc</param>
              <param index="5">Exposure type enumerator</param>
              <param index="6">Command Identity</param>
              <param index="7">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</param>
            </entry>

            <entry name="MAV_CMD_DO_DIGICAM_CONTROL" value="203">
              <description>Mission command to control an on-board camera controller system.</description>
              <param index="1">Session control e.g. show/hide lens</param>
              <param index="2">Zoom's absolute position</param>
              <param index="3">Zooming step value to offset zoom from the current position</param>
              <param index="4">Focus Locking, Unlocking or Re-locking</param>
              <param index="5">Shooting Command</param>
              <param index="6">Command Identity</param>
              <param index="7">Empty</param>
            </entry>

            <!-- Camera Mount Mission Commands Enumeration -->
            <entry name="MAV_CMD_DO_MOUNT_CONFIGURE" value="204">
              <description>Mission command to configure a camera or antenna mount</description>
              <param index="1">Mount operation mode (see MAV_MOUNT_MODE enum)</param>
              <param index="2">stabilize roll? (1 = yes, 0 = no)</param>
              <param index="3">stabilize pitch? (1 = yes, 0 = no)</param>
              <param index="4">stabilize yaw? (1 = yes, 0 = no)</param>
              <param index="5">Empty</param>
              <param index="6">Empty</param>
              <param index="7">Empty</param>
            </entry>

            <entry name="MAV_CMD_DO_MOUNT_CONTROL" value="205">
              <description>Mission command to control a camera or antenna mount</description>
              <param index="1">pitch(deg*100) or lat, depending on mount mode.</param>
              <param index="2">roll(deg*100) or lon depending on mount mode</param>
              <param index="3">yaw(deg*100) or alt (in cm) depending on mount mode</param>
              <param index="4">Empty</param>
              <param index="5">Empty</param>
              <param index="6">Empty</param>
              <param index="7">Empty</param>
            </entry>
          </enum>

          <!-- fenced mode enums -->
          <enum name="FENCE_ACTION">
            <entry name="FENCE_ACTION_NONE" value="0">
              <description>Disable fenced mode</description>
            </entry>
            <entry name="FENCE_ACTION_GUIDED" value="1">
              <description>Switched to guided mode to return point (fence point 0)</description>
            </entry>
          </enum>

          <enum name="FENCE_BREACH">
            <entry name="FENCE_BREACH_NONE" value="0">
              <description>No last fence breach</description>
            </entry>
            <entry name="FENCE_BREACH_MINALT" value="1">
              <description>Breached minimum altitude</description>
            </entry>
            <entry name="FENCE_BREACH_MAXALT" value="2">
              <description>Breached minimum altitude</description>
            </entry>
            <entry name="FENCE_BREACH_BOUNDARY" value="3">
              <description>Breached fence boundary</description>
            </entry>
          </enum>
        </enums>

     <messages>
          <message id="150" name="SENSOR_OFFSETS">
               <description>Offsets and calibrations values for hardware
        sensors. This makes it easier to debug the calibration process.</description>
               <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
               <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
               <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
               <field type="float" name="mag_declination">magnetic declination (radians)</field>
               <field type="int32_t" name="raw_press">raw pressure from barometer</field>
               <field type="int32_t" name="raw_temp">raw temperature from barometer</field>
               <field type="float" name="gyro_cal_x">gyro X calibration</field>
               <field type="float" name="gyro_cal_y">gyro Y calibration</field>
               <field type="float" name="gyro_cal_z">gyro Z calibration</field>
               <field type="float" name="accel_cal_x">accel X calibration</field>
               <field type="float" name="accel_cal_y">accel Y calibration</field>
               <field type="float" name="accel_cal_z">accel Z calibration</field>
          </message>

          <message id="151" name="SET_MAG_OFFSETS">
               <description>set the magnetometer offsets</description>
               <field type="uint8_t" name="target_system">System ID</field>
               <field type="uint8_t" name="target_component">Component ID</field>
               <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
               <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
               <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
          </message>

          <message id="152" name="MEMINFO">
               <description>state of APM memory</description>
               <field type="uint16_t" name="brkval">heap top</field>
               <field type="uint16_t" name="freemem">free memory</field>
          </message>

          <message id="153" name="AP_ADC">
               <description>raw ADC output</description>
               <field type="uint16_t" name="adc1">ADC output 1</field>
               <field type="uint16_t" name="adc2">ADC output 2</field>
               <field type="uint16_t" name="adc3">ADC output 3</field>
               <field type="uint16_t" name="adc4">ADC output 4</field>
               <field type="uint16_t" name="adc5">ADC output 5</field>
               <field type="uint16_t" name="adc6">ADC output 6</field>
          </message>

          <!-- Camera Controller Messages -->
          <message name="DIGICAM_CONFIGURE" id="154">
            <description>Configure on-board Camera Control System.</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field>
            <field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field>
            <field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field>
            <field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
            <field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
            <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
            <field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
            <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
            <field name="extra_value" type="float">Correspondent value to given extra_param</field>
          </message>

          <message name="DIGICAM_CONTROL" id="155">
            <description>Control on-board Camera Control System to take shots.</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field>
            <field name="zoom_pos" type="uint8_t">1 to N //Zoom'
s absolute position (0 means ignore)</field>
            <field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field>
            <field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
            <field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
            <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
            <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
            <field name="extra_value" type="float">Correspondent value to given extra_param</field>
          </message>

          <!-- Camera Mount Messages -->
          <message name="MOUNT_CONFIGURE" id="156">
            <description>Message to configure a camera mount, directional antenna, etc.</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field>
            <field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field>
            <field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field>
            <field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field>
          </message>

          <message name="MOUNT_CONTROL" id="157">
            <description>Message to control a camera mount, directional antenna, etc.</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
            <field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
            <field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
            <field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field>
          </message>

          <message name="MOUNT_STATUS" id="158">
            <description>Message with some status from APM to GCS about camera or antenna mount</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
            <field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
            <field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
          </message>

          <!-- geo-fence messages -->
          <message name="FENCE_POINT" id="160">
            <description>A fence point. Used to set a point when from
              GCS -> MAV. Also used to return a point from MAV -> GCS</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
            <field name="count" type="uint8_t">total number of points (for sanity checking)</field>
            <field name="lat" type="float">Latitude of point</field>
            <field name="lng" type="float">Longitude of point</field>
          </message>

          <message name="FENCE_FETCH_POINT" id="161">
            <description>Request a current fence point from MAV</description>
            <field name="target_system" type="uint8_t">System ID</field>
            <field name="target_component" type="uint8_t">Component ID</field>
            <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
          </message>

          <message name="FENCE_STATUS" id="162">
            <description>Status of geo-fencing. Sent in extended
            status stream when fencing enabled</description>
            <field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field>
            <field name="breach_count" type="uint16_t">number of fence breaches</field>
            <field name="breach_type" type="uint8_t">last breach type (see FENCE_BREACH_* enum)</field>
            <field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field>
          </message>

          <message name="AHRS" id="163">
            <description>Status of DCM attitude estimator</description>
            <field type="float" name="omegaIx">X gyro drift estimate rad/s</field>
            <field type="float" name="omegaIy">Y gyro drift estimate rad/s</field>
            <field type="float" name="omegaIz">Z gyro drift estimate rad/s</field>
            <field type="float" name="accel_weight">average accel_weight</field>
            <field type="float" name="renorm_val">average renormalisation value</field>
            <field type="float" name="error_rp">average error_roll_pitch value</field>
            <field type="float" name="error_yaw">average error_yaw value</field>
          </message>

          <message name="SIMSTATE" id="164">
            <description>Status of simulation environment, if used</description>
            <field type="float" name="roll">Roll angle (rad)</field>
            <field type="float" name="pitch">Pitch angle (rad)</field>
            <field type="float" name="yaw">Yaw angle (rad)</field>
            <field type="float" name="xacc">X acceleration m/s/s</field>
            <field type="float" name="yacc">Y acceleration m/s/s</field>
            <field type="float" name="zacc">Z acceleration m/s/s</field>
            <field type="float" name="xgyro">Angular speed around X axis rad/s</field>
            <field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
            <field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
          </message>

          <message name="HWSTATUS" id="165">
            <description>Status of key hardware</description>
            <field type="uint16_t" name="Vcc">board voltage (mV)</field>
            <field type="uint8_t"  name="I2Cerr">I2C error count</field>
          </message>

          <message name="RADIO" id="166">
            <description>Status generated by radio</description>
            <field type="uint8_t" name="rssi">local signal strength</field>
            <field type="uint8_t" name="remrssi">remote signal strength</field>
            <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
            <field type="uint8_t" name="noise">background noise level</field>
            <field type="uint8_t" name="remnoise">remote background noise level</field>
            <field type="uint16_t" name="rxerrors">receive errors</field>
            <field type="uint16_t" name="fixed">count of error corrected packets</field>
          </message>
     </messages>
</mavlink>