Commit 4ac0d183 authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/cc1833429fae240d234464668602a5656a0dcb2e
parent d5538ea0
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -10018,6 +10018,126 @@ static void mavlink_test_gimbal_manager_set_tiltpan(uint8_t system_id, uint8_t c ...@@ -10018,6 +10018,126 @@ static void mavlink_test_gimbal_manager_set_tiltpan(uint8_t system_id, uint8_t c
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_esc_info(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_INFO >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_esc_info_t packet_in = {
93372036854775807ULL,{ 963497880, 963497881, 963497882, 963497883 },18483,{ 18587, 18588, 18589, 18590 },235,46,113,180,{ 247, 248, 249, 250 }
};
mavlink_esc_info_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.counter = packet_in.counter;
packet1.index = packet_in.index;
packet1.count = packet_in.count;
packet1.connection_type = packet_in.connection_type;
packet1.info = packet_in.info;
mav_array_memcpy(packet1.error_count, packet_in.error_count, sizeof(uint32_t)*4);
mav_array_memcpy(packet1.failure_flags, packet_in.failure_flags, sizeof(uint16_t)*4);
mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_ESC_INFO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_INFO_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_info_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_esc_info_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_info_pack(system_id, component_id, &msg , packet1.index , packet1.time_usec , packet1.counter , packet1.count , packet1.connection_type , packet1.info , packet1.failure_flags , packet1.error_count , packet1.temperature );
mavlink_msg_esc_info_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.index , packet1.time_usec , packet1.counter , packet1.count , packet1.connection_type , packet1.info , packet1.failure_flags , packet1.error_count , packet1.temperature );
mavlink_msg_esc_info_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_esc_info_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_info_send(MAVLINK_COMM_1 , packet1.index , packet1.time_usec , packet1.counter , packet1.count , packet1.connection_type , packet1.info , packet1.failure_flags , packet1.error_count , packet1.temperature );
mavlink_msg_esc_info_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_esc_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_STATUS >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_esc_status_t packet_in = {
93372036854775807ULL,{ 963497880, 963497881, 963497882, 963497883 },{ 185.0, 186.0, 187.0, 188.0 },{ 297.0, 298.0, 299.0, 300.0 },173
};
mavlink_esc_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.index = packet_in.index;
mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(int32_t)*4);
mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(float)*4);
mav_array_memcpy(packet1.current, packet_in.current, sizeof(float)*4);
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_esc_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_status_pack(system_id, component_id, &msg , packet1.index , packet1.time_usec , packet1.rpm , packet1.voltage , packet1.current );
mavlink_msg_esc_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.index , packet1.time_usec , packet1.rpm , packet1.voltage , packet1.current );
mavlink_msg_esc_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_esc_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_esc_status_send(MAVLINK_COMM_1 , packet1.index , packet1.time_usec , packet1.rpm , packet1.voltage , packet1.current );
mavlink_msg_esc_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_wifi_config_ap(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_wifi_config_ap(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
...@@ -12548,6 +12668,8 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink ...@@ -12548,6 +12668,8 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_gimbal_device_attitude_status(system_id, component_id, last_msg); mavlink_test_gimbal_device_attitude_status(system_id, component_id, last_msg);
mavlink_test_autopilot_state_for_gimbal_device(system_id, component_id, last_msg); mavlink_test_autopilot_state_for_gimbal_device(system_id, component_id, last_msg);
mavlink_test_gimbal_manager_set_tiltpan(system_id, component_id, last_msg); mavlink_test_gimbal_manager_set_tiltpan(system_id, component_id, last_msg);
mavlink_test_esc_info(system_id, component_id, last_msg);
mavlink_test_esc_status(system_id, component_id, last_msg);
mavlink_test_wifi_config_ap(system_id, component_id, last_msg); mavlink_test_wifi_config_ap(system_id, component_id, last_msg);
mavlink_test_protocol_version(system_id, component_id, last_msg); mavlink_test_protocol_version(system_id, component_id, last_msg);
mavlink_test_ais_vessel(system_id, component_id, last_msg); mavlink_test_ais_vessel(system_id, component_id, last_msg);
......
This diff is collapsed.
...@@ -1226,6 +1226,56 @@ ...@@ -1226,6 +1226,56 @@
<description>The node is no longer available online.</description> <description>The node is no longer available online.</description>
</entry> </entry>
</enum> </enum>
<enum name="ESC_CONNECTION_TYPE">
<!-- This enum is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Indicates the ESC connection type.</description>
<entry value="0" name="ESC_CONNECTION_TYPE_PPM">
<description>Traditional PPM ESC.</description>
</entry>
<entry value="1" name="ESC_CONNECTION_TYPE_SERIAL">
<description>Serial Bus connected ESC.</description>
</entry>
<entry value="2" name="ESC_CONNECTION_TYPE_ONESHOT">
<description>One Shot PPM ESC.</description>
</entry>
<entry value="3" name="ESC_CONNECTION_TYPE_I2C">
<description>I2C ESC.</description>
</entry>
<entry value="4" name="ESC_CONNECTION_TYPE_CAN">
<description>CAN-Bus ESC.</description>
</entry>
<entry value="5" name="ESC_CONNECTION_TYPE_DSHOT">
<description>DShot ESC.</description>
</entry>
</enum>
<enum name="ESC_FAILURE_FLAGS" bitmask="true">
<!-- This enum is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Flags to report ESC failures.</description>
<entry value="0" name="ESC_FAILURE_NONE">
<description>No ESC failure.</description>
</entry>
<entry value="1" name="ESC_FAILURE_OVER_CURRENT">
<description>Over current failure.</description>
</entry>
<entry value="2" name="ESC_FAILURE_OVER_VOLTAGE">
<description>Over voltage failure.</description>
</entry>
<entry value="4" name="ESC_FAILURE_OVER_TEMPERATURE">
<description>Over temperature failure.</description>
</entry>
<entry value="8" name="ESC_FAILURE_OVER_RPM">
<description>Over RPM failure.</description>
</entry>
<entry value="16" name="ESC_FAILURE_INCONSISTENT_CMD">
<description>Inconsistent command failure i.e. out of bounds.</description>
</entry>
<entry value="32" name="ESC_FAILURE_MOTOR_STUCK">
<description>Motor stuck failure.</description>
</entry>
<entry value="64" name="ESC_FAILURE_GENERIC">
<description>Generic ESC failure.</description>
</entry>
</enum>
<enum name="STORAGE_STATUS"> <enum name="STORAGE_STATUS">
<description>Flags to indicate the status of camera storage.</description> <description>Flags to indicate the status of camera storage.</description>
<entry value="0" name="STORAGE_STATUS_EMPTY"> <entry value="0" name="STORAGE_STATUS_EMPTY">
...@@ -6521,6 +6571,30 @@ ...@@ -6521,6 +6571,30 @@
<field type="float" name="tilt_rate" units="rad/s">Tilt/pitch angular rate (positive: up, negative: down, NaN to be ignored).</field> <field type="float" name="tilt_rate" units="rad/s">Tilt/pitch angular rate (positive: up, negative: down, NaN to be ignored).</field>
<field type="float" name="pan_rate" units="rad/s">Pan/yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).</field> <field type="float" name="pan_rate" units="rad/s">Pan/yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).</field>
</message> </message>
<message id="290" name="ESC_INFO">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data.</description>
<field type="uint8_t" name="index">Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.</field>
<field type="uint64_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.</field>
<field type="uint16_t" name="counter">Counter of data packets received.</field>
<field type="uint8_t" name="count">Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.</field>
<field type="uint8_t" name="connection_type" enum="ESC_CONNECTION_TYPE">Connection type protocol for all ESC.</field>
<field type="uint8_t" name="info" display="bitmask">Information regarding online/offline status of each ESC.</field>
<field type="uint16_t[4]" name="failure_flags" enum="ESC_FAILURE_FLAGS" display="bitmask">Bitmap of ESC failure flags.</field>
<field type="uint32_t[4]" name="error_count">Number of reported errors by each ESC since boot.</field>
<field type="uint8_t[4]" name="temperature" units="degC">Temperature measured by each ESC. UINT8_MAX if data not supplied by ESC.</field>
</message>
<message id="291" name="ESC_STATUS">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer).</description>
<field type="uint8_t" name="index">Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.</field>
<field type="uint64_t" name="time_usec" units="us">Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.</field>
<field type="int32_t[4]" name="rpm" units="rpm">Reported motor RPM from each ESC (negative for reverse rotation).</field>
<field type="float[4]" name="voltage" units="V">Voltage measured from each ESC.</field>
<field type="float[4]" name="current" units="A">Current measured from each ESC.</field>
</message>
<message id="299" name="WIFI_CONFIG_AP"> <message id="299" name="WIFI_CONFIG_AP">
<description>Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE</description> <description>Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE</description>
<field type="char[32]" name="ssid">Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.</field> <field type="char[32]" name="ssid">Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.</field>
......
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0%
or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment