diff --git a/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml b/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml new file mode 100644 index 0000000000000000000000000000000000000000..012385fd4d8f1ef16e2783f194fa34c30a5a57b5 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml @@ -0,0 +1,81 @@ +<?xml version='1.0'?> +<!-- ASLUAV Mavlink Message Definition File --> +<!-- Used for the ASLUAV fixed-wing autopilot (www.asl.ethz.ch), which implements extensions to the Pixhawk (www.pixhawk.org) autopilot --> +<mavlink> + <include>common.xml</include> + <messages> + <message id="201" name="SENS_POWER"> + <description>Voltage and current sensor data</description> + <field type="float" name="adc121_vspb_volt"> Power board voltage sensor reading in volts</field> + <field type="float" name="adc121_cspb_amp"> Power board current sensor reading in amps</field> + <field type="float" name="adc121_cs1_amp"> Board current sensor 1 reading in amps</field> + <field type="float" name="adc121_cs2_amp"> Board current sensor 2 reading in amps</field> + </message> + <message id="202" name="SENS_MPPT"> + <description>Maximum Power Point Tracker (MPPT) sensor data for solar module power performance tracking</description> + <field type="uint64_t" name="mppt_timestamp"> MPPT last timestamp </field> + <field type="float" name="mppt1_volt"> MPPT1 voltage </field> + <field type="float" name="mppt1_amp"> MPPT1 current </field> + <field type="uint16_t" name="mppt1_pwm"> MPPT1 pwm </field> + <field type="uint8_t" name="mppt1_status"> MPPT1 status </field> + <field type="float" name="mppt2_volt"> MPPT2 voltage </field> + <field type="float" name="mppt2_amp"> MPPT2 current </field> + <field type="uint16_t" name="mppt2_pwm"> MPPT2 pwm </field> + <field type="uint8_t" name="mppt2_status"> MPPT2 status </field> + <field type="float" name="mppt3_volt"> MPPT3 voltage </field> + <field type="float" name="mppt3_amp"> MPPT3 current </field> + <field type="uint16_t" name="mppt3_pwm"> MPPT3 pwm </field> + <field type="uint8_t" name="mppt3_status"> MPPT3 status </field> + </message> + <message id="203" name="ASLCTRL_DATA"> + <description>ASL-fixed-wing controller data</description> + <field type="uint64_t" name="timestamp"> Timestamp</field> + <field type="uint8_t" name="aslctrl_mode"> ASLCTRL control-mode (manual, stabilized, auto, etc...)</field> + <field type="float" name="h"> See sourcecode for a description of these values... </field> + <field type="float" name="hRef"> </field> + <field type="float" name="hRef_t"> </field> + <field type="float" name="PitchAngle">Pitch angle [deg]</field> + <field type="float" name="PitchAngleRef">Pitch angle reference[deg] </field> + <field type="float" name="q"> </field> + <field type="float" name="qRef"> </field> + <field type="float" name="uElev"> </field> + <field type="float" name="uThrot"> </field> + <field type="float" name="uThrot2"> </field> + <field type="float" name="aZ"> </field> + <field type="float" name="AirspeedRef">Airspeed reference [m/s]</field> + <field type="uint8_t" name="SpoilersEngaged"> </field> + <field type="float" name="YawAngle">Yaw angle [deg]</field> + <field type="float" name="YawAngleRef">Yaw angle reference[deg]</field> + <field type="float" name="RollAngle">Roll angle [deg]</field> + <field type="float" name="RollAngleRef">Roll angle reference[deg]</field> + <field type="float" name="p"> </field> + <field type="float" name="pRef"> </field> + <field type="float" name="r"> </field> + <field type="float" name="rRef"> </field> + <field type="float" name="uAil"> </field> + <field type="float" name="uRud"> </field> + </message> + <message id="204" name="ASLCTRL_DEBUG"> + <description>ASL-fixed-wing controller debug data</description> + <field type="uint32_t" name="i32_1"> Debug data</field> + <field type="uint8_t" name="i8_1"> Debug data</field> + <field type="uint8_t" name="i8_2"> Debug data</field> + <field type="float" name="f_1"> Debug data </field> + <field type="float" name="f_2"> Debug data</field> + <field type="float" name="f_3"> Debug data</field> + <field type="float" name="f_4"> Debug data</field> + <field type="float" name="f_5"> Debug data</field> + <field type="float" name="f_6"> Debug data</field> + <field type="float" name="f_7"> Debug data</field> + <field type="float" name="f_8"> Debug data</field> + </message> + <message id="205" name="ASLUAV_STATUS"> + <description>Extended state information for ASLUAVs</description> + <field type="uint8_t" name="LED_status"> Status of the position-indicator LEDs</field> + <field type="uint8_t" name="SATCOM_status"> Status of the IRIDIUM satellite communication system</field> + <field type="uint8_t[8]" name="Servo_status"> Status vector for up to 8 servos</field> + <field type="float" name="Motor_rpm"> Motor RPM </field> + <!-- to be extended--> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 9e217fd12a2f92a943b78c9252f0f47c08daf614..d933eeb7ff2b6616a84fc071b9f1e8ec73f1f3e7 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -55,6 +55,9 @@ <entry value="16" name="MAV_AUTOPILOT_AEROB"> <description>Aerob -- http://aerob.ru</description> </entry> + <entry value="17" name="MAV_AUTOPILOT_ASLUAV"> + <description>ASLUAV autopilot -- http://www.asl.ethz.ch</description> + </entry> </enum> <enum name="MAV_TYPE"> <entry value="0" name="MAV_TYPE_GENERIC"> @@ -1473,7 +1476,7 @@ <!-- FIXME to be removed / merged with SYSTEM_TIME --> <message id="4" name="PING"> <description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description> - <field type="uint64_t" name="time_usec">Unix timestamp in microseconds</field> + <field type="uint64_t" name="time_usec">Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)</field> <field type="uint32_t" name="seq">PING sequence</field> <field type="uint8_t" name="target_system">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field> <field type="uint8_t" name="target_component">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field> @@ -2181,14 +2184,20 @@ <field type="float" name="temperature">Temperature in degrees celsius</field> <field type="uint16_t" name="fields_updated">Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature</field> </message> - <message id="106" name="OMNIDIRECTIONAL_FLOW"> - <description>Optical flow from an omnidirectional flow sensor (e.g. PX4FLOW with wide angle lens)</description> + <message id="106" name="OPTICAL_FLOW_RAD"> + <description>Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)</description> <field type="uint64_t" name="time_usec">Timestamp (microseconds, synced to UNIX time or since system boot)</field> <field type="uint8_t" name="sensor_id">Sensor ID</field> - <field type="int16_t[10]" name="left">Flow in deci pixels (1 = 0.1 pixel) on left hemisphere</field> - <field type="int16_t[10]" name="right">Flow in deci pixels (1 = 0.1 pixel) on right hemisphere</field> - <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field> - <field type="float" name="front_distance_m">Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance</field> + <field type="uint32_t" name="integration_time_us">Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.</field> + <field type="float" name="integrated_x">Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)</field> + <field type="float" name="integrated_y">Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)</field> + <field type="float" name="integrated_xgyro">RH rotation around X axis (rad)</field> + <field type="float" name="integrated_ygyro">RH rotation around Y axis (rad)</field> + <field type="float" name="integrated_zgyro">RH rotation around Z axis (rad)</field> + <field type="int16_t" name="temperature">Temperature * 100 in centi-degrees Celsius</field> + <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: no valid flow, 255: maximum quality</field> + <field type="uint32_t" name="time_delta_distance_us">Time in microseconds since the distance was sampled.</field> + <field type="float" name="distance">Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.</field> </message> <message id="107" name="HIL_SENSOR"> <description>The IMU readings in SI units in NED body frame</description> @@ -2251,6 +2260,11 @@ <field type="uint8_t" name="target_system">System ID (0 for broadcast)</field> <field type="uint8_t" name="target_component">Component ID (0 for broadcast)</field> <field type="uint8_t[251]" name="payload">Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.</field> + </message> + <message id="111" name="TIMESYNC"> + <description>Time synchronization message.</description> + <field type="int64_t" name="tc1">Time sync timestamp 1</field> + <field type="int64_t" name="ts1">Time sync timestamp 2</field> </message> <message id="113" name="HIL_GPS"> <description>The global position, as returned by the Global Positioning System (GPS). This is @@ -2270,15 +2284,19 @@ <field type="uint8_t" name="satellites_visible">Number of satellites visible. If unknown, set to 255</field> </message> <message id="114" name="HIL_OPTICAL_FLOW"> - <description>Simulated optical flow from a flow sensor (e.g. optical mouse sensor)</description> - <field type="uint64_t" name="time_usec">Timestamp (UNIX)</field> + <description>Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)</description> + <field type="uint64_t" name="time_usec">Timestamp (microseconds, synced to UNIX time or since system boot)</field> <field type="uint8_t" name="sensor_id">Sensor ID</field> - <field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field> - <field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field> - <field type="float" name="flow_comp_m_x">Flow in meters in x-sensor direction, angular-speed compensated</field> - <field type="float" name="flow_comp_m_y">Flow in meters in y-sensor direction, angular-speed compensated</field> - <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field> - <field type="float" name="ground_distance">Ground distance in meters. Positive value: distance known. Negative value: Unknown distance</field> + <field type="uint32_t" name="integration_time_us">Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.</field> + <field type="float" name="integrated_x">Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)</field> + <field type="float" name="integrated_y">Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)</field> + <field type="float" name="integrated_xgyro">RH rotation around X axis (rad)</field> + <field type="float" name="integrated_ygyro">RH rotation around Y axis (rad)</field> + <field type="float" name="integrated_zgyro">RH rotation around Z axis (rad)</field> + <field type="int16_t" name="temperature">Temperature * 100 in centi-degrees Celsius</field> + <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: no valid flow, 255: maximum quality</field> + <field type="uint32_t" name="time_delta_distance_us">Time in microseconds since the distance was sampled.</field> + <field type="float" name="distance">Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.</field> </message> <message id="115" name="HIL_STATE_QUATERNION"> <description>Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.</description>