Commit ec04636d authored by PX4BuildBot's avatar PX4BuildBot

autogenerated headers for rev...

autogenerated headers for rev https://github.com/mavlink/mavlink/tree/4957656d4683bf042b5b364ed97a5d172a08b960
parent 92c6c58e
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
...@@ -11231,6 +11231,68 @@ static void mavlink_test_smart_battery_status(uint8_t system_id, uint8_t compone ...@@ -11231,6 +11231,68 @@ static void mavlink_test_smart_battery_status(uint8_t system_id, uint8_t compone
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_generator_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_GENERATOR_STATUS >= 256) {
return;
}
#endif
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_generator_status_t packet_in = {
93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,18691,18795,18899
};
mavlink_generator_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.status = packet_in.status;
packet1.battery_current = packet_in.battery_current;
packet1.load_current = packet_in.load_current;
packet1.power_generated = packet_in.power_generated;
packet1.bus_voltage = packet_in.bus_voltage;
packet1.bat_current_setpoint = packet_in.bat_current_setpoint;
packet1.generator_speed = packet_in.generator_speed;
packet1.rectifier_temperature = packet_in.rectifier_temperature;
packet1.generator_temperature = packet_in.generator_temperature;
#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
// cope with extensions
memset(MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN);
}
#endif
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_generator_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_generator_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_generator_status_pack(system_id, component_id, &msg , packet1.status , packet1.generator_speed , packet1.battery_current , packet1.load_current , packet1.power_generated , packet1.bus_voltage , packet1.rectifier_temperature , packet1.bat_current_setpoint , packet1.generator_temperature );
mavlink_msg_generator_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_generator_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status , packet1.generator_speed , packet1.battery_current , packet1.load_current , packet1.power_generated , packet1.bus_voltage , packet1.rectifier_temperature , packet1.bat_current_setpoint , packet1.generator_temperature );
mavlink_msg_generator_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_generator_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_generator_status_send(MAVLINK_COMM_1 , packet1.status , packet1.generator_speed , packet1.battery_current , packet1.load_current , packet1.power_generated , packet1.bus_voltage , packet1.rectifier_temperature , packet1.bat_current_setpoint , packet1.generator_temperature );
mavlink_msg_generator_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_actuator_output_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_actuator_output_status(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
...@@ -12302,6 +12364,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink ...@@ -12302,6 +12364,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_orbit_execution_status(system_id, component_id, last_msg); mavlink_test_orbit_execution_status(system_id, component_id, last_msg);
mavlink_test_smart_battery_info(system_id, component_id, last_msg); mavlink_test_smart_battery_info(system_id, component_id, last_msg);
mavlink_test_smart_battery_status(system_id, component_id, last_msg); mavlink_test_smart_battery_status(system_id, component_id, last_msg);
mavlink_test_generator_status(system_id, component_id, last_msg);
mavlink_test_actuator_output_status(system_id, component_id, last_msg); mavlink_test_actuator_output_status(system_id, component_id, last_msg);
mavlink_test_time_estimate_to_target(system_id, component_id, last_msg); mavlink_test_time_estimate_to_target(system_id, component_id, last_msg);
mavlink_test_tunnel(system_id, component_id, last_msg); mavlink_test_tunnel(system_id, component_id, last_msg);
......
This diff is collapsed.
...@@ -3312,6 +3312,63 @@ ...@@ -3312,6 +3312,63 @@
<description>Under-temperature fault.</description> <description>Under-temperature fault.</description>
</entry> </entry>
</enum> </enum>
<enum name="GENERATOR_STATUS_FLAG" bitmask="true">
<description>Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly).</description>
<entry value="1" name="GENERATOR_STATUS_FLAG_OFF">
<description>Generator is off.</description>
</entry>
<entry value="2" name="GENERATOR_STATUS_FLAG_READY">
<description>Generator is ready to start generating power.</description>
</entry>
<entry value="4" name="GENERATOR_STATUS_FLAG_GENERATING">
<description>Generator is generating power.</description>
</entry>
<entry value="8" name="GENERATOR_STATUS_FLAG_CHARGING">
<description>Generator is charging the batteries (generating enough power to charge and provide the load).</description>
</entry>
<entry value="16" name="GENERATOR_STATUS_FLAG_REDUCED_POWER">
<description>Generator is operating at a reduced maximum power.</description>
</entry>
<entry value="32" name="GENERATOR_STATUS_FLAG_MAXPOWER">
<description>Generator is providing the maximum output.</description>
</entry>
<entry value="64" name="GENERATOR_STATUS_FLAG_OVERTEMP_WARNING">
<description>Generator is near the maximum operating temperature, cooling is insufficient.</description>
</entry>
<entry value="128" name="GENERATOR_STATUS_FLAG_OVERTEMP_FAULT">
<description>Generator hit the maximum operating temperature and shutdown.</description>
</entry>
<entry value="256" name="GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING">
<description>Power electronics are near the maximum operating temperature, cooling is insufficient.</description>
</entry>
<entry value="512" name="GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT">
<description>Power electronics hit the maximum operating temperature and shutdown.</description>
</entry>
<entry value="1024" name="GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT">
<description>Power electronics experienced a fault and shutdown.</description>
</entry>
<entry value="2048" name="GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT">
<description>The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening.</description>
</entry>
<entry value="4096" name="GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING">
<description>Generator controller having communication problems.</description>
</entry>
<entry value="8192" name="GENERATOR_STATUS_FLAG_COOLING_WARNING">
<description>Power electronic or generator cooling system error.</description>
</entry>
<entry value="16384" name="GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT">
<description>Generator controller power rail experienced a fault.</description>
</entry>
<entry value="32768" name="GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT">
<description>Generator controller exceeded the overcurrent threshold and shutdown to prevent damage.</description>
</entry>
<entry value="65536" name="GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT">
<description>Generator controller detected a high current going into the batteries and shutdown to prevent battery damage.</description>
</entry>
<entry value="131072" name="GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT">
<description>Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating.</description>
</entry>
</enum>
<enum name="MAV_VTOL_STATE"> <enum name="MAV_VTOL_STATE">
<description>Enumeration of VTOL states</description> <description>Enumeration of VTOL states</description>
<entry value="0" name="MAV_VTOL_STATE_UNDEFINED"> <entry value="0" name="MAV_VTOL_STATE_UNDEFINED">
...@@ -6511,6 +6568,20 @@ ...@@ -6511,6 +6568,20 @@
<field type="uint16_t" default="0" name="cell_offset">The cell number of the first index in the 'voltages' array field. Using this field allows you to specify cell voltages for batteries with more than 16 cells.</field> <field type="uint16_t" default="0" name="cell_offset">The cell number of the first index in the 'voltages' array field. Using this field allows you to specify cell voltages for batteries with more than 16 cells.</field>
<field type="uint16_t[16]" name="voltages" units="mV">Individual cell voltages. Batteries with more 16 cells can use the cell_offset field to specify the cell offset for the array specified in the current message . Index values above the valid cell count for this battery should have the UINT16_MAX value.</field> <field type="uint16_t[16]" name="voltages" units="mV">Individual cell voltages. Batteries with more 16 cells can use the cell_offset field to specify the cell offset for the array specified in the current message . Index values above the valid cell count for this battery should have the UINT16_MAX value.</field>
</message> </message>
<message id="373" name="GENERATOR_STATUS">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Telemetry of power generation system. Alternator or mechanical generator.</description>
<field type="uint64_t" name="status" display="bitmask" enum="GENERATOR_STATUS_FLAG">Status flags.</field>
<field type="uint16_t" name="generator_speed" units="rpm">Speed of electrical generator or alternator. UINT16_MAX: field not provided.</field>
<field type="float" name="battery_current" units="A">Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.</field>
<field type="float" name="load_current" units="A">Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided</field>
<field type="float" name="power_generated" units="W">The power being generated. NaN: field not provided</field>
<field type="float" name="bus_voltage" units="V">Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.</field>
<field type="int16_t" name="rectifier_temperature" units="degC">The temperature of the rectifier or power converter. INT16_MAX: field not provided.</field>
<field type="float" name="bat_current_setpoint" units="A">The target battery current. Positive for out. Negative for in. NaN: field not provided</field>
<field type="int16_t" name="generator_temperature" units="degC">The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.</field>
</message>
<message id="375" name="ACTUATOR_OUTPUT_STATUS"> <message id="375" name="ACTUATOR_OUTPUT_STATUS">
<description>The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW.</description> <description>The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW.</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (since system boot).</field> <field type="uint64_t" name="time_usec" units="us">Timestamp (since system boot).</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