|
33 | 33 | <param index="6">Empty</param> |
34 | 34 | <param index="7">Empty</param> |
35 | 35 | </entry> |
| 36 | + |
| 37 | + <entry name="MAV_CMD_DO_START_MAG_CAL" value="42424"> |
| 38 | + <description>Initiate a magnetometer calibration</description> |
| 39 | + <param index="1">uint8_t bitmask of magnetometers (0 means all)</param> |
| 40 | + <param index="2">Automatically retry on failure (0=no retry, 1=retry).</param> |
| 41 | + <param index="3">Save without user input (0=require input, 1=autosave).</param> |
| 42 | + <param index="4">Delay (seconds)</param> |
| 43 | + <param index="5">Empty</param> |
| 44 | + <param index="6">Empty</param> |
| 45 | + <param index="7">Empty</param> |
| 46 | + </entry> |
| 47 | + |
| 48 | + <entry name="MAV_CMD_DO_ACCEPT_MAG_CAL" value="42425"> |
| 49 | + <description>Initiate a magnetometer calibration</description> |
| 50 | + <param index="1">uint8_t bitmask of magnetometers (0 means all)</param> |
| 51 | + <param index="2">Empty</param> |
| 52 | + <param index="3">Empty</param> |
| 53 | + <param index="4">Empty</param> |
| 54 | + <param index="5">Empty</param> |
| 55 | + <param index="6">Empty</param> |
| 56 | + <param index="7">Empty</param> |
| 57 | + </entry> |
| 58 | + |
| 59 | + <entry name="MAV_CMD_DO_CANCEL_MAG_CAL" value="42426"> |
| 60 | + <description>Cancel a running magnetometer calibration</description> |
| 61 | + <param index="1">uint8_t bitmask of magnetometers (0 means all)</param> |
| 62 | + <param index="2">Empty</param> |
| 63 | + <param index="3">Empty</param> |
| 64 | + <param index="4">Empty</param> |
| 65 | + <param index="5">Empty</param> |
| 66 | + <param index="6">Empty</param> |
| 67 | + <param index="7">Empty</param> |
| 68 | + </entry> |
36 | 69 | </enum> |
37 | 70 |
|
38 | 71 | <!-- AP_Limits Enums --> |
|
114 | 147 | <entry name="CLOSEDLOOP" value="3"> <description>Closed loop feedback from camera, we know for sure it has successfully taken a picture</description></entry> |
115 | 148 | <entry name="OPENLOOP" value="4"> <description>Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture</description></entry> |
116 | 149 | </enum> |
| 150 | + |
| 151 | + <!-- Gimbal payload enumerations --> |
| 152 | + <enum name="MAV_MODE_GIMBAL"> |
| 153 | + <entry name="MAV_MODE_GIMBAL_UNINITIALIZED" value="0"> |
| 154 | + <description>Gimbal is powered on but has not received an initialize command from the host vehicle</description> |
| 155 | + </entry> |
| 156 | + <entry name="MAV_MODE_GIMBAL_HOMING" value="1"> |
| 157 | + <description>Gimbal is currently executing its homing routine</description> |
| 158 | + </entry> |
| 159 | + <entry name="MAV_MODE_GIMBAL_STABILIZED_RATE" value="2"> |
| 160 | + <description>Gimbal is actively stabilizing, taking rate commands</description> |
| 161 | + </entry> |
| 162 | + <entry name="MAV_MODE_GIMBAL_STABILIZED_ANGLE" value="3"> |
| 163 | + <description>Gimbal is actively stabilizing, taking angle target commands</description> |
| 164 | + </entry> |
| 165 | + <entry name="MAV_MODE_GIMBAL_FAULT" value="4"> |
| 166 | + <description>Gimbal has experienced a fault, and is currently in limp mode</description> |
| 167 | + </entry> |
| 168 | + </enum> |
| 169 | + |
| 170 | + <!-- GoPro command result enumeration --> |
| 171 | + <enum name="GOPRO_CMD_RESULT"> |
| 172 | + <entry name="GOPRO_CMD_RESULT_UNKNOWN" value="0"> |
| 173 | + <description>The result of the command is unknown</description> |
| 174 | + </entry> |
| 175 | + <entry name="GOPRO_CMD_RESULT_SUCCESSFUL" value="1"> |
| 176 | + <description>The command was successfully sent, and a response was successfully received</description> |
| 177 | + </entry> |
| 178 | + <entry name="GOPRO_CMD_RESULT_SEND_CMD_START_TIMEOUT" value="2"> |
| 179 | + <description>Timed out waiting for the GoPro to acknowledge our request to send a command</description> |
| 180 | + </entry> |
| 181 | + <entry name="GOPRO_CMD_RESULT_SEND_CMD_COMPLETE_TIMEOUT" value="3"> |
| 182 | + <description>Timed out waiting for the GoPro to read the command</description> |
| 183 | + </entry> |
| 184 | + <entry name="GOPRO_CMD_RESULT_GET_RESPONSE_START_TIMEOUT" value="4"> |
| 185 | + <description>Timed out waiting for the GoPro to begin transmitting a response to the command</description> |
| 186 | + </entry> |
| 187 | + <entry name="GOPRO_CMD_RESULT_GET_RESPONSE_COMPLETE_TIMEOUT" value="5"> |
| 188 | + <description>Timed out waiting for the GoPro to finish transmitting a response to the command</description> |
| 189 | + </entry> |
| 190 | + <entry name="GOPRO_CMD_RESULT_GET_CMD_COMPLETE_TIMEOUT" value="6"> |
| 191 | + <description>Timed out waiting for the GoPro to finish transmitting its own command</description> |
| 192 | + </entry> |
| 193 | + <entry name="GOPRO_CMD_RESULT_SEND_RESPONSE_START_TIMEOUT" value="7"> |
| 194 | + <description>Timed out waiting for the GoPro to start reading a response to its own command</description> |
| 195 | + </entry> |
| 196 | + <entry name="GOPRO_CMD_RESULT_SEND_RESPONSE_COMPLETE_TIMEOUT" value="8"> |
| 197 | + <description>Timed out waiting for the GoPro to finish reading a response to its own command</description> |
| 198 | + </entry> |
| 199 | + <entry name="GOPRO_CMD_RESULT_PREEMPTED" value="9"> |
| 200 | + <description>Command to the GoPro was preempted by the GoPro sending its own command</description> |
| 201 | + </entry> |
| 202 | + <entry name="GOPRO_CMD_RECEIVED_DATA_OVERFLOW" value="10"> |
| 203 | + <description>More data than expected received in response to the command</description> |
| 204 | + </entry> |
| 205 | + <entry name="GOPRO_CMD_RECEIVED_DATA_UNDERFLOW" value="11"> |
| 206 | + <description>Less data than expected received in response to the command</description> |
| 207 | + </entry> |
| 208 | + </enum> |
117 | 209 |
|
118 | 210 | <!-- led control pattern enums (enumeration of specific patterns) --> |
119 | 211 | <enum name="LED_CONTROL_PATTERN"> |
|
122 | 214 | <entry name="LED_CONTROL_PATTERN_CUSTOM" value="255"> <description>Custom Pattern using custom bytes fields</description></entry> |
123 | 215 | </enum> |
124 | 216 |
|
| 217 | + <enum name="MAG_CAL_STATUS"> |
| 218 | + <entry name="MAG_CAL_NOT_STARTED" value="0"></entry> |
| 219 | + <entry name="MAG_CAL_WAITING_TO_START" value="1"></entry> |
| 220 | + <entry name="MAG_CAL_RUNNING_STEP_ONE" value="2"></entry> |
| 221 | + <entry name="MAG_CAL_RUNNING_STEP_TWO" value="3"></entry> |
| 222 | + <entry name="MAG_CAL_SUCCESS" value="4"></entry> |
| 223 | + <entry name="MAG_CAL_FAILED" value="5"></entry> |
| 224 | + </enum> |
| 225 | + |
125 | 226 | </enums> |
126 | 227 |
|
127 | 228 | <messages> |
|
452 | 553 | <message name="CAMERA_FEEDBACK" id="180"> |
453 | 554 | <description>Camera Capture Feedback</description> |
454 | 555 | <field name="time_usec" type="uint64_t">Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB)</field> |
455 | | - <field name="target_system" type="uint8_t" >System ID</field> <!-- support multiple concurrent vehicles --> |
| 556 | + <field name="target_system" type="uint8_t" >System ID</field> <!-- support multiple concurrent vehicles --> |
456 | 557 | <field name="cam_idx" type="uint8_t" >Camera ID</field> <!-- component ID, to support multiple cameras --> |
457 | 558 | <field name="img_idx" type="uint16_t">Image index</field> <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping --> |
458 | 559 | <field name="lat" type="int32_t" >Latitude in (deg * 1E7)</field> |
|
493 | 594 | </message> |
494 | 595 |
|
495 | 596 | <message name="GIMBAL_REPORT" id="184"> |
496 | | - <description>Report from MAVLink enabled gimbal to vehicle. The deltas are in gimbal sensor frame. Joint measurements assume a 312 ordering (azimuth, roll, pitch).</description> |
| 597 | + <description>3 axis gimbal mesuraments</description> |
497 | 598 | <field type="uint8_t" name="target_system">System ID</field> |
498 | 599 | <field type="uint8_t" name="target_component">Component ID</field> |
499 | 600 | <field type="float" name="delta_time">Time since last update (seconds)</field> |
500 | | - <field type="float" name="delta_angle_x">Delta angle X, radians</field> |
501 | | - <field type="float" name="delta_angle_y">Delta angle Y, radians</field> |
502 | | - <field type="float" name="delta_angle_z">Delta angle Z, radians</field> |
503 | | - <field type="float" name="delta_velocity_x">Delta velocity X, m/s</field> |
504 | | - <field type="float" name="delta_velocity_y">Delta velocity Y, m/s</field> |
505 | | - <field type="float" name="delta_velocity_z">Delta velocity Z, m/s</field> |
506 | | - <field type="float" name="joint_roll">Joint roll, radians</field> |
507 | | - <field type="float" name="joint_pitch">Joint pitch, radians</field> |
508 | | - <field type="float" name="joint_yaw">Joint yaw, radians</field> |
| 601 | + <field type="float" name="delta_angle_x">Delta angle X (radians)</field> |
| 602 | + <field type="float" name="delta_angle_y">Delta angle Y (radians)</field> |
| 603 | + <field type="float" name="delta_angle_z">Delta angle X (radians)</field> |
| 604 | + <field type="float" name="delta_velocity_x">Delta velocity X (m/s)</field> |
| 605 | + <field type="float" name="delta_velocity_y">Delta velocity Y (m/s)</field> |
| 606 | + <field type="float" name="delta_velocity_z">Delta velocity Z (m/s)</field> |
| 607 | + <field type="float" name="joint_roll"> Joint ROLL (radians)</field> |
| 608 | + <field type="float" name="joint_el"> Joint EL (radians)</field> |
| 609 | + <field type="float" name="joint_az"> Joint AZ (radians)</field> |
509 | 610 | </message> |
510 | 611 |
|
511 | 612 | <message name="GIMBAL_CONTROL" id="185"> |
512 | | - <description>Control packet from vehicle to MAVLink enabled gimbal. All values in gimbal sensor frame</description> |
| 613 | + <description>Control message for rate gimbal</description> |
513 | 614 | <field type="uint8_t" name="target_system">System ID</field> |
514 | 615 | <field type="uint8_t" name="target_component">Component ID</field> |
515 | | - <field type="float" name="demanded_rate_x">Demanded angular rate X, radians/s</field> |
516 | | - <field type="float" name="demanded_rate_y">Demanded angular rate Y, radians/s</field> |
517 | | - <field type="float" name="demanded_rate_z">Demanded angular rate Z, radians/s</field> |
518 | | - <field type="float" name="gyro_bias_x">Gyro bias X, radians/s</field> |
519 | | - <field type="float" name="gyro_bias_y">Gyro bias Y, radians/s</field> |
520 | | - <field type="float" name="gyro_bias_z">Gyro bias Z, radians/s</field> |
| 616 | + <field type="float" name="demanded_rate_x">Demanded angular rate X (rad/s)</field> |
| 617 | + <field type="float" name="demanded_rate_y">Demanded angular rate Y (rad/s)</field> |
| 618 | + <field type="float" name="demanded_rate_z">Demanded angular rate Z (rad/s)</field> |
521 | 619 | </message> |
522 | 620 |
|
523 | 621 | <message name="LED_CONTROL" id="186"> |
|
529 | 627 | <field type="uint8_t" name="custom_len">Custom Byte Length</field> |
530 | 628 | <field type="uint8_t[24]" name="custom_bytes">Custom Bytes</field> |
531 | 629 | </message> |
| 630 | + |
| 631 | + <message name="GOPRO_POWER_ON" id="187"> |
| 632 | + <description>Instruct a HeroBus attached GoPro to power on</description> |
| 633 | + <field name="target_system" type="uint8_t">System ID</field> |
| 634 | + <field name="target_component" type="uint8_t">Component ID</field> |
| 635 | + </message> |
| 636 | + |
| 637 | + <message name="GOPRO_POWER_OFF" id="188"> |
| 638 | + <description>Instruct a HeroBus attached GoPro to power off</description> |
| 639 | + <field name="target_system" type="uint8_t">System ID</field> |
| 640 | + <field name="target_component" type="uint8_t">Component ID</field> |
| 641 | + </message> |
| 642 | + |
| 643 | + <message name="GOPRO_COMMAND" id="189"> |
| 644 | + <description>Send a command to a HeroBus attached GoPro. Will generate a GOPRO_RESPONSE message with results of the command</description> |
| 645 | + <field name="target_system" type="uint8_t">System ID</field> |
| 646 | + <field name="target_component" type="uint8_t">Component ID</field> |
| 647 | + <field name="gp_cmd_name_1" type="uint8_t">First character of the 2 character GoPro command</field> |
| 648 | + <field name="gp_cmd_name_2" type="uint8_t">Second character of the 2 character GoPro command</field> |
| 649 | + <field name="gp_cmd_parm" type="uint8_t">Parameter for the command</field> |
| 650 | + </message> |
| 651 | + |
| 652 | + <message name="GOPRO_RESPONSE" id="190"> |
| 653 | + <description> |
| 654 | + Response to a command sent to a HeroBus attached GoPro with a GOPRO_COMMAND message. Contains response from the camera as well as information about any errors encountered while attempting to communicate with the camera |
| 655 | + </description> |
| 656 | + <field name="gp_cmd_name_1" type="uint8_t">First character of the 2 character GoPro command that generated this response</field> |
| 657 | + <field name="gp_cmd_name_2" type="uint8_t">Second character of the 2 character GoPro command that generated this response</field> |
| 658 | + <field name="gp_cmd_response_status" type="uint8_t">Response byte from the GoPro's response to the command. 0 = Success, 1 = Failure</field> |
| 659 | + <field name="gp_cmd_response_argument" type="uint8_t">Response argument from the GoPro's response to the command</field> |
| 660 | + <field name="gp_cmd_result" type="uint16_t" enum="GOPRO_CMD_RESULT">Result of the command attempt to the GoPro, as defined by GOPRO_CMD_RESULT enum.</field> |
| 661 | + </message> |
| 662 | + |
| 663 | + <message name="MAG_CAL_PROGRESS" id="191"> |
| 664 | + <description>Reports progress of compass calibration.</description> |
| 665 | + <field type="uint8_t" name="compass_id">Compass being calibrated</field> |
| 666 | + <field type="uint8_t" name="cal_mask">Bitmask of compasses being calibrated</field> |
| 667 | + <field type="uint8_t" name="cal_status">Status (see MAG_CAL_STATUS enum)</field> |
| 668 | + <field type="uint8_t" name="attempt">Attempt number</field> |
| 669 | + <field type="uint8_t" name="completion_pct">Completion percentage</field> |
| 670 | + <field type="uint8_t[10]" name="completion_mask">Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid)</field> |
| 671 | + <field type="float" name="direction_x">Body frame direction vector for display</field> |
| 672 | + <field type="float" name="direction_y">Body frame direction vector for display</field> |
| 673 | + <field type="float" name="direction_z">Body frame direction vector for display</field> |
| 674 | + </message> |
| 675 | + |
| 676 | + <message name="MAG_CAL_REPORT" id="192"> |
| 677 | + <description>Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.</description> |
| 678 | + <field type="uint8_t" name="compass_id">Compass being calibrated</field> |
| 679 | + <field type="uint8_t" name="cal_mask">Bitmask of compasses being calibrated</field> |
| 680 | + <field type="uint8_t" name="cal_status">Status (see MAG_CAL_STATUS enum)</field> |
| 681 | + <field type="uint8_t" name="autosaved">0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters</field> |
| 682 | + <field type="float" name="fitness">RMS milligauss residuals</field> |
| 683 | + <field type="float" name="ofs_x">X offset</field> |
| 684 | + <field type="float" name="ofs_y">Y offset</field> |
| 685 | + <field type="float" name="ofs_z">Z offset</field> |
| 686 | + <field type="float" name="diag_x">X diagonal (matrix 11)</field> |
| 687 | + <field type="float" name="diag_y">Y diagonal (matrix 22)</field> |
| 688 | + <field type="float" name="diag_z">Z diagonal (matrix 33)</field> |
| 689 | + <field type="float" name="offdiag_x">X off-diagonal (matrix 12 and 21)</field> |
| 690 | + <field type="float" name="offdiag_y">Y off-diagonal (matrix 13 and 31)</field> |
| 691 | + <field type="float" name="offdiag_z">Z off-diagonal (matrix 32 and 23)</field> |
| 692 | + </message> |
532 | 693 |
|
533 | 694 | </messages> |
534 | 695 | </mavlink> |
0 commit comments